From 873e64e34a1d1229abe28a7252e9196e08f12a3f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 10 Jan 2024 14:53:36 +0900 Subject: [PATCH] feat: tune parameters for optimization path planning (#774) * feat: tune parameters for optimization path planning Signed-off-by: Takayuki Murooka * disable warm start Signed-off-by: Takayuki Murooka * Update autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml --------- Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner.param.yaml | 6 +++--- .../path_smoother/elastic_band_smoother.param.yaml | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml index af7de475bd..17a044fb67 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/obstacle_avoidance_planner.param.yaml @@ -31,7 +31,7 @@ max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] # make max_goal_moving_dist long to keep start point fixed for pull over max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] - max_delta_time_sec: 1.0 # threshold of delta time for replan [second] + max_delta_time_sec: 0.0 # threshold of delta time for replan [second] # mpt param mpt: @@ -40,7 +40,7 @@ steer_limit_constraint: false visualize_sampling_num: 1 enable_manual_warm_start: false - enable_warm_start: true + enable_warm_start: false enable_optimization_validation: false common: @@ -62,7 +62,7 @@ # weight parameter for optimization weight: # collision free - soft_collision_free_weight: 1000.0 # soft weight for lateral error around the middle point + soft_collision_free_weight: 1.0 # soft weight for lateral error around the middle point # tracking error lat_error_weight: 1.0 # weight for lateral error diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml index c67d29c418..a9e71368e3 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/path_smoother/elastic_band_smoother.param.yaml @@ -44,4 +44,4 @@ max_ego_moving_dist: 5.0 # threshold of ego's moving distance for replan [m] # make max_goal_moving_dist long to keep start point fixed for pull over max_goal_moving_dist: 15.0 # threshold of goal's moving distance for replan [m] - max_delta_time_sec: 1.0 # threshold of delta time for replan [second] + max_delta_time_sec: 0.0 # threshold of delta time for replan [second]