From 973bcb9261227aeb57f6b7cb3ab2283eb9faca36 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 5 Mar 2025 10:19:48 +0900 Subject: [PATCH 1/2] support cruise planner's factor Signed-off-by: Kento Yabuuchi --- system/autoware_default_adapi/src/planning.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 98f1c846d202e..25e33f424bcb3 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_slowdown", 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_slowdown", "/planning/planning_factors/occlusion_spot", "/planning/planning_factors/run_out", "/planning/planning_factors/stop_line", From 78f1ef930905e0b73918e03c43cd0cb6f1653bc4 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Wed, 5 Mar 2025 10:33:16 +0900 Subject: [PATCH 2/2] not slowdown but slow_down Signed-off-by: Kento Yabuuchi --- system/autoware_default_adapi/src/planning.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 25e33f424bcb3..cbc254a6e522c 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -46,7 +46,7 @@ const std::map conversion_map = { {"obstacle_cruise_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"obstacle_stop_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"obstacle_stop", PlanningBehavior::ROUTE_OBSTACLE}, - {"obstacle_slowdown", PlanningBehavior::ROUTE_OBSTACLE}, + {"obstacle_slow_down", PlanningBehavior::ROUTE_OBSTACLE}, {"obstacle_cruise", PlanningBehavior::ROUTE_OBSTACLE}, {"motion_velocity_planner", PlanningBehavior::ROUTE_OBSTACLE}, {"walkway", PlanningBehavior::SIDEWALK}, @@ -222,7 +222,7 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/planning_factors/obstacle_stop_planner", "/planning/planning_factors/obstacle_stop", "/planning/planning_factors/obstacle_cruise", - "/planning/planning_factors/obstacle_slowdown", + "/planning/planning_factors/obstacle_slow_down", "/planning/planning_factors/occlusion_spot", "/planning/planning_factors/run_out", "/planning/planning_factors/stop_line",