Skip to content

Commit ee3f250

Browse files
committed
setup node interface test
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent b84fe84 commit ee3f250

File tree

4 files changed

+47
-84
lines changed

4 files changed

+47
-84
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt

+8-8
Original file line numberDiff line numberDiff line change
@@ -32,14 +32,14 @@ else()
3232
endif()
3333

3434
if(BUILD_TESTING)
35-
# ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
36-
# test/src/test_node_interface.cpp TODO(Maxime)
37-
# )
38-
# target_link_libraries(test_${PROJECT_NAME}
39-
# gtest_main
40-
# ${PROJECT_NAME}_lib
41-
# )
42-
# target_include_directories(test_${PROJECT_NAME} PRIVATE src)
35+
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
36+
test/src/test_node_interface.cpp
37+
)
38+
target_link_libraries(test_${PROJECT_NAME}
39+
gtest_main
40+
${PROJECT_NAME}_lib
41+
)
42+
target_include_directories(test_${PROJECT_NAME} PRIVATE src)
4343
endif()
4444

4545
ament_auto_package(INSTALL_TO_SHARE
Original file line numberDiff line numberDiff line change
@@ -1,2 +0,0 @@
1-
/**:
2-
ros__parameters:

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@
4646
<test_depend>ament_cmake_ros</test_depend>
4747
<test_depend>ament_lint_auto</test_depend>
4848
<test_depend>autoware_lint_common</test_depend>
49+
<test_depend>autoware_motion_velocity_out_of_lane_module</test_depend>
50+
<test_depend>autoware_planning_test_manager</test_depend>
4951

5052
<member_of_group>rosidl_interface_packages</member_of_group>
5153

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp

+37-74
Original file line numberDiff line numberDiff line change
@@ -15,67 +15,51 @@
1515
#include "node.hpp"
1616

1717
#include <ament_index_cpp/get_package_share_directory.hpp>
18-
#include <planning_test_utils/planning_interface_test_manager.hpp>
19-
#include <planning_test_utils/planning_interface_test_manager_utils.hpp>
18+
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
19+
#include <autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp>
2020

2121
#include <gtest/gtest.h>
2222

23-
#include <cmath>
2423
#include <vector>
2524

26-
using behavior_velocity_planner::BehaviorVelocityPlannerNode;
25+
using autoware::motion_velocity_planner::MotionVelocityPlannerNode;
2726
using planning_test_utils::PlanningInterfaceTestManager;
2827

2928
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
3029
{
3130
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
3231

33-
// set subscriber with topic name: behavior_velocity_planner → test_node_
34-
test_manager->setPathSubscriber("behavior_velocity_planner_node/output/path");
32+
// set subscriber with topic name: motion_velocity_planner → test_node_
33+
test_manager->setTrajectorySubscriber("motion_velocity_planner_node/output/trajectory");
3534

36-
// set behavior_velocity_planner node's input topic name(this topic is changed to test node)
37-
test_manager->setPathWithLaneIdTopicName(
38-
"behavior_velocity_planner_node/input/path_with_lane_id");
35+
// set motion_velocity_planner node's input topic name(this topic is changed to test node)
36+
test_manager->setTrajectoryInputTopicName("motion_velocity_planner_node/input/trajectory");
3937

40-
test_manager->setInitialPoseTopicName("behavior_velocity_planner_node/input/vehicle_odometry");
41-
test_manager->setOdometryTopicName("behavior_velocity_planner_node/input/vehicle_odometry");
38+
test_manager->setInitialPoseTopicName("motion_velocity_planner_node/input/vehicle_odometry");
39+
test_manager->setOdometryTopicName("motion_velocity_planner_node/input/vehicle_odometry");
4240

4341
return test_manager;
4442
}
4543

46-
std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
44+
std::shared_ptr<MotionVelocityPlannerNode> generateNode()
4745
{
4846
auto node_options = rclcpp::NodeOptions{};
4947

5048
const auto planning_test_utils_dir =
5149
ament_index_cpp::get_package_share_directory("planning_test_utils");
52-
const auto behavior_velocity_planner_dir =
53-
ament_index_cpp::get_package_share_directory("behavior_velocity_planner");
50+
const auto motion_velocity_planner_dir =
51+
ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node");
5452
const auto motion_velocity_smoother_dir =
5553
ament_index_cpp::get_package_share_directory("motion_velocity_smoother");
5654

57-
const auto get_behavior_velocity_module_config = [](const std::string & module) {
58-
const auto package_name = "behavior_velocity_" + module + "_module";
55+
const auto get_motion_velocity_module_config = [](const std::string & module) {
56+
const auto package_name = "autoware_motion_velocity_" + module + "_module";
5957
const auto package_path = ament_index_cpp::get_package_share_directory(package_name);
6058
return package_path + "/config/" + module + ".param.yaml";
6159
};
6260

6361
std::vector<std::string> module_names;
64-
module_names.emplace_back("behavior_velocity_planner::CrosswalkModulePlugin");
65-
module_names.emplace_back("behavior_velocity_planner::WalkwayModulePlugin");
66-
module_names.emplace_back("behavior_velocity_planner::TrafficLightModulePlugin");
67-
module_names.emplace_back("behavior_velocity_planner::IntersectionModulePlugin");
68-
module_names.emplace_back("behavior_velocity_planner::MergeFromPrivateModulePlugin");
69-
module_names.emplace_back("behavior_velocity_planner::BlindSpotModulePlugin");
70-
module_names.emplace_back("behavior_velocity_planner::DetectionAreaModulePlugin");
71-
module_names.emplace_back("behavior_velocity_planner::VirtualTrafficLightModulePlugin");
72-
module_names.emplace_back("behavior_velocity_planner::NoStoppingAreaModulePlugin");
73-
module_names.emplace_back("behavior_velocity_planner::StopLineModulePlugin");
74-
module_names.emplace_back("behavior_velocity_planner::OcclusionSpotModulePlugin");
75-
module_names.emplace_back("behavior_velocity_planner::RunOutModulePlugin");
76-
module_names.emplace_back("behavior_velocity_planner::SpeedBumpModulePlugin");
77-
module_names.emplace_back("behavior_velocity_planner::OutOfLaneModulePlugin");
78-
module_names.emplace_back("behavior_velocity_planner::NoDrivableLaneModulePlugin");
62+
module_names.emplace_back("autoware::motion_velocity_planner::OutOfLaneModule");
7963

8064
std::vector<rclcpp::Parameter> params;
8165
params.emplace_back("launch_modules", module_names);
@@ -89,70 +73,49 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
8973
planning_test_utils_dir + "/config/test_vehicle_info.param.yaml",
9074
motion_velocity_smoother_dir + "/config/default_motion_velocity_smoother.param.yaml",
9175
motion_velocity_smoother_dir + "/config/Analytical.param.yaml",
92-
behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml",
93-
get_behavior_velocity_module_config("blind_spot"),
94-
get_behavior_velocity_module_config("crosswalk"),
95-
get_behavior_velocity_module_config("walkway"),
96-
get_behavior_velocity_module_config("detection_area"),
97-
get_behavior_velocity_module_config("intersection"),
98-
get_behavior_velocity_module_config("no_stopping_area"),
99-
get_behavior_velocity_module_config("occlusion_spot"),
100-
get_behavior_velocity_module_config("run_out"),
101-
get_behavior_velocity_module_config("speed_bump"),
102-
get_behavior_velocity_module_config("stop_line"),
103-
get_behavior_velocity_module_config("traffic_light"),
104-
get_behavior_velocity_module_config("virtual_traffic_light"),
105-
get_behavior_velocity_module_config("out_of_lane"),
106-
get_behavior_velocity_module_config("no_drivable_lane")});
107-
108-
// TODO(Takagi, Isamu): set launch_modules
109-
// TODO(Kyoichi Sugahara) set to true launch_virtual_traffic_light
110-
// TODO(Kyoichi Sugahara) set to true launch_occlusion_spot
111-
// TODO(Kyoichi Sugahara) set to true launch_run_out
112-
// TODO(Kyoichi Sugahara) set to true launch_speed_bump
113-
114-
return std::make_shared<BehaviorVelocityPlannerNode>(node_options);
76+
motion_velocity_planner_dir + "/config/motion_velocity_planner.param.yaml",
77+
get_motion_velocity_module_config("out_of_lane")});
78+
79+
return std::make_shared<MotionVelocityPlannerNode>(node_options);
11580
}
11681

11782
void publishMandatoryTopics(
11883
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
119-
std::shared_ptr<BehaviorVelocityPlannerNode> test_target_node)
84+
std::shared_ptr<MotionVelocityPlannerNode> test_target_node)
12085
{
12186
// publish necessary topics from test_manager
12287
test_manager->publishTF(test_target_node, "/tf");
123-
test_manager->publishAcceleration(test_target_node, "behavior_velocity_planner_node/input/accel");
88+
test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel");
12489
test_manager->publishPredictedObjects(
125-
test_target_node, "behavior_velocity_planner_node/input/dynamic_objects");
90+
test_target_node, "motion_velocity_planner_node/input/dynamic_objects");
12691
test_manager->publishPointCloud(
127-
test_target_node, "behavior_velocity_planner_node/input/no_ground_pointcloud");
92+
test_target_node, "motion_velocity_planner_node/input/no_ground_pointcloud");
12893
test_manager->publishOdometry(
129-
test_target_node, "behavior_velocity_planner_node/input/vehicle_odometry");
130-
test_manager->publishAcceleration(test_target_node, "behavior_velocity_planner_node/input/accel");
131-
test_manager->publishMap(test_target_node, "behavior_velocity_planner_node/input/vector_map");
94+
test_target_node, "motion_velocity_planner_node/input/vehicle_odometry");
95+
test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel");
96+
test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map");
13297
test_manager->publishTrafficSignals(
133-
test_target_node, "behavior_velocity_planner_node/input/traffic_signals");
134-
test_manager->publishMaxVelocity(
135-
test_target_node, "behavior_velocity_planner_node/input/external_velocity_limit_mps");
98+
test_target_node, "motion_velocity_planner_node/input/traffic_signals");
13699
test_manager->publishVirtualTrafficLightState(
137-
test_target_node, "behavior_velocity_planner_node/input/virtual_traffic_light_states");
100+
test_target_node, "motion_velocity_planner_node/input/virtual_traffic_light_states");
138101
test_manager->publishOccupancyGrid(
139-
test_target_node, "behavior_velocity_planner_node/input/occupancy_grid");
102+
test_target_node, "motion_velocity_planner_node/input/occupancy_grid");
140103
}
141104

142-
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID)
105+
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
143106
{
144107
rclcpp::init(0, nullptr);
145108
auto test_manager = generateTestManager();
146109
auto test_target_node = generateNode();
147110

148111
publishMandatoryTopics(test_manager, test_target_node);
149112

150-
// test with nominal path_with_lane_id
151-
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
113+
// test with nominal trajectory
114+
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node));
152115
EXPECT_GE(test_manager->getReceivedTopicNum(), 1);
153116

154-
// test with empty path_with_lane_id
155-
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalPathWithLaneId(test_target_node));
117+
// test with empty trajectory
118+
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalTrajectory(test_target_node));
156119
rclcpp::shutdown();
157120
}
158121

@@ -165,12 +128,12 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
165128
publishMandatoryTopics(test_manager, test_target_node);
166129

167130
// test for normal trajectory
168-
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalPathWithLaneId(test_target_node));
131+
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node));
169132

170-
// make sure behavior_path_planner is running
133+
// make sure motion_velocity_planner is running
171134
EXPECT_GE(test_manager->getReceivedTopicNum(), 1);
172135

173-
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromPathWithLaneId(test_target_node));
136+
ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromTrajectory(test_target_node));
174137

175138
rclcpp::shutdown();
176139
}

0 commit comments

Comments
 (0)