Skip to content

Commit

Permalink
refactor(avoidance): rename ununderstandable params
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Jun 27, 2023
1 parent 9053dcf commit 1571e4b
Showing 1 changed file with 13 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 # [-]
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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]
Expand All @@ -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]
Expand Down

0 comments on commit 1571e4b

Please sign in to comment.