diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp index 8bf30757aafb7..020a184224a02 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include using autoware::freespace_planner::FreespacePlannerNode; @@ -29,10 +30,8 @@ using autoware::planning_test_manager::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); - test_manager->setRouteInputTopicName("freespace_planner/input/route"); - test_manager->setTrajectorySubscriber("freespace_planner/output/trajectory"); - test_manager->setOdometryTopicName("freespace_planner/input/odometry"); - test_manager->setInitialPoseTopicName("freespace_planner/input/odometry"); + test_manager->subscribeOutput( + "freespace_planner/output/trajectory"); return test_manager; } @@ -55,10 +54,16 @@ void publishMandatoryTopics( rclcpp::Node::SharedPtr test_target_node) { // publish necessary topics from test_manager - test_manager->publishTF(test_target_node, "/tf"); - test_manager->publishOdometry(test_target_node, "freespace_planner/input/odometry"); - test_manager->publishOccupancyGrid(test_target_node, "freespace_planner/input/occupancy_grid"); - test_manager->publishParkingScenario(test_target_node, "freespace_planner/input/scenario"); + test_manager->publishInput( + test_target_node, "/tf", autoware::test_utils::makeTFMsg(test_target_node, "base_link", "map")); + test_manager->publishInput( + test_target_node, "freespace_planner/input/odometry", autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "freespace_planner/input/occupancy_grid", + autoware::test_utils::makeCostMapMsg()); + test_manager->publishInput( + test_target_node, "freespace_planner/input/scenario", + autoware::test_utils::makeScenarioMsg(tier4_planning_msgs::msg::Scenario::PARKING)); } // the following tests are disable because they randomly fail @@ -70,12 +75,16 @@ TEST(PlanningModuleInterfaceTest, DISABLED_testPlanningInterfaceWithVariousTraje auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "freespace_planner/input/route"; + // test with normal route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -87,11 +96,16 @@ TEST(PlanningModuleInterfaceTest, DISABLED_NodeTestWithOffTrackEgoPose) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "freespace_planner/input/route"; + const std::string input_odometry_topic = "freespace_planner/input/odometry"; + // test for normal route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index 2235704a3a070..db9fef1cb7598 100644 --- a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include using autoware::motion_planning::ObstacleCruisePlannerNode; @@ -31,12 +32,8 @@ std::shared_ptr generateTestManager() auto test_manager = std::make_shared(); // set subscriber with topic name: obstacle_cruise_planner → test_node_ - test_manager->setTrajectorySubscriber("obstacle_cruise_planner/output/trajectory"); - - // set obstacle_cruise_planners input topic name(this topic is changed to test node): - test_manager->setTrajectoryInputTopicName("obstacle_cruise_planner/input/trajectory"); - - test_manager->setOdometryTopicName("obstacle_cruise_planner/input/odometry"); + test_manager->subscribeOutput( + "obstacle_cruise_planner/output/trajectory"); return test_manager; } @@ -63,9 +60,15 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "obstacle_cruise_planner/input/odometry"); - test_manager->publishPredictedObjects(test_target_node, "obstacle_cruise_planner/input/objects"); - test_manager->publishAcceleration(test_target_node, "obstacle_cruise_planner/input/acceleration"); + test_manager->publishInput( + test_target_node, "obstacle_cruise_planner/input/odometry", + autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "obstacle_cruise_planner/input/objects", + autoware_perception_msgs::msg::PredictedObjects{}); + test_manager->publishInput( + test_target_node, "obstacle_cruise_planner/input/acceleration", + geometry_msgs::msg::AccelWithCovarianceStamped{}); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -76,12 +79,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "obstacle_cruise_planner/input/trajectory"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } @@ -94,12 +101,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "obstacle_cruise_planner/input/trajectory"; + const std::string input_odometry_topic = "obstacle_cruise_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp index 9da8409c6c2ae..2654be0937d35 100644 --- a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp +++ b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp @@ -23,6 +23,7 @@ #include #include +#include #include using autoware::motion_planning::ObstacleStopPlannerNode; @@ -32,9 +33,8 @@ using tier4_planning_msgs::msg::ExpandStopRange; std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); - test_manager->setTrajectorySubscriber("obstacle_stop_planner/output/trajectory"); - test_manager->setTrajectoryInputTopicName("obstacle_stop_planner/input/trajectory"); - test_manager->setOdometryTopicName("obstacle_stop_planner/input/odometry"); + test_manager->subscribeOutput( + "obstacle_stop_planner/output/trajectory"); return test_manager; } @@ -65,21 +65,21 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "obstacle_stop_planner/input/odometry"); - test_manager->publishPointCloud(test_target_node, "obstacle_stop_planner/input/pointcloud"); - test_manager->publishAcceleration(test_target_node, "obstacle_stop_planner/input/acceleration"); - test_manager->publishPredictedObjects(test_target_node, "obstacle_stop_planner/input/objects"); -} - -void publishExpandStopRange( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - auto test_node = test_manager->getTestNode(); - const auto expand_stop_range = test_manager->getTestNode()->create_publisher( - "obstacle_stop_planner/input/expand_stop_range", 1); - expand_stop_range->publish(ExpandStopRange{}); - autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3); + test_manager->publishInput( + test_target_node, "obstacle_stop_planner/input/odometry", autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "obstacle_stop_planner/input/pointcloud", + sensor_msgs::msg::PointCloud2{}.set__header( + std_msgs::msg::Header{}.set__frame_id("base_link"))); + test_manager->publishInput( + test_target_node, "obstacle_stop_planner/input/acceleration", + geometry_msgs::msg::AccelWithCovarianceStamped{}); + test_manager->publishInput( + test_target_node, "obstacle_stop_planner/input/objects", + autoware_perception_msgs::msg::PredictedObjects{}); + test_manager->publishInput( + test_target_node, "obstacle_stop_planner/input/expand_stop_range", + tier4_planning_msgs::msg::ExpandStopRange{}); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -90,15 +90,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); - publishExpandStopRange(test_manager, test_target_node); + + const std::string input_trajectory_topic = "obstacle_stop_planner/input/trajectory"; // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - test_manager->testWithAbnormalTrajectory(test_target_node); + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic); rclcpp::shutdown(); } @@ -110,14 +112,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); - publishExpandStopRange(test_manager, test_target_node); + + const std::string input_trajectory_topic = "obstacle_stop_planner/input/trajectory"; + const std::string input_odometry_topic = "obstacle_stop_planner/input/odometry"; // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp index e310fecf15d8c..164da3173b655 100644 --- a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp +++ b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -47,21 +48,24 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) auto test_target_node = std::make_shared(node_options); // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "path_optimizer/input/odometry"); + test_manager->publishInput( + test_target_node, "path_optimizer/input/odometry", autoware::test_utils::makeOdometry()); // set subscriber with topic name: path_optimizer → test_node_ - test_manager->setTrajectorySubscriber("path_optimizer/output/path"); + test_manager->subscribeOutput( + "path_optimizer/output/path"); - // set path_optimizer's input topic name(this topic is changed to test node) - test_manager->setPathInputTopicName("path_optimizer/input/path"); + const std::string input_trajectory_topic = "path_optimizer/input/path"; // test with normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPath(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPath(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with trajectory with empty/one point/overlapping point - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPath(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPath(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } diff --git a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp index 7402541c727ff..edf03556f2c21 100644 --- a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp +++ b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -46,22 +47,27 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) std::make_shared(node_options); // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "autoware_path_smoother/input/odometry"); + test_manager->publishInput( + test_target_node, "autoware_path_smoother/input/odometry", + autoware::test_utils::makeOdometry()); // set subscriber with topic name - test_manager->setTrajectorySubscriber("autoware_path_smoother/output/traj"); - test_manager->setPathSubscriber("autoware_path_smoother/output/path"); + test_manager->subscribeOutput( + "autoware_path_smoother/output/traj"); + test_manager->subscribeOutput( + "autoware_path_smoother/output/path"); - // set input topic name (this topic is changed to test node) - test_manager->setPathInputTopicName("autoware_path_smoother/input/path"); + const std::string input_path_topic = "autoware_path_smoother/input/path"; // test with normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPath(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPath(test_target_node, input_path_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with trajectory with empty/one point/overlapping point - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPath(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPath(test_target_node, input_path_topic)); rclcpp::shutdown(); } diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index cf45154893af7..127cb11d8e101 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -32,29 +32,10 @@ #include #include +#include #include -#include -#include -#include -#include -#include -#include -#include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include #include #include @@ -63,190 +44,77 @@ #include #include #include +#include namespace autoware::planning_test_manager { -using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_map_msgs::msg::LaneletMapBin; -using autoware_perception_msgs::msg::PredictedObjects; -using autoware_perception_msgs::msg::TrafficLightGroupArray; -using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::Path; -using autoware_planning_msgs::msg::Trajectory; -using geometry_msgs::msg::AccelWithCovarianceStamped; -using geometry_msgs::msg::Point; -using geometry_msgs::msg::PoseStamped; -using geometry_msgs::msg::Quaternion; -using geometry_msgs::msg::TransformStamped; -using nav_msgs::msg::OccupancyGrid; -using nav_msgs::msg::Odometry; -using sensor_msgs::msg::PointCloud2; -using tf2_msgs::msg::TFMessage; -using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_planning_msgs::msg::Scenario; -using tier4_planning_msgs::msg::VelocityLimit; - -enum class ModuleName { - UNKNOWN = 0, - START_PLANNER, -}; - class PlanningInterfaceTestManager { public: PlanningInterfaceTestManager(); - void publishOdometry( - rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift = 0.0); - - void publishInitialPose( - rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift = 0.0, - ModuleName module_name = ModuleName::UNKNOWN); - - void publishMaxVelocity(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishPointCloud(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishAcceleration(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishPredictedObjects(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishOccupancyGrid(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishCostMap(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishMap(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishLaneDrivingScenario(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishParkingScenario(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishParkingState(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishTrajectory(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishRoute(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishTF(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishInitialPoseTF(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishOperationModeState(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishTrafficSignals(rclcpp::Node::SharedPtr target_node, std::string topic_name); - - void setTrajectoryInputTopicName(std::string topic_name); - void setParkingTrajectoryInputTopicName(std::string topic_name); - void setLaneDrivingTrajectoryInputTopicName(std::string topic_name); - void setRouteInputTopicName(std::string topic_name); - void setPathInputTopicName(std::string topic_name); - void setPathWithLaneIdTopicName(std::string topic_name); - void setPathTopicName(std::string topic_name); - - void setTrajectorySubscriber(std::string topic_name); - void setScenarioSubscriber(std::string topic_name); - void setPathWithLaneIdSubscriber(std::string topic_name); - void setRouteSubscriber(std::string topic_name); - void setPathSubscriber(std::string topic_name); - - void setInitialPoseTopicName(std::string topic_name); - void setOdometryTopicName(std::string topic_name); - - void testWithNominalTrajectory(rclcpp::Node::SharedPtr target_node); - void testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node); - - void testWithNominalRoute(rclcpp::Node::SharedPtr target_node); - void testWithAbnormalRoute(rclcpp::Node::SharedPtr target_node); - - void testWithBehaviorNominalRoute( - rclcpp::Node::SharedPtr target_node, ModuleName module_name = ModuleName::UNKNOWN); - - void testWithNominalPathWithLaneId(rclcpp::Node::SharedPtr target_node); - void testWithAbnormalPathWithLaneId(rclcpp::Node::SharedPtr target_node); - - void testWithNominalPath(rclcpp::Node::SharedPtr target_node); - void testWithAbnormalPath(rclcpp::Node::SharedPtr target_node); - - // for invalid ego poses, contains some tests inside. - void testRouteWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node); - void testPathWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node); - void testPathWithLaneIdWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node); - void testTrajectoryWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node); - - // ego vehicle is located far from trajectory - void testOffTrackFromRoute(rclcpp::Node::SharedPtr target_node); - void testOffTrackFromPath(rclcpp::Node::SharedPtr target_node); - void testOffTrackFromPathWithLaneId(rclcpp::Node::SharedPtr target_node); - void testOffTrackFromTrajectory(rclcpp::Node::SharedPtr target_node); - - int getReceivedTopicNum(); - rclcpp::Node::SharedPtr getTestNode() const; + template + void publishInput( + const rclcpp::Node::SharedPtr target_node, const std::string & topic_name, const InputT & input, + const int repeat_count = 3) const + { + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, {}, input, repeat_count); + } -private: - // Publisher (necessary for node running) - rclcpp::Publisher::SharedPtr odom_pub_; - rclcpp::Publisher::SharedPtr initial_pose_pub_; - rclcpp::Publisher::SharedPtr max_velocity_pub_; - rclcpp::Publisher::SharedPtr point_cloud_pub_; - rclcpp::Publisher::SharedPtr acceleration_pub_; - rclcpp::Publisher::SharedPtr predicted_objects_pub_; - rclcpp::Publisher::SharedPtr occupancy_grid_pub_; - rclcpp::Publisher::SharedPtr cost_map_pub_; - rclcpp::Publisher::SharedPtr map_pub_; - rclcpp::Publisher::SharedPtr scenario_pub_; - rclcpp::Publisher::SharedPtr parking_scenario_pub_; - rclcpp::Publisher::SharedPtr lane_driving_scenario_pub_; - rclcpp::Publisher::SharedPtr parking_state_pub_; - rclcpp::Publisher::SharedPtr trajectory_pub_; - rclcpp::Publisher::SharedPtr route_pub_; - rclcpp::Publisher::SharedPtr TF_pub_; - rclcpp::Publisher::SharedPtr initial_pose_tf_pub_; - rclcpp::Publisher::SharedPtr operation_mode_state_pub_; - rclcpp::Publisher::SharedPtr traffic_signals_pub_; + template + void subscribeOutput(const std::string & topic_name) + { + const auto qos = []() { + if constexpr (std::is_same_v) { + return rclcpp::QoS{1}; + } + return rclcpp::QoS{10}; + }(); + + test_output_subs_.push_back(test_node_->create_subscription( + topic_name, qos, [this](const typename OutputT::ConstSharedPtr) { received_topic_num_++; })); + } + + void testWithNormalTrajectory( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + void testWithAbnormalTrajectory( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void testWithNormalRoute(rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + void testWithAbnormalRoute(rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void testWithBehaviorNormalRoute( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void testWithNormalPathWithLaneId( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + void testWithAbnormalPathWithLaneId( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + void testWithNormalPath(rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + void testWithAbnormalPath(rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void testWithOffTrackInitialPoses( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void testWithOffTrackOdometry( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name); + + void resetReceivedTopicNum() { received_topic_num_ = 0; } + + size_t getReceivedTopicNum() const { return received_topic_num_; } + + rclcpp::Node::SharedPtr getTestNode() const { return test_node_; } + +private: // Subscriber - rclcpp::Subscription::SharedPtr traj_sub_; - rclcpp::Subscription::SharedPtr route_sub_; - rclcpp::Subscription::SharedPtr scenario_sub_; - rclcpp::Subscription::SharedPtr path_with_lane_id_sub_; - rclcpp::Subscription::SharedPtr path_sub_; - - // Publisher for testing(trajectory) - rclcpp::Publisher::SharedPtr normal_trajectory_pub_; - rclcpp::Publisher::SharedPtr abnormal_trajectory_pub_; - - // Publisher for testing(route) - rclcpp::Publisher::SharedPtr normal_route_pub_; - rclcpp::Publisher::SharedPtr abnormal_route_pub_; - - // Publisher for testing(route) - rclcpp::Publisher::SharedPtr behavior_normal_route_pub_; - - // Publisher for testing(PathWithLaneId) - rclcpp::Publisher::SharedPtr normal_path_with_lane_id_pub_; - rclcpp::Publisher::SharedPtr abnormal_path_with_lane_id_pub_; - - // Publisher for testing(Path) - rclcpp::Publisher::SharedPtr normal_path_pub_; - rclcpp::Publisher::SharedPtr abnormal_path_pub_; - - std::string input_trajectory_name_ = ""; - std::string input_parking_trajectory_name_ = ""; - std::string input_lane_driving_trajectory_name_ = ""; - std::string input_route_name_ = ""; - std::string input_path_name_ = ""; - std::string input_path_with_lane_id_name_ = ""; - std::string input_initial_pose_name_ = ""; // for the map based pose - std::string input_odometry_name_ = ""; + std::vector test_output_subs_; // Node rclcpp::Node::SharedPtr test_node_; - std::string map_frame_ = "map"; - size_t count_{0}; - std::shared_ptr tf_buffer_; - std::shared_ptr tf_listener_; - void publishNominalTrajectory(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishAbnormalTrajectory( - rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory); - - void publishNominalRoute(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishAbnormalRoute( - rclcpp::Node::SharedPtr target_node, const LaneletRoute & abnormal_route); - - void publishBehaviorNominalRoute( - rclcpp::Node::SharedPtr target_node, std::string topic_name, - ModuleName module_name = ModuleName::UNKNOWN); - void publishNominalPathWithLaneId(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishAbNominalPathWithLaneId(rclcpp::Node::SharedPtr target_node, std::string topic_name); - - void publishNominalPath(rclcpp::Node::SharedPtr target_node, std::string topic_name); - void publishAbnormalPath(rclcpp::Node::SharedPtr target_node, std::string topic_name); + size_t received_topic_num_ = 0; }; // class PlanningInterfaceTestManager } // namespace autoware::planning_test_manager diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index f07efd0cda116..1d5dbd607cfb5 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -12,446 +12,115 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/motion_utils/trajectory/conversion.hpp" +#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" -#include -#include -#include -#include +#include + +#include +#include +#include #include #include #include -#include namespace autoware::planning_test_manager { +using autoware_planning_msgs::msg::LaneletRoute; +using autoware_planning_msgs::msg::Path; +using autoware_planning_msgs::msg::Trajectory; +using tier4_planning_msgs::msg::PathWithLaneId; PlanningInterfaceTestManager::PlanningInterfaceTestManager() { test_node_ = std::make_shared("planning_interface_test_node"); - tf_buffer_ = std::make_shared(test_node_->get_clock()); - tf_listener_ = std::make_shared(*tf_buffer_); -} - -void PlanningInterfaceTestManager::publishOdometry( - rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, odom_pub_, autoware::test_utils::makeOdometry(shift)); -} - -void PlanningInterfaceTestManager::publishMaxVelocity( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::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) -{ - PointCloud2 point_cloud_msg{}; - point_cloud_msg.header.frame_id = "base_link"; - autoware::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) +void PlanningInterfaceTestManager::testWithNormalTrajectory( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, acceleration_pub_, AccelWithCovarianceStamped{}); + publishInput( + target_node, topic_name, autoware::test_utils::generateTrajectory(10, 1.0), 5); } -void PlanningInterfaceTestManager::publishPredictedObjects( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithAbnormalTrajectory( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, predicted_objects_pub_, PredictedObjects{}); + publishInput(target_node, topic_name, Trajectory{}, 5); + publishInput( + target_node, topic_name, autoware::test_utils::generateTrajectory(1, 0.0), 5); + publishInput( + target_node, topic_name, + autoware::test_utils::generateTrajectory(10, 0.0, 0.0, 0.0, 0.0, 1), 5); } -void PlanningInterfaceTestManager::publishOccupancyGrid( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithNormalRoute( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, occupancy_grid_pub_, - autoware::test_utils::makeCostMapMsg()); + publishInput(target_node, topic_name, autoware::test_utils::makeNormalRoute(), 5); } -void PlanningInterfaceTestManager::publishCostMap( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithAbnormalRoute( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, cost_map_pub_, autoware::test_utils::makeCostMapMsg()); + publishInput(target_node, topic_name, LaneletRoute{}, 5); } -void PlanningInterfaceTestManager::publishMap( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithBehaviorNormalRoute( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, map_pub_, autoware::test_utils::makeMapBinMsg()); -} - -void PlanningInterfaceTestManager::publishLaneDrivingScenario( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, lane_driving_scenario_pub_, - autoware::test_utils::makeScenarioMsg(Scenario::LANEDRIVING)); -} - -void PlanningInterfaceTestManager::publishParkingScenario( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, parking_scenario_pub_, - autoware::test_utils::makeScenarioMsg(Scenario::PARKING)); -} - -void PlanningInterfaceTestManager::publishInitialPose( - rclcpp::Node::SharedPtr target_node, std::string topic_name, const double shift, - ModuleName module_name) -{ - if (module_name == ModuleName::START_PLANNER) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, initial_pose_pub_, - autoware_planning_test_manager::utils::makeInitialPoseFromLaneId(10291)); - } else { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, initial_pose_pub_, - autoware::test_utils::makeInitialPose(shift)); - } + publishInput(target_node, topic_name, autoware::test_utils::makeBehaviorNormalRoute(), 5); } -void PlanningInterfaceTestManager::publishParkingState( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::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) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, trajectory_pub_, Trajectory{}); -} - -void PlanningInterfaceTestManager::publishRoute( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, route_pub_, autoware::test_utils::makeNormalRoute()); -} - -void PlanningInterfaceTestManager::publishTF( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, TF_pub_, - autoware::test_utils::makeTFMsg(target_node, "base_link", "map")); -} - -void PlanningInterfaceTestManager::publishOperationModeState( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::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) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, traffic_signals_pub_, TrafficLightGroupArray{}); -} - -void PlanningInterfaceTestManager::publishInitialPoseTF( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, initial_pose_tf_pub_, - autoware::test_utils::makeTFMsg(target_node, "odom", "base_link")); -} - -void PlanningInterfaceTestManager::setTrajectoryInputTopicName(std::string topic_name) -{ - input_trajectory_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setParkingTrajectoryInputTopicName(std::string topic_name) -{ - input_parking_trajectory_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setLaneDrivingTrajectoryInputTopicName(std::string topic_name) -{ - input_lane_driving_trajectory_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setRouteInputTopicName(std::string topic_name) -{ - input_route_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setPathInputTopicName(std::string topic_name) -{ - input_path_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setPathWithLaneIdTopicName(std::string topic_name) -{ - input_path_with_lane_id_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setInitialPoseTopicName(std::string topic_name) -{ - input_initial_pose_name_ = topic_name; -} - -void PlanningInterfaceTestManager::setOdometryTopicName(std::string topic_name) -{ - input_odometry_name_ = topic_name; -} - -void PlanningInterfaceTestManager::publishNominalTrajectory( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_trajectory_pub_, - autoware::test_utils::generateTrajectory(10, 1.0), 5); -} - -void PlanningInterfaceTestManager::publishAbnormalTrajectory( - rclcpp::Node::SharedPtr target_node, const Trajectory & abnormal_trajectory) -{ - autoware::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) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_route_pub_, autoware::test_utils::makeNormalRoute(), - 5); -} - -void PlanningInterfaceTestManager::publishBehaviorNominalRoute( - rclcpp::Node::SharedPtr target_node, std::string topic_name, ModuleName module_name) -{ - if (module_name == ModuleName::START_PLANNER) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, behavior_normal_route_pub_, - autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId(10291, 10333), 5); - } else { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, behavior_normal_route_pub_, - autoware::test_utils::makeBehaviorNormalRoute(), 5); - } -} - -void PlanningInterfaceTestManager::publishAbnormalRoute( - rclcpp::Node::SharedPtr target_node, const LaneletRoute & abnormal_route) -{ - autoware::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) +void PlanningInterfaceTestManager::testWithNormalPathWithLaneId( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { 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); + publishInput(target_node, topic_name, path, 5); } catch (const std::exception & e) { std::cerr << e.what() << '\n'; } } -void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithAbnormalPathWithLaneId( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, abnormal_path_with_lane_id_pub_, PathWithLaneId{}, 5); + publishInput(target_node, topic_name, PathWithLaneId{}, 5); } -void PlanningInterfaceTestManager::publishNominalPath( - rclcpp::Node::SharedPtr target_node, std::string topic_name) +void PlanningInterfaceTestManager::testWithNormalPath( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { try { const auto path = autoware::test_utils::loadPathWithLaneIdInYaml(); - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_path_pub_, + publishInput( + target_node, topic_name, autoware::motion_utils::convertToPath(path), 5); } catch (const std::exception & e) { std::cerr << e.what() << '\n'; } } -void PlanningInterfaceTestManager::publishAbnormalPath( - rclcpp::Node::SharedPtr target_node, std::string topic_name) -{ - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, abnormal_path_pub_, Path{}, 5); -} - -void PlanningInterfaceTestManager::setTrajectorySubscriber(std::string topic_name) -{ - autoware::test_utils::setSubscriber(test_node_, topic_name, traj_sub_, count_); -} - -void PlanningInterfaceTestManager::setRouteSubscriber(std::string topic_name) -{ - autoware::test_utils::setSubscriber(test_node_, topic_name, route_sub_, count_); -} -void PlanningInterfaceTestManager::setScenarioSubscriber(std::string topic_name) -{ - autoware::test_utils::setSubscriber(test_node_, topic_name, scenario_sub_, count_); -} - -void PlanningInterfaceTestManager::setPathWithLaneIdSubscriber(std::string topic_name) -{ - autoware::test_utils::setSubscriber(test_node_, topic_name, path_with_lane_id_sub_, count_); -} - -void PlanningInterfaceTestManager::setPathSubscriber(std::string topic_name) -{ - autoware::test_utils::setSubscriber(test_node_, topic_name, path_sub_, count_); -} - -// test for normal working -void PlanningInterfaceTestManager::testWithNominalTrajectory(rclcpp::Node::SharedPtr target_node) -{ - publishNominalTrajectory(target_node, input_trajectory_name_); -} - -// check to see if target node is dead. -void PlanningInterfaceTestManager::testWithAbnormalTrajectory(rclcpp::Node::SharedPtr target_node) -{ - publishAbnormalTrajectory(target_node, Trajectory{}); - publishAbnormalTrajectory( - target_node, autoware::test_utils::generateTrajectory(1, 0.0)); - publishAbnormalTrajectory( - target_node, autoware::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 for normal working -void PlanningInterfaceTestManager::testWithBehaviorNominalRoute( - rclcpp::Node::SharedPtr target_node, ModuleName module_name) -{ - publishBehaviorNominalRoute(target_node, input_route_name_, module_name); -} - -// check to see if target node is dead. -void PlanningInterfaceTestManager::testWithAbnormalRoute(rclcpp::Node::SharedPtr target_node) -{ - publishAbnormalRoute(target_node, LaneletRoute{}); -} - -// test for normal working -void PlanningInterfaceTestManager::testWithNominalPathWithLaneId( - rclcpp::Node::SharedPtr target_node) -{ - publishNominalPathWithLaneId(target_node, input_path_with_lane_id_name_); -} - -// check to see if target node is dead. -void PlanningInterfaceTestManager::testWithAbnormalPathWithLaneId( - rclcpp::Node::SharedPtr target_node) -{ - publishAbNominalPathWithLaneId(target_node, input_path_with_lane_id_name_); -} - -// put all abnormal ego pose related tests in this functions to run all tests with one line code -void PlanningInterfaceTestManager::testRouteWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node) -{ - testOffTrackFromRoute(target_node); -} - -// put all abnormal ego pose related tests in this functions to run all tests with one line code -void PlanningInterfaceTestManager::testPathWithInvalidEgoPose(rclcpp::Node::SharedPtr target_node) -{ - testOffTrackFromPath(target_node); -} - -// put all abnormal ego pose related tests in this functions to run all tests with one line code -void PlanningInterfaceTestManager::testPathWithLaneIdWithInvalidEgoPose( - rclcpp::Node::SharedPtr target_node) -{ - testOffTrackFromPathWithLaneId(target_node); -} - -// put all abnormal ego pose related tests in this functions to run all tests with one line code -void PlanningInterfaceTestManager::testTrajectoryWithInvalidEgoPose( - rclcpp::Node::SharedPtr target_node) -{ - testOffTrackFromTrajectory(target_node); -} - -void PlanningInterfaceTestManager::testOffTrackFromRoute(rclcpp::Node::SharedPtr target_node) -{ - 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) { - publishInitialPose(target_node, input_initial_pose_name_, deviation); - } -} - -void PlanningInterfaceTestManager::testOffTrackFromPath(rclcpp::Node::SharedPtr target_node) +void PlanningInterfaceTestManager::testWithAbnormalPath( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - // write me - (void)target_node; + publishInput(target_node, topic_name, Path{}, 5); } -void PlanningInterfaceTestManager::testOffTrackFromPathWithLaneId( - rclcpp::Node::SharedPtr target_node) +void PlanningInterfaceTestManager::testWithOffTrackInitialPoses( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - publishNominalPathWithLaneId(target_node, input_path_with_lane_id_name_); - - const std::vector deviation_from_path = {0.0, 1.0, 10.0, 100.0}; - for (const auto & deviation : deviation_from_path) { - publishOdometry(target_node, input_odometry_name_, deviation); + for (const auto & deviation : {0.0, 1.0, 10.0, 100.0}) { + publishInput(target_node, topic_name, autoware::test_utils::makeInitialPose(deviation), 5); } } -void PlanningInterfaceTestManager::testOffTrackFromTrajectory(rclcpp::Node::SharedPtr target_node) +void PlanningInterfaceTestManager::testWithOffTrackOdometry( + rclcpp::Node::SharedPtr target_node, const std::string & topic_name) { - publishNominalTrajectory(target_node, input_trajectory_name_); - - const std::vector deviation_from_traj = {0.0, 1.0, 10.0, 100.0}; - for (const auto & deviation : deviation_from_traj) { - publishOdometry(target_node, input_odometry_name_, deviation); + for (const auto & deviation : {0.0, 1.0, 10.0, 100.0}) { + publishInput(target_node, topic_name, autoware::test_utils::makeOdometry(deviation), 5); } } - -void PlanningInterfaceTestManager::testWithNominalPath(rclcpp::Node::SharedPtr target_node) -{ - publishNominalPath(target_node, input_path_name_); -} - -void PlanningInterfaceTestManager::testWithAbnormalPath(rclcpp::Node::SharedPtr target_node) -{ - publishAbnormalPath(target_node, input_path_name_); -} - -int PlanningInterfaceTestManager::getReceivedTopicNum() -{ - return count_; -} - -rclcpp::Node::SharedPtr PlanningInterfaceTestManager::getTestNode() const -{ - return test_node_; -} - } // namespace autoware::planning_test_manager diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp index 2cf03e04311f2..e52b74571282d 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include using autoware::planning_test_manager::PlanningInterfaceTestManager; @@ -31,12 +32,8 @@ std::shared_ptr generateTestManager() auto test_manager = std::make_shared(); // set subscriber with topic name: planning_validator → test_node_ - test_manager->setTrajectorySubscriber("planning_validator/output/trajectory"); - - // set planning_validator's input topic name(this topic is changed to test node) - test_manager->setTrajectoryInputTopicName("planning_validator/input/trajectory"); - - test_manager->setOdometryTopicName("planning_validator/input/kinematics"); + test_manager->subscribeOutput( + "planning_validator/output/trajectory"); return test_manager; } @@ -60,7 +57,8 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "planning_validator/input/kinematics"); + test_manager->publishInput( + test_target_node, "planning_validator/input/kinematics", autoware::test_utils::makeOdometry()); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -70,12 +68,15 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "planning_validator/input/trajectory"; + // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); } TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) @@ -85,10 +86,13 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "planning_validator/input/trajectory"; + const std::string input_odometry_topic = "planning_validator/input/kinematics"; + // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); } diff --git a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp index ef9af48967a11..0256e7463b5a7 100644 --- a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp +++ b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp @@ -22,7 +22,9 @@ #include #include +#include #include + namespace autoware::scenario_selector { using autoware::planning_test_manager::PlanningInterfaceTestManager; @@ -32,9 +34,7 @@ std::shared_ptr generateTestManager() auto test_manager = std::make_shared(); // set subscriber with topic name: scenario_selector → test_node_ - test_manager->setScenarioSubscriber("output/scenario"); - - test_manager->setOdometryTopicName("input/odometry"); + test_manager->subscribeOutput("output/scenario"); return test_manager; } @@ -58,12 +58,18 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "input/odometry"); - 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"); - test_manager->publishOperationModeState(test_target_node, "input/operation_mode_state"); + test_manager->publishInput( + test_target_node, "input/odometry", autoware::test_utils::makeOdometry()); + test_manager->publishInput(test_target_node, "is_parking_completed", std_msgs::msg::Bool{}); + test_manager->publishInput( + test_target_node, "input/parking/trajectory", autoware_planning_msgs::msg::Trajectory{}); + test_manager->publishInput( + test_target_node, "input/lanelet_map", autoware::test_utils::makeMapBinMsg()); + test_manager->publishInput( + test_target_node, "input/route", autoware::test_utils::makeNormalRoute()); + test_manager->publishInput( + test_target_node, "input/operation_mode_state", + autoware_adapi_v1_msgs::msg::OperationModeState{}); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode) @@ -74,15 +80,15 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryLaneDrivingMode 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"); + const std::string input_trajectory_topic = "input/lane_driving/trajectory"; // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } @@ -95,15 +101,15 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectoryParkingMode) 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"); + const std::string input_trajectory_topic = "input/parking/trajectory"; // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } @@ -115,14 +121,14 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) 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"); + const std::string input_trajectory_topic = "input/lane_driving/trajectory"; + const std::string input_odometry_topic = "input/odometry"; // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } } // namespace autoware::scenario_selector diff --git a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp index b590af1b3ee0a..d8a424095fcc8 100644 --- a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp +++ b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include using autoware::planning_test_manager::PlanningInterfaceTestManager; @@ -29,9 +30,8 @@ using autoware::velocity_smoother::VelocitySmootherNode; std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); - test_manager->setTrajectorySubscriber("velocity_smoother/output/trajectory"); - test_manager->setTrajectoryInputTopicName("velocity_smoother/input/trajectory"); - test_manager->setOdometryTopicName("/localization/kinematic_state"); + test_manager->subscribeOutput( + "velocity_smoother/output/trajectory"); return test_manager; } @@ -60,12 +60,17 @@ void publishMandatoryTopics( rclcpp::Node::SharedPtr test_target_node) { // publish necessary topics from test_manager - test_manager->publishOdometry(test_target_node, "/localization/kinematic_state"); - test_manager->publishMaxVelocity( - test_target_node, "velocity_smoother/input/external_velocity_limit_mps"); - test_manager->publishOperationModeState( - test_target_node, "velocity_smoother/input/operation_mode_state"); - test_manager->publishAcceleration(test_target_node, "velocity_smoother/input/acceleration"); + test_manager->publishInput( + test_target_node, "/localization/kinematic_state", autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "velocity_smoother/input/external_velocity_limit_mps", + tier4_planning_msgs::msg::VelocityLimit{}); + test_manager->publishInput( + test_target_node, "velocity_smoother/input/operation_mode_state", + autoware_adapi_v1_msgs::msg::OperationModeState{}); + test_manager->publishInput( + test_target_node, "velocity_smoother/input/acceleration", + geometry_msgs::msg::AccelWithCovarianceStamped{}); } TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInput) @@ -76,12 +81,15 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "velocity_smoother/output/trajectory"; + // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test for trajectory with empty/one point/overlapping point - ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } @@ -94,11 +102,14 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "velocity_smoother/output/trajectory"; + const std::string input_odometry_topic = "/localization/kinematic_state"; + // test for normal trajectory - ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW(test_manager->testTrajectoryWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW(test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 349d92377d091..c917171c2eb19 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -35,12 +35,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) {"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -54,13 +58,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) {"autoware::behavior_path_planner::AvoidanceByLaneChangeModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 488475079613f..1b2593288ca34 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -32,12 +32,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -51,13 +55,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) {"autoware::behavior_path_planner::DynamicObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 506e43a94de1d..0f1ab11acf3c3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -36,12 +36,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -56,13 +60,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index f6b3e9eeaf715..393ca57bc3a67 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -36,12 +36,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -55,13 +59,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) "autoware::behavior_path_planner::LaneChangeLeftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp index 4930ead6d355d..d3bc4a25e97ca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/test_utils.cpp @@ -26,33 +26,13 @@ namespace autoware::behavior_path_planner { -namespace -{ -using tier4_planning_msgs::msg::LateralOffset; - -void publishLateralOffset( - std::shared_ptr test_manager, - std::shared_ptr test_target_node) -{ - auto test_node = test_manager->getTestNode(); - const auto pub_lateral_offset = test_manager->getTestNode()->create_publisher( - "behavior_path_planner/input/lateral_offset", 1); - pub_lateral_offset->publish(LateralOffset{}); - autoware::test_utils::spinSomeNodes(test_node, test_target_node, 3); -} -} // namespace - std::shared_ptr generateTestManager() { auto test_manager = std::make_shared(); // set subscriber with topic name: behavior_path_planner → test_node_ - test_manager->setPathWithLaneIdSubscriber("behavior_path_planner/output/path"); - - // set behavior_path_planner's input topic name(this topic is changed to test node) - test_manager->setRouteInputTopicName("behavior_path_planner/input/route"); - - test_manager->setInitialPoseTopicName("behavior_path_planner/input/odometry"); + test_manager->subscribeOutput( + "behavior_path_planner/output/path"); return test_manager; } @@ -103,16 +83,32 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishInitialPose(test_target_node, "behavior_path_planner/input/odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_path_planner/input/accel"); - test_manager->publishPredictedObjects(test_target_node, "behavior_path_planner/input/perception"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_path_planner/input/occupancy_grid_map"); - test_manager->publishLaneDrivingScenario( - test_target_node, "behavior_path_planner/input/scenario"); - test_manager->publishMap(test_target_node, "behavior_path_planner/input/vector_map"); - test_manager->publishCostMap(test_target_node, "behavior_path_planner/input/costmap"); - test_manager->publishOperationModeState(test_target_node, "system/operation_mode/state"); - publishLateralOffset(test_manager, test_target_node); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/odometry", + autoware::test_utils::makeInitialPose()); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/accel", + geometry_msgs::msg::AccelWithCovarianceStamped{}); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/perception", + autoware_perception_msgs::msg::PredictedObjects{}); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/occupancy_grid_map", + autoware::test_utils::makeCostMapMsg()); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/scenario", + autoware::test_utils::makeScenarioMsg(tier4_planning_msgs::msg::Scenario::LANEDRIVING)); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/vector_map", + autoware::test_utils::makeMapBinMsg()); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/costmap", + autoware::test_utils::makeCostMapMsg()); + test_manager->publishInput( + test_target_node, "system/operation_mode/state", + autoware_adapi_v1_msgs::msg::OperationModeState{}); + test_manager->publishInput( + test_target_node, "behavior_path_planner/input/lateral_offset", + tier4_planning_msgs::msg::LateralOffset{}); } } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp index 0c933345e7647..4526f8a642408 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp @@ -34,12 +34,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -51,13 +55,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = generateNode({}, {}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index c248a40eb151a..1603f0c225ce2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -34,12 +34,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -52,13 +56,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) generateNode({"side_shift"}, {"autoware::behavior_path_planner::SideShiftModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index c2531e5f2bb9f..4c36245e5b7d0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -32,12 +32,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionRoute) {"autoware::behavior_path_planner::StaticObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty route - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalRoute(test_target_node, input_route_topic)); rclcpp::shutdown(); } @@ -51,13 +55,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) {"autoware::behavior_path_planner::StaticObstacleAvoidanceModuleManager"}); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_route_topic = "behavior_path_planner/input/route"; + const std::string input_odometry_topic = "behavior_path_planner/input/odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithBehaviorNominalRoute(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithBehaviorNormalRoute(test_target_node, input_route_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testRouteWithInvalidEgoPose(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp index e0ceca4e12951..ab8876a012654 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp index 7a875327d4dde..6246adb0facea 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp index f84d22debea8e..a359a3a64e416 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp index b515107e0ae8e..5ab57735af505 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp index 875e757cbfcec..714dbc102cc05 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp index 8b9f39e97d22b..45ce88c8e92d4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/test_utils.cpp @@ -29,14 +29,8 @@ std::shared_ptr generateTestManager() auto test_manager = std::make_shared(); // set subscriber with topic name: behavior_velocity_planner → test_node_ - test_manager->setPathSubscriber("behavior_velocity_planner_node/output/path"); - - // set behavior_velocity_planner node's input topic name(this topic is changed to test node) - test_manager->setPathWithLaneIdTopicName( - "behavior_velocity_planner_node/input/path_with_lane_id"); - - test_manager->setInitialPoseTopicName("behavior_velocity_planner_node/input/vehicle_odometry"); - test_manager->setOdometryTopicName("behavior_velocity_planner_node/input/vehicle_odometry"); + test_manager->subscribeOutput( + "behavior_velocity_planner_node/output/path"); return test_manager; } @@ -99,21 +93,35 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishTF(test_target_node, "/tf"); - test_manager->publishAcceleration(test_target_node, "behavior_velocity_planner_node/input/accel"); - test_manager->publishPredictedObjects( - test_target_node, "behavior_velocity_planner_node/input/dynamic_objects"); - test_manager->publishPointCloud( - test_target_node, "behavior_velocity_planner_node/input/no_ground_pointcloud"); - test_manager->publishOdometry( - test_target_node, "behavior_velocity_planner_node/input/vehicle_odometry"); - test_manager->publishAcceleration(test_target_node, "behavior_velocity_planner_node/input/accel"); - test_manager->publishMap(test_target_node, "behavior_velocity_planner_node/input/vector_map"); - test_manager->publishTrafficSignals( - test_target_node, "behavior_velocity_planner_node/input/traffic_signals"); - test_manager->publishMaxVelocity( - test_target_node, "behavior_velocity_planner_node/input/external_velocity_limit_mps"); - test_manager->publishOccupancyGrid( - test_target_node, "behavior_velocity_planner_node/input/occupancy_grid"); + test_manager->publishInput( + test_target_node, "/tf", autoware::test_utils::makeTFMsg(test_target_node, "base_link", "map")); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/accel", + geometry_msgs::msg::AccelWithCovarianceStamped{}); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/dynamic_objects", + autoware_perception_msgs::msg::PredictedObjects{}); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/no_ground_pointcloud", + sensor_msgs::msg::PointCloud2{}.set__header( + std_msgs::msg::Header{}.set__frame_id("base_link"))); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/vehicle_odometry", + autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/accel", + geometry_msgs::msg::AccelWithCovarianceStamped{}); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/vector_map", + autoware::test_utils::makeMapBinMsg()); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/traffic_signals", + autoware_perception_msgs::msg::TrafficLightGroupArray{}); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/external_velocity_limit_mps", + tier4_planning_msgs::msg::VelocityLimit{}); + test_manager->publishInput( + test_target_node, "behavior_velocity_planner_node/input/occupancy_grid", + autoware::test_utils::makeCostMapMsg()); } } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp index 6e232318c1711..d62710f4daa24 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -48,13 +53,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode({}); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp index 75bf59751ed44..9e906c816b63c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp index c6d6ff638cfbb..ac158a0e59084 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp index e24c2dab5dab9..7c261486c1270 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp index 0e22413c0c8ec..74c61696a0d58 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_node_interface.cpp @@ -53,12 +53,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); publishVirtualTrafficLightState(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -76,13 +81,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); publishVirtualTrafficLightState(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp index e0b7fa5c31965..fb8286874fe03 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/test/test_node_interface.cpp @@ -31,12 +31,17 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID) autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + // test with nominal path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty path_with_lane_id - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); rclcpp::shutdown(); } @@ -51,13 +56,19 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = autoware::behavior_velocity_planner::generateNode(plugin_info_vec); autoware::behavior_velocity_planner::publishMandatoryTopics(test_manager, test_target_node); + const std::string input_path_with_lane_id_topic = + "behavior_velocity_planner_node/input/path_with_lane_id"; + const std::string input_odometry_topic = "behavior_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalPathWithLaneId(test_target_node, input_path_with_lane_id_topic)); // make sure behavior_path_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); } diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp index b4a95dc020ffd..6ce5e3e506262 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node_universe/test/src/test_node_interface.cpp @@ -32,13 +32,8 @@ std::shared_ptr generateTestManager() auto test_manager = std::make_shared(); // set subscriber with topic name: motion_velocity_planner → test_node_ - test_manager->setTrajectorySubscriber("motion_velocity_planner_node/output/trajectory"); - - // set motion_velocity_planner node's input topic name(this topic is changed to test node) - test_manager->setTrajectoryInputTopicName("motion_velocity_planner_node/input/trajectory"); - - test_manager->setInitialPoseTopicName("motion_velocity_planner_node/input/vehicle_odometry"); - test_manager->setOdometryTopicName("motion_velocity_planner_node/input/vehicle_odometry"); + test_manager->subscribeOutput( + "motion_velocity_planner_node/output/trajectory"); return test_manager; } @@ -89,20 +84,30 @@ void publishMandatoryTopics( std::shared_ptr test_target_node) { // publish necessary topics from test_manager - test_manager->publishTF(test_target_node, "/tf"); - test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel"); - test_manager->publishPredictedObjects( - test_target_node, "motion_velocity_planner_node/input/dynamic_objects"); - test_manager->publishPointCloud( - test_target_node, "motion_velocity_planner_node/input/no_ground_pointcloud"); - test_manager->publishOdometry( - test_target_node, "motion_velocity_planner_node/input/vehicle_odometry"); - test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel"); - test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map"); - test_manager->publishTrafficSignals( - test_target_node, "motion_velocity_planner_node/input/traffic_signals"); - test_manager->publishOccupancyGrid( - test_target_node, "motion_velocity_planner_node/input/occupancy_grid"); + test_manager->publishInput( + test_target_node, "/tf", autoware::test_utils::makeTFMsg(test_target_node, "base_link", "map")); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/accel", + geometry_msgs::msg::AccelWithCovarianceStamped{}); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/dynamic_objects", + autoware_perception_msgs::msg::PredictedObjects{}); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/no_ground_pointcloud", + sensor_msgs::msg::PointCloud2{}.set__header( + std_msgs::msg::Header{}.set__frame_id("base_link"))); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/vehicle_odometry", + autoware::test_utils::makeOdometry()); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/vector_map", + autoware::test_utils::makeMapBinMsg()); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/traffic_signals", + autoware_perception_msgs::msg::TrafficLightGroupArray{}); + test_manager->publishInput( + test_target_node, "motion_velocity_planner_node/input/occupancy_grid", + autoware::test_utils::makeCostMapMsg()); } TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) @@ -113,12 +118,16 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "motion_velocity_planner_node/input/trajectory"; + // test with nominal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); EXPECT_GE(test_manager->getReceivedTopicNum(), 1); // test with empty trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithAbnormalTrajectory(test_target_node, input_trajectory_topic)); rclcpp::shutdown(); } @@ -130,13 +139,18 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) auto test_target_node = generateNode(); publishMandatoryTopics(test_manager, test_target_node); + const std::string input_trajectory_topic = "motion_velocity_planner_node/input/trajectory"; + const std::string input_odometry_topic = "motion_velocity_planner_node/input/vehicle_odometry"; + // test for normal trajectory - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithNormalTrajectory(test_target_node, input_trajectory_topic)); // make sure motion_velocity_planner is running EXPECT_GE(test_manager->getReceivedTopicNum(), 1); - ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromTrajectory(test_target_node)); + ASSERT_NO_THROW_WITH_ERROR_MSG( + test_manager->testWithOffTrackOdometry(test_target_node, input_odometry_topic)); rclcpp::shutdown(); }