Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(test_utils): return parser as optional #9391

Merged
merged 6 commits into from
Dec 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@

#include <array>
#include <memory>
#include <optional>
#include <string>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -197,10 +198,10 @@ template <typename T>
T parse(const std::string & filename);

template <>
LaneletRoute parse(const std::string & filename);
std::optional<LaneletRoute> parse(const std::string & filename);

template <>
PathWithLaneId parse(const std::string & filename);
std::optional<PathWithLaneId> parse(const std::string & filename);

template <typename MessageType>
auto create_const_shared_ptr(MessageType && payload)
Expand Down
7 changes: 6 additions & 1 deletion common/autoware_test_utils/src/autoware_test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,12 @@ PathWithLaneId loadPathWithLaneIdInYaml()
const auto yaml_path =
get_absolute_path_to_config("autoware_test_utils", "path_with_lane_id_data.yaml");

return parse<PathWithLaneId>(yaml_path);
if (const auto path = parse<std::optional<PathWithLaneId>>(yaml_path)) {
return *path;
}

throw std::runtime_error(
"Failed to parse YAML file: " + yaml_path + ". The file might be corrupted.");
}

lanelet::ConstLanelet make_lanelet(
Expand Down
45 changes: 18 additions & 27 deletions common/autoware_test_utils/src/mock_data_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <rclcpp/logging.hpp>

#include <algorithm>
#include <optional>
#include <string>
#include <vector>

Expand Down Expand Up @@ -220,11 +221,7 @@
{
std::vector<PathPointWithLaneId> path_points;

if (!node["points"]) {
return path_points;
}

const auto & points = node["points"];
const auto & points = node;
path_points.reserve(points.size());
std::transform(
points.begin(), points.end(), std::back_inserter(path_points), [&](const YAML::Node & input) {
Expand Down Expand Up @@ -428,36 +425,30 @@
}

template <>
LaneletRoute parse(const std::string & filename)
std::optional<LaneletRoute> parse(const std::string & filename)
{
LaneletRoute lanelet_route;
try {
YAML::Node config = YAML::LoadFile(filename);

lanelet_route.start_pose = (config["start_pose"]) ? parse<Pose>(config["start_pose"]) : Pose();
lanelet_route.goal_pose = (config["goal_pose"]) ? parse<Pose>(config["goal_pose"]) : Pose();
lanelet_route.segments = parse<std::vector<LaneletSegment>>(config["segments"]);
} catch (const std::exception & e) {
RCLCPP_DEBUG(rclcpp::get_logger("autoware_test_utils"), "Exception caught: %s", e.what());
YAML::Node node = YAML::LoadFile(filename);
if (!node["start_pose"] || !node["goal_pose"] || !node["segments"]) {

Check warning on line 431 in common/autoware_test_utils/src/mock_data_parser.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

parse has 1 complex conditionals with 2 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
return std::nullopt;

Check warning on line 432 in common/autoware_test_utils/src/mock_data_parser.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_test_utils/src/mock_data_parser.cpp#L432

Added line #L432 was not covered by tests
}
return lanelet_route;

return parse<LaneletRoute>(node);
}

template <>
PathWithLaneId parse(const std::string & filename)
std::optional<PathWithLaneId> parse(const std::string & filename)
{
PathWithLaneId path;
YAML::Node yaml_node = YAML::LoadFile(filename);

try {
path.header = parse<Header>(yaml_node["header"]);
path.points = parse<std::vector<PathPointWithLaneId>>(yaml_node);
path.left_bound = parse<std::vector<Point>>(yaml_node["left_bound"]);
path.right_bound = parse<std::vector<Point>>(yaml_node["right_bound"]);
} catch (const std::exception & e) {
RCLCPP_DEBUG(rclcpp::get_logger("autoware_test_utils"), "Exception caught: %s", e.what());
YAML::Node node = YAML::LoadFile(filename);

if (!node["header"] || !node["points"] || !node["left_bound"] || !node["right_bound"]) {

Check warning on line 443 in common/autoware_test_utils/src/mock_data_parser.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

parse has 1 complex conditionals with 3 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
return std::nullopt;

Check warning on line 444 in common/autoware_test_utils/src/mock_data_parser.cpp

View check run for this annotation

Codecov / codecov/patch

common/autoware_test_utils/src/mock_data_parser.cpp#L444

Added line #L444 was not covered by tests
}

PathWithLaneId path;
path.header = parse<Header>(node["header"]);
path.points = parse<std::vector<PathPointWithLaneId>>(node["points"]);
path.left_bound = parse<std::vector<Point>>(node["left_bound"]);
path.right_bound = parse<std::vector<Point>>(node["right_bound"]);
return path;
}
} // namespace autoware::test_utils
140 changes: 75 additions & 65 deletions common/autoware_test_utils/test/test_mock_data_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -788,38 +788,44 @@ TEST(ParseFunction, CompleteFromFilename)
const auto parser_test_route =
autoware_test_utils_dir + "/test_data/lanelet_route_parser_test.yaml";

const auto lanelet_route = parse<LaneletRoute>(parser_test_route);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.y, 2.0);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.z, 3.0);
if (const auto lanelet_route_opt = parse<std::optional<LaneletRoute>>(parser_test_route)) {
const auto & lanelet_route = *lanelet_route_opt;
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.y, 2.0);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.z, 3.0);

EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.x, 0.1);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.y, 0.2);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.z, 0.3);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.w, 0.4);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.x, 0.1);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.y, 0.2);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.z, 0.3);
EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.w, 0.4);

EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.x, 4.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.y, 5.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.z, 6.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.x, 0.5);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.y, 0.6);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.z, 0.7);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.w, 0.8);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.x, 4.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.y, 5.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.z, 6.0);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.x, 0.5);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.y, 0.6);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.z, 0.7);
EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.w, 0.8);

ASSERT_EQ(
lanelet_route.segments.size(),
uint64_t(2)); // Assuming only one segment in the provided YAML for this test
const auto & segment1 = lanelet_route.segments[1];
EXPECT_EQ(segment1.preferred_primitive.id, 44);
EXPECT_EQ(segment1.primitives.size(), uint64_t(4));
EXPECT_EQ(segment1.primitives[0].id, 55);
EXPECT_EQ(segment1.primitives[0].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[1].id, 66);
EXPECT_EQ(segment1.primitives[1].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[2].id, 77);
EXPECT_EQ(segment1.primitives[2].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[3].id, 88);
EXPECT_EQ(segment1.primitives[3].primitive_type, "lane");
ASSERT_EQ(
lanelet_route.segments.size(),
uint64_t(2)); // Assuming only one segment in the provided YAML for this test
const auto & segment1 = lanelet_route.segments[1];
EXPECT_EQ(segment1.preferred_primitive.id, 44);
EXPECT_EQ(segment1.primitives.size(), uint64_t(4));
EXPECT_EQ(segment1.primitives[0].id, 55);
EXPECT_EQ(segment1.primitives[0].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[1].id, 66);
EXPECT_EQ(segment1.primitives[1].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[2].id, 77);
EXPECT_EQ(segment1.primitives[2].primitive_type, "lane");
EXPECT_EQ(segment1.primitives[3].id, 88);
EXPECT_EQ(segment1.primitives[3].primitive_type, "lane");
} else {
const std::string fail_reason =
"Failed to parse YAML file: " + parser_test_route + ". The file might be corrupted.";
FAIL() << fail_reason;
}
}

TEST(ParseFunction, ParsePathWithLaneID)
Expand All @@ -829,45 +835,49 @@ TEST(ParseFunction, ParsePathWithLaneID)
const auto parser_test_path =
autoware_test_utils_dir + "/test_data/path_with_lane_id_parser_test.yaml";

const auto path = parse<PathWithLaneId>(parser_test_path);
EXPECT_EQ(path.header.stamp.sec, 20);
EXPECT_EQ(path.header.stamp.nanosec, 5);
if (const auto path_opt = parse<std::optional<PathWithLaneId>>(parser_test_path)) {
const auto & path = *path_opt;
EXPECT_EQ(path.header.stamp.sec, 20);
EXPECT_EQ(path.header.stamp.nanosec, 5);

const auto path_points = path.points;
const auto & p1 = path_points.front();
EXPECT_DOUBLE_EQ(p1.point.pose.position.x, 12.9);
EXPECT_DOUBLE_EQ(p1.point.pose.position.y, 3.8);
EXPECT_DOUBLE_EQ(p1.point.pose.position.z, 4.7);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.x, 1.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.y, 2.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.z, 3.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.w, 4.0);
EXPECT_FLOAT_EQ(p1.point.longitudinal_velocity_mps, 1.2);
EXPECT_FLOAT_EQ(p1.point.lateral_velocity_mps, 3.4);
EXPECT_FLOAT_EQ(p1.point.heading_rate_rps, 5.6);
EXPECT_TRUE(p1.point.is_final);
EXPECT_EQ(p1.lane_ids.front(), 912);
const auto path_points = path.points;
const auto & p1 = path_points.front();
EXPECT_DOUBLE_EQ(p1.point.pose.position.x, 12.9);
EXPECT_DOUBLE_EQ(p1.point.pose.position.y, 3.8);
EXPECT_DOUBLE_EQ(p1.point.pose.position.z, 4.7);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.x, 1.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.y, 2.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.z, 3.0);
EXPECT_DOUBLE_EQ(p1.point.pose.orientation.w, 4.0);
EXPECT_FLOAT_EQ(p1.point.longitudinal_velocity_mps, 1.2);
EXPECT_FLOAT_EQ(p1.point.lateral_velocity_mps, 3.4);
EXPECT_FLOAT_EQ(p1.point.heading_rate_rps, 5.6);
EXPECT_TRUE(p1.point.is_final);
EXPECT_EQ(p1.lane_ids.front(), 912);

const auto & p2 = path_points.back();
EXPECT_DOUBLE_EQ(p2.point.pose.position.x, 0.0);
EXPECT_DOUBLE_EQ(p2.point.pose.position.y, 20.5);
EXPECT_DOUBLE_EQ(p2.point.pose.position.z, 90.11);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.x, 4.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.y, 3.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.z, 2.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.w, 1.0);
EXPECT_FLOAT_EQ(p2.point.longitudinal_velocity_mps, 2.1);
EXPECT_FLOAT_EQ(p2.point.lateral_velocity_mps, 4.3);
EXPECT_FLOAT_EQ(p2.point.heading_rate_rps, 6.5);
EXPECT_FALSE(p2.point.is_final);
EXPECT_EQ(p2.lane_ids.front(), 205);
const auto & p2 = path_points.back();
EXPECT_DOUBLE_EQ(p2.point.pose.position.x, 0.0);
EXPECT_DOUBLE_EQ(p2.point.pose.position.y, 20.5);
EXPECT_DOUBLE_EQ(p2.point.pose.position.z, 90.11);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.x, 4.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.y, 3.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.z, 2.0);
EXPECT_DOUBLE_EQ(p2.point.pose.orientation.w, 1.0);
EXPECT_FLOAT_EQ(p2.point.longitudinal_velocity_mps, 2.1);
EXPECT_FLOAT_EQ(p2.point.lateral_velocity_mps, 4.3);
EXPECT_FLOAT_EQ(p2.point.heading_rate_rps, 6.5);
EXPECT_FALSE(p2.point.is_final);
EXPECT_EQ(p2.lane_ids.front(), 205);

EXPECT_DOUBLE_EQ(path.left_bound.front().x, 55.0);
EXPECT_DOUBLE_EQ(path.left_bound.front().y, 66.0);
EXPECT_DOUBLE_EQ(path.left_bound.front().z, 77.0);
EXPECT_DOUBLE_EQ(path.left_bound.front().x, 55.0);
EXPECT_DOUBLE_EQ(path.left_bound.front().y, 66.0);
EXPECT_DOUBLE_EQ(path.left_bound.front().z, 77.0);

EXPECT_DOUBLE_EQ(path.right_bound.front().x, 0.55);
EXPECT_DOUBLE_EQ(path.right_bound.front().y, 0.66);
EXPECT_DOUBLE_EQ(path.right_bound.front().z, 0.77);
EXPECT_DOUBLE_EQ(path.right_bound.front().x, 0.55);
EXPECT_DOUBLE_EQ(path.right_bound.front().y, 0.66);
EXPECT_DOUBLE_EQ(path.right_bound.front().z, 0.77);
} else {
FAIL() << "Yaml file might've corrupted.";
}
}
} // namespace autoware::test_utils
Original file line number Diff line number Diff line change
Expand Up @@ -279,9 +279,13 @@
void PlanningInterfaceTestManager::publishNominalPathWithLaneId(
rclcpp::Node::SharedPtr target_node, std::string topic_name)
{
autoware::test_utils::publishToTargetNode(
test_node_, target_node, topic_name, normal_path_with_lane_id_pub_,
autoware::test_utils::loadPathWithLaneIdInYaml(), 5);
try {
const auto path = autoware::test_utils::loadPathWithLaneIdInYaml();
autoware::test_utils::publishToTargetNode(
test_node_, target_node, topic_name, normal_path_with_lane_id_pub_, path, 5);
} catch (const std::exception & e) {
std::cerr << e.what() << '\n';
}

Check warning on line 288 in planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp#L288

Added line #L288 was not covered by tests
}

void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId(
Expand All @@ -294,11 +298,14 @@
void PlanningInterfaceTestManager::publishNominalPath(
rclcpp::Node::SharedPtr target_node, std::string topic_name)
{
autoware::test_utils::publishToTargetNode(
test_node_, target_node, topic_name, normal_path_pub_,
autoware::motion_utils::convertToPath<tier4_planning_msgs::msg::PathWithLaneId>(
autoware::test_utils::loadPathWithLaneIdInYaml()),
5);
try {
const auto path = autoware::test_utils::loadPathWithLaneIdInYaml();
autoware::test_utils::publishToTargetNode(
test_node_, target_node, topic_name, normal_path_pub_,
autoware::motion_utils::convertToPath<tier4_planning_msgs::msg::PathWithLaneId>(path), 5);
} catch (const std::exception & e) {
std::cerr << e.what() << '\n';
}

Check warning on line 308 in planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp#L308

Added line #L308 was not covered by tests
}

void PlanningInterfaceTestManager::publishAbnormalPath(
Expand Down
15 changes: 13 additions & 2 deletions planning/autoware_route_handler/test/test_route_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,11 @@ class TestRouteHandler : public ::testing::Test
TestRouteHandler()
{
set_route_handler("2km_test.osm");
set_test_route(lane_change_right_test_route_filename);
try {
set_test_route(lane_change_right_test_route_filename);
} catch (const std::exception & e) {
std::cerr << e.what() << '\n';
}
}

TestRouteHandler(const TestRouteHandler &) = delete;
Expand All @@ -68,7 +72,14 @@ class TestRouteHandler : public ::testing::Test
{
const auto rh_test_route =
get_absolute_path_to_route(autoware_route_handler_dir, route_filename);
route_handler_->setRoute(autoware::test_utils::parse<LaneletRoute>(rh_test_route));
if (
const auto route_opt =
autoware::test_utils::parse<std::optional<LaneletRoute>>(rh_test_route)) {
route_handler_->setRoute(*route_opt);
} else {
throw std::runtime_error(
"Failed to parse YAML file: " + rh_test_route + ". The file might be corrupted.");
}
}

lanelet::ConstLanelets get_current_lanes()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,11 @@ class TestNormalLaneChange : public ::testing::Test
auto route_handler_ptr = std::make_shared<RouteHandler>(map_bin_msg);
const auto rh_test_route =
get_absolute_path_to_route(autoware_route_handler_dir, lane_change_right_test_route_filename);
route_handler_ptr->setRoute(autoware::test_utils::parse<LaneletRoute>(rh_test_route));
if (
const auto route_opt =
autoware::test_utils::parse<std::optional<LaneletRoute>>(rh_test_route)) {
route_handler_ptr->setRoute(*route_opt);
}

return route_handler_ptr;
}
Expand Down
Loading