From 1571e4bbf3205210b5071ed460d4bdb3704ed62e Mon Sep 17 00:00:00 2001 From: satoshi-ota Date: Tue, 27 Jun 2023 10:37:28 +0900 Subject: [PATCH] refactor(avoidance): rename ununderstandable params Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 27 +++++++++---------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 437424838d..a1a864327d 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -28,7 +28,7 @@ # avoidance is performed for the object type with true target_object: car: - enable: true # [-] + is_target: true # [-] moving_speed_threshold: 1.0 # [m/s] moving_time_threshold: 1.0 # [s] max_expand_ratio: 0.0 # [-] @@ -37,7 +37,7 @@ safety_buffer_lateral: 0.7 # [m] safety_buffer_longitudinal: 0.0 # [m] truck: - enable: true + is_target: true moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -46,7 +46,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bus: - enable: true + is_target: true moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -55,7 +55,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 trailer: - enable: true + is_target: true moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -64,7 +64,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 unknown: - enable: true + is_target: true moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -73,7 +73,7 @@ safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bicycle: - enable: true + is_target: true moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -82,7 +82,7 @@ safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 motorcycle: - enable: true + is_target: true moving_speed_threshold: 1.0 # 3.6km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -91,7 +91,7 @@ safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 pedestrian: - enable: true + is_target: true moving_speed_threshold: 0.28 # 1.0km/h moving_time_threshold: 1.0 max_expand_ratio: 0.0 @@ -104,12 +104,12 @@ # For target object filtering target_filtering: - # filtering moving objects - threshold_time_force_avoidance_for_stopped_vehicle: 10.0 # [s] + # params for avoidance of not-parked objects + threshold_time_force_avoidance_for_stopped_vehicle: 10.0 # [s] + object_ignore_section_traffic_light_in_front_distance: 30.0 # [m] + object_ignore_section_crosswalk_in_front_distance: 30.0 # [m] + object_ignore_section_crosswalk_behind_distance: 30.0 # [m] # detection range - object_ignore_distance_traffic_light: 30.0 # [m] - object_ignore_distance_crosswalk_forward: 30.0 # [m] - object_ignore_distance_crosswalk_backward: 30.0 # [m] object_check_forward_distance: 150.0 # [m] object_check_backward_distance: 10.0 # [m] object_check_goal_distance: 20.0 # [m] @@ -132,7 +132,6 @@ avoidance: # avoidance lateral parameters lateral: - lateral_collision_margin: 1.0 # [m] lateral_execution_threshold: 0.499 # [m] lateral_small_shift_threshold: 0.101 # [m] road_shoulder_safety_margin: 0.3 # [m]