From a2d1b98032831d825b616ba3549dc00d09f1de4e Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Thu, 3 Oct 2024 21:36:44 +0900 Subject: [PATCH] config 3: avoidance at high speed between incoming NPCs Signed-off-by: Maxime CLEMENT --- .../scenario_planning/common/common.param.yaml | 2 +- .../static_obstacle_avoidance.param.yaml | 18 +++++++++--------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml index 4edbbf2d35..6ccb223f76 100644 --- a/autoware_launch/config/planning/scenario_planning/common/common.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/common/common.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - max_vel: 4.17 # max velocity limit [m/s] + max_vel: 14.17 # max velocity limit [m/s] # constraints param for normal driving normal: diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml index 111f62ba12..94ae3bf305 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml @@ -10,7 +10,7 @@ # "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object. # "same_direction_lane" : this module uses same direction lane to avoid object if need. # "opposite_direction_lane": this module uses both same direction and opposite direction lane. - use_lane_type: "current_lane" + use_lane_type: "opposite_direction_lane" # drivable area setting use_intersection_areas: true use_hatched_road_markings: true @@ -23,9 +23,9 @@ th_moving_time: 2.0 # [s] longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.2 # [m] - hard_margin_for_parked_vehicle: 0.2 # [m] + soft_margin: 1.0 # [m] + hard_margin: 0.7 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER th_error_eclipse_long_radius : 0.6 # [m] @@ -176,7 +176,7 @@ safety_check: # safety check target type target_type: - car: true # [-] + car: false # [-] truck: true # [-] bus: true # [-] trailer: true # [-] @@ -291,10 +291,10 @@ constraints: # lateral constraints lateral: - velocity: [1.39, 4.17, 11.1] # [m/s] - max_accel_values: [0.5, 0.5, 0.5] # [m/ss] - min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] + velocity: [1.39, 4.17, 11.1, 15.0] # [m/s] + max_accel_values: [0.5, 0.5, 0.5, 2.0] # [m/ss] + min_jerk_values: [0.2, 0.2, 0.2, 0.0] # [m/sss] + max_jerk_values: [1.0, 1.0, 1.0, 2.0] # [m/sss] # longitudinal constraints longitudinal: