Skip to content

Commit

Permalink
adapt velocity_smoother to new test manager
Browse files Browse the repository at this point in the history
Signed-off-by: mitukou1109 <[email protected]>
  • Loading branch information
mitukou1109 committed Jan 17, 2025
1 parent ec07b32 commit b8eb8fc
Showing 1 changed file with 23 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,8 @@ using autoware::velocity_smoother::VelocitySmootherNode;
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
test_manager->setTrajectorySubscriber("velocity_smoother/output/trajectory");
test_manager->setTrajectoryInputTopicName("velocity_smoother/input/trajectory");
test_manager->setOdometryTopicName("/localization/kinematic_state");
test_manager->subscribeOutput<autoware_planning_msgs::msg::Trajectory>(
"velocity_smoother/output/trajectory");
return test_manager;
}

Expand Down Expand Up @@ -60,12 +59,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)
Expand All @@ -76,12 +80,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();
}
Expand All @@ -94,11 +101,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->testWithOffTrackOdometries(test_target_node, input_odometry_topic));

rclcpp::shutdown();
}

0 comments on commit b8eb8fc

Please sign in to comment.