Skip to content

Commit

Permalink
feat(avoidance): margin can be set independently for each class (#286)
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Apr 13, 2023
1 parent a0a1d95 commit 9f677fc
Showing 1 changed file with 40 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
detection_area_left_expand_dist: 1.0 # [m]
drivable_area_right_bound_offset: 0.0 # [m]
drivable_area_left_bound_offset: 0.0 # [m]
object_envelope_buffer: 0.3 # [m]

# avoidance module common setting
enable_bound_clipping: false
Expand All @@ -26,14 +25,46 @@

# avoidance is performed for the object type with true
target_object:
car: true
truck: true
bus: true
trailer: true
unknown: false
bicycle: false
motorcycle: false
pedestrian: false
car:
enable: true
envelope_buffer_margin: 0.3
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
truck:
enable: true
envelope_buffer_margin: 0.3
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
bus:
enable: true
envelope_buffer_margin: 0.3
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
trailer:
enable: true
envelope_buffer_margin: 0.3
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
unknown:
enable: false
envelope_buffer_margin: 0.3
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
bicycle:
enable: false
envelope_buffer_margin: 0.8
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
motorcycle:
enable: false
envelope_buffer_margin: 0.8
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
pedestrian:
enable: false
envelope_buffer_margin: 0.8
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0

# For target object filtering
target_filtering:
Expand Down Expand Up @@ -66,7 +97,6 @@
# avoidance lateral parameters
lateral:
lateral_collision_margin: 1.0 # [m]
lateral_collision_safety_buffer: 0.7 # [m]
lateral_passable_safety_buffer: 1.0 # [m]
road_shoulder_safety_margin: 0.3 # [m]
avoidance_execution_lateral_threshold: 0.499
Expand All @@ -75,7 +105,6 @@
# avoidance distance parameters
longitudinal:
prepare_time: 2.0 # [s]
longitudinal_collision_safety_buffer: 0.0 # [m]
min_prepare_distance: 1.0 # [m]
min_avoidance_distance: 10.0 # [m]
min_nominal_avoidance_speed: 7.0 # [m/s]
Expand Down

0 comments on commit 9f677fc

Please sign in to comment.