@@ -46,7 +46,7 @@ const std::map<std::string, std::string> conversion_map = {
46
46
{" obstacle_cruise_planner" , PlanningBehavior::ROUTE_OBSTACLE},
47
47
{" obstacle_stop_planner" , PlanningBehavior::ROUTE_OBSTACLE},
48
48
{" obstacle_stop" , PlanningBehavior::ROUTE_OBSTACLE},
49
- {" obstacle_slowdown " , PlanningBehavior::ROUTE_OBSTACLE},
49
+ {" obstacle_slow_down " , PlanningBehavior::ROUTE_OBSTACLE},
50
50
{" obstacle_cruise" , PlanningBehavior::ROUTE_OBSTACLE},
51
51
{" motion_velocity_planner" , PlanningBehavior::ROUTE_OBSTACLE},
52
52
{" walkway" , PlanningBehavior::SIDEWALK},
@@ -222,7 +222,7 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning
222
222
" /planning/planning_factors/obstacle_stop_planner" ,
223
223
" /planning/planning_factors/obstacle_stop" ,
224
224
" /planning/planning_factors/obstacle_cruise" ,
225
- " /planning/planning_factors/obstacle_slowdown " ,
225
+ " /planning/planning_factors/obstacle_slow_down " ,
226
226
" /planning/planning_factors/occlusion_spot" ,
227
227
" /planning/planning_factors/run_out" ,
228
228
" /planning/planning_factors/stop_line" ,
0 commit comments