From 12d621aa4348cc2b275ff1f2c6068df317cae7b2 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 18 Nov 2024 13:34:57 +0900 Subject: [PATCH] feat(behavior_velocity_planner): update velocity factor initialization Update the initialization of the velocity factor in the RunOutModule of the behavior_velocity_planner. The velocity factor is now initialized for the RUN_OUT behavior instead of the ROUTE_OBSTACLE behavior. Signed-off-by: Kyoichi Sugahara --- .../autoware_behavior_velocity_run_out_module/src/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 2296655d700d..c3f91d050638 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -50,7 +50,7 @@ RunOutModule::RunOutModule( debug_ptr_(debug_ptr), state_machine_(std::make_unique(planner_param.approaching.state)) { - velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_.init(PlanningBehavior::RUN_OUT); if (planner_param.run_out.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr();