Skip to content

Commit 9602e9a

Browse files
beyzabeyzanurkaya
beyza
authored andcommitted
add necessary parameters
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 84fe16d commit 9602e9a

File tree

1 file changed

+7
-1
lines changed

1 file changed

+7
-1
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,18 @@
11
/**:
22
ros__parameters:
33
dynamic_obstacle_stop: # module to stop or before entering the immediate path of a moving object
4-
extra_object_width: 1.0 # [m] extra width around detected objects
54
minimum_object_velocity: 0.5 # [m/s] objects with a velocity bellow this value are ignored
5+
extra_object_width: 1.0 # [m] extra width around detected objects
6+
extra_object_footprint_width: 0.0 # [m] extra width around detected objects for footprint
67
stop_distance_buffer: 0.5 # [m] extra distance to add between the stop point and the collision point
78
time_horizon: 5.0 # [s] time horizon used for collision checks
9+
yaw_threshold: 2.35 # [rad] yaw threshold used for collision checks
10+
yaw_threshold_behind_object: 0.6 # [rad] yaw threshold used for collision checks for objects behind the ego vehicle
811
hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection
912
add_stop_duration_buffer : 0.5 # [s] duration where a collision must be continuously detected before a stop decision is added
1013
remove_stop_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being remove
1114
minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision
1215
ignore_unavoidable_collisions : true # if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight)
16+
ignore_objects_behind_ego: false # if true, ignore objects that are behind the ego vehicle
17+
behind_object_distance_threshold: 10.0 # [m] distance behind the ego vehicle to ignore objects
18+
use_predicted_path: true # if true, use the predicted path of the object to calculate the collision point

0 commit comments

Comments
 (0)