diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 98f1c846d202e..cbc254a6e522c 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -45,6 +45,9 @@ const std::map conversion_map = { {"blind_spot", PlanningBehavior::REAR_CHECK}, {"obstacle_cruise_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"obstacle_stop_planner", PlanningBehavior::ROUTE_OBSTACLE}, + {"obstacle_stop", PlanningBehavior::ROUTE_OBSTACLE}, + {"obstacle_slow_down", PlanningBehavior::ROUTE_OBSTACLE}, + {"obstacle_cruise", PlanningBehavior::ROUTE_OBSTACLE}, {"motion_velocity_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"walkway", PlanningBehavior::SIDEWALK}, {"start_planner", PlanningBehavior::START_PLANNER}, @@ -217,6 +220,9 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/planning_factors/no_stopping_area", "/planning/planning_factors/obstacle_cruise_planner", "/planning/planning_factors/obstacle_stop_planner", + "/planning/planning_factors/obstacle_stop", + "/planning/planning_factors/obstacle_cruise", + "/planning/planning_factors/obstacle_slow_down", "/planning/planning_factors/occlusion_spot", "/planning/planning_factors/run_out", "/planning/planning_factors/stop_line",