diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index c1ad5015ca1df..eb1e9e6acede8 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -100,7 +100,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - test_manager->testWithAbnormalRoute(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalRoute(test_target_node)); rclcpp::shutdown(); } diff --git a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp index 94347f3974aff..e25794d85722e 100644 --- a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -28,18 +28,14 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu auto test_manager = std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto freespace_planner_dir = ament_index_cpp::get_package_share_directory("freespace_planner"); - node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", freespace_planner_dir + "/config/freespace_planner.param.yaml"}); - auto test_target_node = std::make_shared(node_options); // publish necessary topics from test_manager @@ -59,5 +55,5 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - test_manager->testWithAbnormalRoute(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalRoute(test_target_node)); } diff --git a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp index 4b97b618b0084..d9577a5c62814 100644 --- a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp +++ b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -28,16 +28,12 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu auto test_manager = std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - node_options.append_parameter_override("algorithm_type", "JerkFiltered"); node_options.append_parameter_override("publish_debug_trajs", false); - - const auto motion_velocity_smoother_dir = - ament_index_cpp::get_package_share_directory("motion_velocity_smoother"); - const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - + const auto motion_velocity_smoother_dir = + ament_index_cpp::get_package_share_directory("motion_velocity_smoother"); node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", @@ -66,5 +62,5 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); } diff --git a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index 266a8553295c5..5e35c710f7b1f 100644 --- a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -28,20 +28,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) auto test_manager = std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - const auto obstacle_cruise_planner_dir = ament_index_cpp::get_package_share_directory("obstacle_cruise_planner"); - const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_common.param.yaml", "--params-file", planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", obstacle_cruise_planner_dir + "/config/default_common.param.yaml", "--params-file", obstacle_cruise_planner_dir + "/config/obstacle_cruise_planner.param.yaml"}); - auto test_target_node = std::make_shared(node_options); @@ -58,9 +54,8 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) // test for normal trajectory ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); - EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); } diff --git a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp index 288ae1a61ff14..dc646e35d09a6 100644 --- a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp +++ b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp index bba4b99101576..e91e229ede9fd 100644 --- a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp +++ b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -45,7 +45,8 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) // publish necessary topics from test_manager test_manager->publishOdometry(test_target_node, "obstacle_velocity_limiter/input/odometry"); - test_manager->publishPointCloud(test_target_node, "obstacle_velocity_limiter/input/pointcloud"); + test_manager->publishPointCloud( + test_target_node, "obstacle_velocity_limiter/input/obstacle_pointcloud"); test_manager->publishOccupancyGrid( test_target_node, "obstacle_velocity_limiter/input/occupancy_grid"); test_manager->publishPredictedObjects( @@ -64,5 +65,5 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); } diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp index 14b16b4fcbc87..0c77498cb9f5c 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -90,11 +90,10 @@ class PlanningInterfaceTestManager public: PlanningInterfaceTestManager(); - void publishOdometry(rclcpp::Node::SharedPtr target_node); void publishOdometry(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishInitialPose(rclcpp::Node::SharedPtr target_node); - void publishInitialPose(rclcpp::Node::SharedPtr target_node, std::string topic_name); + void publishInitialPose( + rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift = 0.0); void publishMaxVelocity(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishPointCloud(rclcpp::Node::SharedPtr target_node, std::string topic_name); @@ -119,8 +118,6 @@ class PlanningInterfaceTestManager void publishExternalCrosswalkStates(rclcpp::Node::SharedPtr target_node, std::string topic_name); void publishExternalIntersectionStates( rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishInitialPoseData( - rclcpp::Node::SharedPtr target_node, std::string topic_name, double shift = 0.0); void setTrajectoryInputTopicName(std::string topic_name); void setParkingTrajectoryInputTopicName(std::string topic_name); diff --git a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp index 0015645a52c42..2f690b329e846 100644 --- a/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp +++ b/planning/planning_test_utils/include/planning_interface_test_manager/planning_interface_test_manager_utils.hpp @@ -118,17 +118,6 @@ T generateTrajectory( return traj; } -Route::Message makeNormalRoute() -{ - const std::array start_pose{5.5, 4., 0., M_PI_2}; - const std::array goal_pose{8.0, 26.3, 0, 0}; - Route::Message route; - route.header.frame_id = "map"; - route.start_pose = createPose(start_pose); - route.goal_pose = createPose(goal_pose); - return route; -} - LaneletSegment createLaneletSegment(int id) { LaneletPrimitive primitive; @@ -140,6 +129,49 @@ LaneletSegment createLaneletSegment(int id) return segment; } +lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) +{ + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); + if (errors.empty()) { + return map; + } + + for (const auto & error : errors) { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); + } + return nullptr; +} + +HADMapBin convertToMapBinMsg( + const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) +{ + std::string format_version{}, map_version{}; + lanelet::io_handlers::AutowareOsmParser::parseVersions( + lanelet2_filename, &format_version, &map_version); + + HADMapBin map_bin_msg; + map_bin_msg.header.stamp = now; + map_bin_msg.header.frame_id = "map"; + map_bin_msg.format_version = format_version; + map_bin_msg.map_version = map_version; + lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); + + return map_bin_msg; +} + +Route::Message makeNormalRoute() +{ + const std::array start_pose{5.5, 4., 0., M_PI_2}; + const std::array goal_pose{8.0, 26.3, 0, 0}; + Route::Message route; + route.header.frame_id = "map"; + route.start_pose = createPose(start_pose); + route.goal_pose = createPose(goal_pose); + return route; +} + // this is for the test lanelet2_map.osm // file hash: a9f84cff03b55a64917bc066451276d2293b0a54f5c088febca0c7fdf2f245d5 Route::Message makeBehaviorNormalRoute() @@ -164,11 +196,12 @@ Route::Message makeBehaviorNormalRoute() return route; } -OccupancyGrid constructCostMap(size_t width, size_t height, double resolution) +OccupancyGrid makeCostMapMsg(size_t width = 150, size_t height = 150, double resolution = 0.2) { - nav_msgs::msg::OccupancyGrid costmap_msg{}; + nav_msgs::msg::OccupancyGrid costmap_msg; // create info + costmap_msg.header.frame_id = "map"; costmap_msg.info.width = width; costmap_msg.info.height = height; costmap_msg.info.resolution = resolution; @@ -181,48 +214,78 @@ OccupancyGrid constructCostMap(size_t width, size_t height, double resolution) return costmap_msg; } -void spinSomeNodes( - rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, - const int repeat_count = 1) +HADMapBin makeMapBinMsg() { - for (int i = 0; i < repeat_count; i++) { - rclcpp::spin_some(test_node); - rclcpp::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(target_node); - rclcpp::sleep_for(std::chrono::milliseconds(100)); + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto lanelet2_path = planning_test_utils_dir + "/test_map/lanelet2_map.osm"; + double center_line_resolution = 5.0; + // load map from file + const auto map = loadMap(lanelet2_path); + if (!map) { + return autoware_auto_mapping_msgs::msg::HADMapBin_>{}; } + + // overwrite centerline + lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false); + + // create map bin msg + const auto map_bin_msg = + convertToMapBinMsg(map, lanelet2_path, rclcpp::Clock(RCL_ROS_TIME).now()); + return map_bin_msg; } -lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) +Odometry makeOdometry() { - lanelet::ErrorMessages errors{}; - lanelet::projection::MGRSProjector projector{}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); - if (errors.empty()) { - return map; - } - - for (const auto & error : errors) { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); - } - return nullptr; + Odometry odometry; + const std::array start_pose{5.5, 4., M_PI_2}; + odometry.pose.pose = createPose(start_pose); + odometry.header.frame_id = "map"; + return odometry; } -HADMapBin createMapBinMsg( - const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) +Odometry makeInitialPose(const double shift = 0.0) { - std::string format_version{}, map_version{}; - lanelet::io_handlers::AutowareOsmParser::parseVersions( - lanelet2_filename, &format_version, &map_version); + Odometry current_odometry; + const auto yaw = 0.9724497591854532; + const auto shift_x = shift * std::sin(yaw); + const auto shift_y = shift * std::cos(yaw); + const std::array start_pose{ + 3722.16015625 + shift_x, 73723.515625 + shift_y, 0.233112560494183, yaw}; + current_odometry.pose.pose = test_utils::createPose(start_pose); + current_odometry.header.frame_id = "map"; + return current_odometry; +} - HADMapBin map_bin_msg; - map_bin_msg.header.stamp = now; - map_bin_msg.header.frame_id = "map"; - map_bin_msg.format_version = format_version; - map_bin_msg.map_version = map_version; - lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); +TFMessage makeTFMsg( + rclcpp::Node::SharedPtr target_node, std::string frame_id = "", std::string child_frame_id = "") +{ + TFMessage tf_msg; + geometry_msgs::msg::Quaternion quaternion; + quaternion.x = 0.; + quaternion.y = 0.; + quaternion.z = 0.23311256049418302; + quaternion.w = 0.9724497591854532; + + TransformStamped tf; + tf.header.stamp = target_node->get_clock()->now(); + tf.header.frame_id = frame_id; + tf.child_frame_id = child_frame_id; + tf.transform.translation.x = 3722.16015625; + tf.transform.translation.y = 73723.515625; + tf.transform.translation.z = 0; + tf.transform.rotation = quaternion; + + tf_msg.transforms.emplace_back(std::move(tf)); + return tf_msg; +} - return map_bin_msg; +Scenario makeScenarioMsg(const std::string scenario) +{ + Scenario scenario_msg; + scenario_msg.current_scenario = scenario; + scenario_msg.activating_scenarios = {scenario}; + return scenario_msg; } template @@ -253,84 +316,6 @@ void setPublisher( createPublisherWithQoS(test_node, topic_name, publisher); } -template -T generateObject(rclcpp::Node::SharedPtr target_node) -{ - if constexpr (std::is_same_v) { - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto lanelet2_path = planning_test_utils_dir + "/test_map/lanelet2_map.osm"; - double center_line_resolution = 5.0; - // load map from file - const auto map = loadMap(lanelet2_path); - if (!map) { - return autoware_auto_mapping_msgs::msg::HADMapBin_>{}; - } - - // overwrite centerline - lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false); - - // create map bin msg - const auto map_bin_msg = createMapBinMsg(map, lanelet2_path, rclcpp::Clock(RCL_ROS_TIME).now()); - return map_bin_msg; - } else if constexpr (std::is_same_v) { - std::shared_ptr trajectory = std::make_shared(); - trajectory->header.stamp = target_node->now(); - return *trajectory; - } else if constexpr (std::is_same_v) { - std::shared_ptr current_odometry = std::make_shared(); - const std::array start_pose{5.5, 4., M_PI_2}; - current_odometry->pose.pose = createPose(start_pose); - current_odometry->header.frame_id = "map"; - return *current_odometry; - } else if constexpr (std::is_same_v) { - auto costmap_msg = constructCostMap(150, 150, 0.2); - costmap_msg.header.frame_id = "map"; - return costmap_msg; - } else if constexpr (std::is_same_v) { - return makeNormalRoute(); - } else if constexpr (std::is_same_v) { - TransformStamped tf; - tf.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); - tf.header.frame_id = "base_link"; - tf.child_frame_id = "map"; - - TFMessage tf_msg{}; - tf_msg.transforms.emplace_back(std::move(tf)); - return tf_msg; - } else if constexpr (std::is_same_v) { - PointCloud2 point_cloud_msg{}; - point_cloud_msg.header.frame_id = "base_link"; - return point_cloud_msg; - } else { - return T{}; - } -} - -template -void publishData( - rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, - typename rclcpp::Publisher::SharedPtr publisher) -{ - setPublisher(test_node, topic_name, publisher); - T object = generateObject(target_node); - publisher->publish(object); - spinSomeNodes(test_node, target_node); -} - -void publishScenarioData( - rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, - rclcpp::Publisher::SharedPtr publisher, const std::string scenario) -{ - auto scenario_msg = std::make_shared(); - scenario_msg->current_scenario = scenario; - scenario_msg->activating_scenarios = {scenario}; - setPublisher(test_node, topic_name, publisher); - publisher->publish(*scenario_msg); - - spinSomeNodes(test_node, target_node); -} - template void createSubscription( rclcpp::Node::SharedPtr test_node, std::string topic_name, @@ -353,6 +338,35 @@ void setSubscriber( test_node, topic_name, [&count](const typename T::ConstSharedPtr) { count++; }, subscriber); } +void spinSomeNodes( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, + const int repeat_count = 1) +{ + for (int i = 0; i < repeat_count; i++) { + rclcpp::spin_some(test_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + rclcpp::spin_some(target_node); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } +} + +template +void publishToTargetNode( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, + typename rclcpp::Publisher::SharedPtr publisher, T data, const int repeat_count = 1) +{ + test_utils::setPublisher(test_node, topic_name, publisher); + publisher->publish(data); + if (topic_name.empty()) { + throw std::runtime_error( + std::string("Topic name for ") + typeid(*publisher).name() + " is empty"); + } + if (target_node->count_subscribers(topic_name) == 0) { + throw std::runtime_error("No subscriber for " + topic_name); + } + test_utils::spinSomeNodes(test_node, target_node, repeat_count); +} + void updateNodeOptions( rclcpp::NodeOptions & node_options, const std::vector & params_files) { diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml index 545ed510c4df0..ec025b57eea6c 100644 --- a/planning/planning_test_utils/package.xml +++ b/planning/planning_test_utils/package.xml @@ -35,7 +35,6 @@ unique_identifier_msgs yaml_cpp_vendor - ament_cmake_gtest ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/planning_test_utils/src/planning_interface_test_manager.cpp b/planning/planning_test_utils/src/planning_interface_test_manager.cpp index d25ebcb444299..db3942d58387d 100644 --- a/planning/planning_test_utils/src/planning_interface_test_manager.cpp +++ b/planning/planning_test_utils/src/planning_interface_test_manager.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -28,200 +28,173 @@ PlanningInterfaceTestManager::PlanningInterfaceTestManager() void PlanningInterfaceTestManager::publishOdometry( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, odom_pub_); -} - -void PlanningInterfaceTestManager::publishOdometry(rclcpp::Node::SharedPtr target_node) -{ - publishOdometry(target_node, input_odometry_name_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, odom_pub_, test_utils::makeOdometry()); } void PlanningInterfaceTestManager::publishMaxVelocity( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, max_velocity_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, max_velocity_pub_, VelocityLimit{}); } void PlanningInterfaceTestManager::publishPointCloud( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, point_cloud_pub_); + PointCloud2 point_cloud_msg{}; + point_cloud_msg.header.frame_id = "base_link"; + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, point_cloud_pub_, point_cloud_msg); } void PlanningInterfaceTestManager::publishAcceleration( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, acceleration_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, acceleration_pub_, AccelWithCovarianceStamped{}); } void PlanningInterfaceTestManager::publishPredictedObjects( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, predicted_objects_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, predicted_objects_pub_, PredictedObjects{}); } void PlanningInterfaceTestManager::publishExpandStopRange( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, expand_stop_range_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, expand_stop_range_pub_, ExpandStopRange{}); } void PlanningInterfaceTestManager::publishOccupancyGrid( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, occupancy_grid_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, occupancy_grid_pub_, test_utils::makeCostMapMsg()); } void PlanningInterfaceTestManager::publishCostMap( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, cost_map_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, cost_map_pub_, test_utils::makeCostMapMsg()); } void PlanningInterfaceTestManager::publishMap( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, map_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, map_pub_, test_utils::makeMapBinMsg()); } void PlanningInterfaceTestManager::publishLaneDrivingScenario( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishScenarioData( - test_node_, target_node, topic_name, lane_driving_scenario_pub_, Scenario::LANEDRIVING); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, lane_driving_scenario_pub_, + test_utils::makeScenarioMsg(Scenario::LANEDRIVING)); } void PlanningInterfaceTestManager::publishParkingScenario( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishScenarioData( - test_node_, target_node, topic_name, parking_scenario_pub_, Scenario::PARKING); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, parking_scenario_pub_, + test_utils::makeScenarioMsg(Scenario::PARKING)); } void PlanningInterfaceTestManager::publishInitialPose( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - publishInitialPoseData(target_node, topic_name); -} - -void PlanningInterfaceTestManager::publishInitialPose(rclcpp::Node::SharedPtr target_node) + rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift) { - publishInitialPose(target_node, input_initial_pose_name_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, initial_pose_pub_, test_utils::makeInitialPose(shift)); } void PlanningInterfaceTestManager::publishParkingState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, parking_state_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, parking_state_pub_, std_msgs::msg::Bool{}); } void PlanningInterfaceTestManager::publishTrajectory( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, trajectory_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, trajectory_pub_, Trajectory{}); } void PlanningInterfaceTestManager::publishRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, route_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, route_pub_, test_utils::makeNormalRoute()); } void PlanningInterfaceTestManager::publishTF( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, TF_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, TF_pub_, + test_utils::makeTFMsg(target_node, "base_link", "map")); } void PlanningInterfaceTestManager::publishLateralOffset( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData(test_node_, target_node, topic_name, lateral_offset_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, lateral_offset_pub_, LateralOffset{}); } void PlanningInterfaceTestManager::publishOperationModeState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, operation_mode_state_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, operation_mode_state_pub_, OperationModeState{}); } void PlanningInterfaceTestManager::publishTrafficSignals( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, traffic_signals_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, traffic_signals_pub_, TrafficSignalArray{}); } + void PlanningInterfaceTestManager::publishExternalTrafficSignals( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, external_traffic_signals_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, external_traffic_signals_pub_, TrafficSignalArray{}); } void PlanningInterfaceTestManager::publishVirtualTrafficLightState( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, virtual_traffic_light_states_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, virtual_traffic_light_states_pub_, + VirtualTrafficLightStateArray{}); } void PlanningInterfaceTestManager::publishExternalCrosswalkStates( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, external_crosswalk_states_pub_); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, external_crosswalk_states_pub_, CrosswalkStatus{}); } void PlanningInterfaceTestManager::publishExternalIntersectionStates( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::publishData( - test_node_, target_node, topic_name, external_intersection_states_pub_); -} - -void PlanningInterfaceTestManager::publishInitialPoseData( - rclcpp::Node::SharedPtr target_node, std::string topic_name, double shift) -{ - std::shared_ptr current_odometry = std::make_shared(); - const auto yaw = 0.9724497591854532; - const auto shift_x = shift * std::sin(yaw); - const auto shift_y = shift * std::cos(yaw); - const std::array start_pose{ - 3722.16015625 + shift_x, 73723.515625 + shift_y, 0.233112560494183, yaw}; - current_odometry->pose.pose = test_utils::createPose(start_pose); - current_odometry->header.frame_id = "map"; - - test_utils::setPublisher(test_node_, topic_name, initial_pose_pub_); - initial_pose_pub_->publish(*current_odometry); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, external_intersection_states_pub_, IntersectionStatus{}); } void PlanningInterfaceTestManager::publishInitialPoseTF( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - geometry_msgs::msg::Quaternion quaternion; - quaternion.x = 0.; - quaternion.y = 0.; - quaternion.z = 0.23311256049418302; - quaternion.w = 0.9724497591854532; - - TransformStamped tf; - tf.header.stamp = target_node->get_clock()->now(); - tf.header.frame_id = "odom"; - tf.child_frame_id = "base_link"; - tf.transform.translation.x = 3722.16015625; - tf.transform.translation.y = 73723.515625; - tf.transform.translation.z = 0; - tf.transform.rotation = quaternion; - - tf2_msgs::msg::TFMessage tf_msg{}; - tf_msg.transforms.emplace_back(std::move(tf)); - - test_utils::setPublisher(test_node_, topic_name, initial_pose_tf_pub_); - initial_pose_tf_pub_->publish(tf_msg); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, initial_pose_tf_pub_, + test_utils::makeTFMsg(target_node, "odom", "base_link")); } void PlanningInterfaceTestManager::setTrajectoryInputTopicName(std::string topic_name) @@ -262,58 +235,53 @@ void PlanningInterfaceTestManager::setOdometryTopicName(std::string topic_name) void PlanningInterfaceTestManager::publishNominalTrajectory( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::setPublisher(test_node_, topic_name, normal_trajectory_pub_); - normal_trajectory_pub_->publish(test_utils::generateTrajectory(10, 1.0)); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_trajectory_pub_, + test_utils::generateTrajectory(10, 1.0), 5); } void PlanningInterfaceTestManager::publishAbnormalTrajectory( rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory) { - test_utils::setPublisher(test_node_, input_trajectory_name_, abnormal_trajectory_pub_); - abnormal_trajectory_pub_->publish(abnormal_trajectory); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, input_trajectory_name_, abnormal_trajectory_pub_, abnormal_trajectory); } void PlanningInterfaceTestManager::publishNominalRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::setPublisher(test_node_, topic_name, normal_route_pub_); - normal_route_pub_->publish(test_utils::makeNormalRoute()); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_route_pub_, test_utils::makeNormalRoute(), 5); } void PlanningInterfaceTestManager::publishBehaviorNominalRoute( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::setPublisher(test_node_, topic_name, behavior_normal_route_pub_); - behavior_normal_route_pub_->publish(test_utils::makeBehaviorNormalRoute()); - test_utils::spinSomeNodes(test_node_, target_node); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, behavior_normal_route_pub_, + test_utils::makeBehaviorNormalRoute(), 5); } void PlanningInterfaceTestManager::publishAbnormalRoute( rclcpp::Node::SharedPtr target_node, const LaneletRoute & abnormal_route) { - test_utils::setPublisher(test_node_, input_route_name_, abnormal_route_pub_); - abnormal_route_pub_->publish(abnormal_route); - test_utils::spinSomeNodes(test_node_, target_node, 5); + test_utils::publishToTargetNode( + test_node_, target_node, input_route_name_, abnormal_route_pub_, abnormal_route, 5); } void PlanningInterfaceTestManager::publishNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::setPublisher(test_node_, topic_name, normal_path_with_lane_id_pub_); - normal_path_with_lane_id_pub_->publish(test_utils::loadPathWithLaneIdInYaml()); - - test_utils::spinSomeNodes(test_node_, target_node, 5); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_path_with_lane_id_pub_, + test_utils::loadPathWithLaneIdInYaml(), 5); } void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - test_utils::setPublisher(test_node_, topic_name, abnormal_path_with_lane_id_pub_); - normal_path_with_lane_id_pub_->publish(PathWithLaneId{}); - test_utils::spinSomeNodes(test_node_, target_node, 5); + test_utils::publishToTargetNode( + test_node_, target_node, topic_name, abnormal_path_with_lane_id_pub_, PathWithLaneId{}, 5); } void PlanningInterfaceTestManager::setTrajectorySubscriber(std::string topic_name) @@ -344,38 +312,33 @@ void PlanningInterfaceTestManager::setPathSubscriber(std::string topic_name) void PlanningInterfaceTestManager::testWithNominalTrajectory(rclcpp::Node::SharedPtr target_node) { publishNominalTrajectory(target_node, input_trajectory_name_); - test_utils::spinSomeNodes(test_node_, target_node, 2); } // check to see if target node is dead. void PlanningInterfaceTestManager::testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node) { - ASSERT_NO_THROW(publishAbnormalTrajectory(target_node, Trajectory{})); - ASSERT_NO_THROW( - publishAbnormalTrajectory(target_node, test_utils::generateTrajectory(1, 0.0))); - ASSERT_NO_THROW(publishAbnormalTrajectory( - target_node, test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1))); + publishAbnormalTrajectory(target_node, Trajectory{}); + publishAbnormalTrajectory(target_node, test_utils::generateTrajectory(1, 0.0)); + publishAbnormalTrajectory( + target_node, test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1)); } // test for normal working void PlanningInterfaceTestManager::testWithNominalRoute(rclcpp::Node::SharedPtr target_node) { publishNominalRoute(target_node, input_route_name_); - test_utils::spinSomeNodes(test_node_, target_node, 5); } // test for normal working void PlanningInterfaceTestManager::testWithBehaviorNominalRoute(rclcpp::Node::SharedPtr target_node) { publishBehaviorNominalRoute(target_node, input_route_name_); - test_utils::spinSomeNodes(test_node_, target_node, 5); } // check to see if target node is dead. void PlanningInterfaceTestManager::testWithAbnormalRoute(rclcpp::Node::SharedPtr target_node) { - ASSERT_NO_THROW(publishAbnormalRoute(target_node, LaneletRoute{})); - test_utils::spinSomeNodes(test_node_, target_node, 5); + publishAbnormalRoute(target_node, LaneletRoute{}); } // test for normal working @@ -383,7 +346,6 @@ void PlanningInterfaceTestManager::testWithNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node) { publishNominalPathWithLaneId(target_node, input_path_with_lane_id_name_); - test_utils::spinSomeNodes(test_node_, target_node, 5); } // check to see if target node is dead. @@ -391,7 +353,6 @@ void PlanningInterfaceTestManager::testWithAbnormalPathWithLaneId( rclcpp::Node::SharedPtr target_node) { publishAbNominalPathWithLaneId(target_node, input_path_with_lane_id_name_); - test_utils::spinSomeNodes(test_node_, target_node, 5); } // put all abnormal ego pose related tests in this functions to run all tests with one line code @@ -422,18 +383,11 @@ void PlanningInterfaceTestManager::testTrajectoryWithInvalidEgoPose( void PlanningInterfaceTestManager::testOffTrackFromRoute(rclcpp::Node::SharedPtr target_node) { - if (input_route_name_.empty()) { - throw std::runtime_error("route topic name is not set"); - } - if (input_initial_pose_name_.empty()) { - throw std::runtime_error("initial topic pose name is not set"); - } - publishBehaviorNominalRoute(target_node, input_route_name_); const std::vector deviation_from_route = {0.0, 1.0, 10.0, 100.0}; for (const auto & deviation : deviation_from_route) { - publishInitialPoseData(target_node, input_initial_pose_name_, deviation); + publishInitialPose(target_node, input_initial_pose_name_, deviation); test_utils::spinSomeNodes(test_node_, target_node, 5); } } diff --git a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp index 33eeb7be97120..8a3e8d2abdb97 100644 --- a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Tier IV, Inc. +// Copyright 2023 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -26,18 +26,14 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) auto test_manager = std::make_shared(); auto node_options = rclcpp::NodeOptions{}; - const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto planning_validator_dir = ament_index_cpp::get_package_share_directory("planning_validator"); - node_options.arguments( {"--ros-args", "--params-file", planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", planning_validator_dir + "/config/planning_validator.param.yaml"}); - auto test_target_node = std::make_shared(node_options); // publish necessary topics from test_manager @@ -54,5 +50,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + + rclcpp::shutdown(); } diff --git a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp index c4949033c31a9..10c9d9863b7b7 100644 --- a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp +++ b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp @@ -22,12 +22,20 @@ #include #include -TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode) +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() { - rclcpp::init(0, nullptr); + auto test_manager = std::make_shared(); - auto test_manager = std::make_shared(); + // set subscriber with topic name: scenario_selector → test_node_ + test_manager->setScenarioSubscriber("output/scenario"); + return test_manager; +} + +std::shared_ptr generateNode() +{ auto node_options = rclcpp::NodeOptions{}; node_options.append_parameter_override("update_rate", 10.0); node_options.append_parameter_override("th_max_message_delay_sec", INFINITY); @@ -36,16 +44,28 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode node_options.append_parameter_override("th_stopped_velocity_mps", 0.01); auto test_target_node = std::make_shared(node_options); + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ // publish necessary topics from test_manager test_manager->publishOdometry(test_target_node, "input/odometry"); - test_manager->publishAcceleration(test_target_node, "input/acceleration"); test_manager->publishParkingState(test_target_node, "is_parking_completed"); test_manager->publishTrajectory(test_target_node, "input/parking/trajectory"); test_manager->publishMap(test_target_node, "input/lanelet_map"); test_manager->publishRoute(test_target_node, "input/route"); +} - // set subscriber with topic name: scenario_selector → test_node_ - test_manager->setScenarioSubscriber("output/scenario"); +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); // set scenario_selector's input topic name(this topic is changed to test node) test_manager->setTrajectoryInputTopicName("input/lane_driving/trajectory"); @@ -55,7 +75,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); rclcpp::shutdown(); } @@ -63,36 +83,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryParkingMode) { rclcpp::init(0, nullptr); - auto test_manager = std::make_shared(); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); - auto node_options = rclcpp::NodeOptions{}; - node_options.append_parameter_override("update_rate", 10.0); - node_options.append_parameter_override("th_max_message_delay_sec", INFINITY); - node_options.append_parameter_override("th_arrived_distance_m", 1.0); - node_options.append_parameter_override("th_stopped_time_sec", 1.0); - node_options.append_parameter_override("th_stopped_velocity_mps", 0.01); - auto test_target_node = std::make_shared(node_options); - - // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "input/odometry"); - test_manager->publishAcceleration(test_target_node, "input/acceleration"); - test_manager->publishParkingState(test_target_node, "is_parking_completed"); - test_manager->publishTrajectory(test_target_node, "input/lane_driving/trajectory"); - test_manager->publishMap(test_target_node, "input/lanelet_map"); - test_manager->publishRoute(test_target_node, "input/route"); - - // set subscriber with topic name: scenario_selector → test_node_ - test_manager->setScenarioSubscriber("output/scenario"); + publishMandatoryTopics(test_manager, test_target_node); // set scenario_selector's input topic name(this topic is changed to test node) test_manager->setTrajectoryInputTopicName("input/parking/trajectory"); // test for normal trajectory ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); - EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); rclcpp::shutdown(); }