Skip to content

Commit

Permalink
feat(behavior_velocity_run_out): cherry pick feature improvements (au…
Browse files Browse the repository at this point in the history
…towarefoundation#621)

* feat(run_out): add parameter to decide whether to use the object's velocity (autowarefoundation#704)

Signed-off-by: Tomohito Ando <[email protected]>

* feat(run_out)!: ignore the collision points on crosswalk (autowarefoundation#737)

suppress on crosswalk

Signed-off-by: Yuki Takagi <[email protected]>

---------

Signed-off-by: Tomohito Ando <[email protected]>
Signed-off-by: Yuki Takagi <[email protected]>
Co-authored-by: Yuki TAKAGI <[email protected]>
  • Loading branch information
TomohitoAndo and yuki-takagi-66 authored Apr 12, 2024
1 parent 412ba24 commit 9b488b2
Showing 1 changed file with 12 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
run_out:
detection_method: "Object" # [-] candidate: Object, ObjectWithoutPath, Points
use_partition_lanelet: true # [-] whether to use partition lanelet map data
suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet:
specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates
stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin
passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin
Expand All @@ -21,14 +22,17 @@

# parameter to create abstracted dynamic obstacles
dynamic_obstacle:
use_mandatory_area: false # [-] whether to use mandatory detection area
min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles
max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles
diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points
height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points
max_prediction_time: 10.0 # [sec] create predicted path until this time
time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path
points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method
use_mandatory_area: false # [-] whether to use mandatory detection area
assume_fixed_velocity:
enable: false # [-] If enabled, the obstacle's velocity is assumed to be within the minimum and maximum velocity values specified below
min_vel_kmph: 0.0 # [km/h] minimum velocity for dynamic obstacles
max_vel_kmph: 5.0 # [km/h] maximum velocity for dynamic obstacles
std_dev_multiplier: 1.96 # [-] min and max velocity of the obstacles are calculated from this value and covariance
diameter: 0.1 # [m] diameter of obstacles. used for creating dynamic obstacles from points
height: 2.0 # [m] height of obstacles. used for creating dynamic obstacles from points
max_prediction_time: 10.0 # [sec] create predicted path until this time
time_step: 0.5 # [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path
points_interval: 0.1 # [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method

# approach if ego has stopped in the front of the obstacle for a certain amount of time
approaching:
Expand Down

0 comments on commit 9b488b2

Please sign in to comment.