15
15
#include " node.hpp"
16
16
17
17
#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>
20
20
21
21
#include < gtest/gtest.h>
22
22
23
- #include < cmath>
24
23
#include < vector>
25
24
26
- using behavior_velocity_planner::BehaviorVelocityPlannerNode ;
25
+ using autoware::motion_velocity_planner::MotionVelocityPlannerNode ;
27
26
using planning_test_utils::PlanningInterfaceTestManager;
28
27
29
28
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager ()
30
29
{
31
30
auto test_manager = std::make_shared<PlanningInterfaceTestManager>();
32
31
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 " );
35
34
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" );
39
37
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" );
42
40
43
41
return test_manager;
44
42
}
45
43
46
- std::shared_ptr<BehaviorVelocityPlannerNode > generateNode ()
44
+ std::shared_ptr<MotionVelocityPlannerNode > generateNode ()
47
45
{
48
46
auto node_options = rclcpp::NodeOptions{};
49
47
50
48
const auto planning_test_utils_dir =
51
49
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 " );
54
52
const auto motion_velocity_smoother_dir =
55
53
ament_index_cpp::get_package_share_directory (" motion_velocity_smoother" );
56
54
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" ;
59
57
const auto package_path = ament_index_cpp::get_package_share_directory (package_name);
60
58
return package_path + " /config/" + module + " .param.yaml" ;
61
59
};
62
60
63
61
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" );
79
63
80
64
std::vector<rclcpp::Parameter> params;
81
65
params.emplace_back (" launch_modules" , module_names);
@@ -89,70 +73,49 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
89
73
planning_test_utils_dir + " /config/test_vehicle_info.param.yaml" ,
90
74
motion_velocity_smoother_dir + " /config/default_motion_velocity_smoother.param.yaml" ,
91
75
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);
115
80
}
116
81
117
82
void publishMandatoryTopics (
118
83
std::shared_ptr<PlanningInterfaceTestManager> test_manager,
119
- std::shared_ptr<BehaviorVelocityPlannerNode > test_target_node)
84
+ std::shared_ptr<MotionVelocityPlannerNode > test_target_node)
120
85
{
121
86
// publish necessary topics from test_manager
122
87
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" );
124
89
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" );
126
91
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" );
128
93
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" );
132
97
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" );
136
99
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" );
138
101
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" );
140
103
}
141
104
142
- TEST (PlanningModuleInterfaceTest, NodeTestWithExceptionPathWithLaneID )
105
+ TEST (PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory )
143
106
{
144
107
rclcpp::init (0 , nullptr );
145
108
auto test_manager = generateTestManager ();
146
109
auto test_target_node = generateNode ();
147
110
148
111
publishMandatoryTopics (test_manager, test_target_node);
149
112
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));
152
115
EXPECT_GE (test_manager->getReceivedTopicNum (), 1 );
153
116
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));
156
119
rclcpp::shutdown ();
157
120
}
158
121
@@ -165,12 +128,12 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
165
128
publishMandatoryTopics (test_manager, test_target_node);
166
129
167
130
// 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));
169
132
170
- // make sure behavior_path_planner is running
133
+ // make sure motion_velocity_planner is running
171
134
EXPECT_GE (test_manager->getReceivedTopicNum (), 1 );
172
135
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));
174
137
175
138
rclcpp::shutdown ();
176
139
}
0 commit comments