@@ -47,21 +47,24 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
47
47
auto test_target_node = std::make_shared<autoware::path_optimizer::PathOptimizer>(node_options);
48
48
49
49
// publish necessary topics from test_manager
50
- test_manager->publishOdometry (test_target_node, " path_optimizer/input/odometry" );
50
+ test_manager->publishInput (
51
+ test_target_node, " path_optimizer/input/odometry" , autoware::test_utils::makeOdometry ());
51
52
52
53
// set subscriber with topic name: path_optimizer → test_node_
53
- test_manager->setTrajectorySubscriber (" path_optimizer/output/path" );
54
+ test_manager->subscribeOutput <autoware_planning_msgs::msg::Trajectory>(
55
+ " path_optimizer/output/path" );
54
56
55
- // set path_optimizer's input topic name(this topic is changed to test node)
56
- test_manager->setPathInputTopicName (" path_optimizer/input/path" );
57
+ const std::string input_trajectory_topic = " path_optimizer/input/path" ;
57
58
58
59
// test with normal trajectory
59
- ASSERT_NO_THROW_WITH_ERROR_MSG (test_manager->testWithNominalPath (test_target_node));
60
+ ASSERT_NO_THROW_WITH_ERROR_MSG (
61
+ test_manager->testWithNormalPath (test_target_node, input_trajectory_topic));
60
62
61
63
EXPECT_GE (test_manager->getReceivedTopicNum (), 1 );
62
64
63
65
// test with trajectory with empty/one point/overlapping point
64
- ASSERT_NO_THROW_WITH_ERROR_MSG (test_manager->testWithAbnormalPath (test_target_node));
66
+ ASSERT_NO_THROW_WITH_ERROR_MSG (
67
+ test_manager->testWithAbnormalPath (test_target_node, input_trajectory_topic));
65
68
66
69
rclcpp::shutdown ();
67
70
}
0 commit comments