Skip to content

Commit

Permalink
feat(avoidance): change lateral margin based on if it's parked vehicle (
Browse files Browse the repository at this point in the history
autowarefoundation#894)

* feat(avoidance): change lateral margin based on if it's parked vehicle

Signed-off-by: satoshi-ota <[email protected]>

* fix(AbLC): update values

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Apr 8, 2024
1 parent afeae6b commit c3bad35
Show file tree
Hide file tree
Showing 2 changed files with 64 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,81 +31,97 @@
execute_num: 1 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 1.0 # [s]
lateral_margin:
soft_margin: 1.0 # [m]
hard_margin: 0.1 # [m]
hard_margin_for_parked_vehicle: 0.1 # [m]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
avoid_margin_lateral: 1.0 # [m]
safety_buffer_lateral: 0.1 # [m]
safety_buffer_longitudinal: 0.0 # [m]
use_conservative_buffer_longitudinal: false # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
truck:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 1.0 # [m]
hard_margin: 0.4 # [m]
hard_margin_for_parked_vehicle: 0.4 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.4
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: false
bus:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.8 # [m]
hard_margin_for_parked_vehicle: 0.8 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: false
trailer:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.8 # [m]
hard_margin_for_parked_vehicle: 0.8 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.8
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: false
unknown:
is_target: false
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 1.0 # [m]
hard_margin: 0.7 # [m]
hard_margin_for_parked_vehicle: 0.7 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: false
bicycle:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: false
motorcycle:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: false
pedestrian:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: false
lower_distance_for_polygon_expansion: 30.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,64 +12,80 @@
moving_time_threshold: 1.0 # [s]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
avoid_margin_lateral: 0.0 # [m]
safety_buffer_lateral: 0.0 # [m]
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
truck:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
bus:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
trailer:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
unknown:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 0.0 # [m]
hard_margin_for_parked_vehicle: 0.0 # [m]
bicycle:
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
motorcycle:
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
pedestrian:
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
lateral_margin:
soft_margin: 0.0 # [m]
hard_margin: 1.0 # [m]
hard_margin_for_parked_vehicle: 1.0 # [m]
lower_distance_for_polygon_expansion: 0.0 # [m]
upper_distance_for_polygon_expansion: 1.0 # [m]

Expand Down

0 comments on commit c3bad35

Please sign in to comment.