forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathavoidance.param.yaml
301 lines (285 loc) · 14.2 KB
/
avoidance.param.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
# see AvoidanceParameters description in avoidance_module_data.hpp for description.
/**:
ros__parameters:
avoidance:
resample_interval_for_planning: 0.3 # [m]
resample_interval_for_output: 4.0 # [m]
drivable_area_right_bound_offset: 0.0 # [m]
drivable_area_left_bound_offset: 0.0 # [m]
# avoidance module common setting
enable_bound_clipping: false
enable_cancel_maneuver: true
disable_path_update: false
# drivable area setting
use_adjacent_lane: true
use_opposite_lane: true
use_intersection_areas: true
use_hatched_road_markings: true
use_freespace_areas: true
# for debug
publish_debug_marker: false
print_debug_info: false
# avoidance is performed for the object type with true
target_object:
car:
execute_num: 1 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 2.0 # [s]
lateral_margin:
soft_margin: 0.7 # [m]
hard_margin: 0.3 # [m]
hard_margin_for_parked_vehicle: 0.3 # [m]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.5 # [m]
safety_buffer_longitudinal: 0.0 # [m]
use_conservative_buffer_longitudinal: true # [-] 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: 2.0
lateral_margin:
soft_margin: 0.9 # [m]
hard_margin: 0.1 # [m]
hard_margin_for_parked_vehicle: 0.1 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
bus:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 2.0
lateral_margin:
soft_margin: 0.9 # [m]
hard_margin: 0.1 # [m]
hard_margin_for_parked_vehicle: 0.1 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
trailer:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 2.0
lateral_margin:
soft_margin: 0.9 # [m]
hard_margin: 0.1 # [m]
hard_margin_for_parked_vehicle: 0.1 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
unknown:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.7 # [m]
hard_margin: -0.2 # [m]
hard_margin_for_parked_vehicle: -0.2 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.1
safety_buffer_longitudinal: 0.0
use_conservative_buffer_longitudinal: true
bicycle:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.7 # [m]
hard_margin: 0.5 # [m]
hard_margin_for_parked_vehicle: 0.5 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
motorcycle:
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.7 # [m]
hard_margin: 0.3 # [m]
hard_margin_for_parked_vehicle: 0.3 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
pedestrian:
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
lateral_margin:
soft_margin: 0.7 # [m]
hard_margin: 0.5 # [m]
hard_margin_for_parked_vehicle: 0.5 # [m]
max_expand_ratio: 0.0
envelope_buffer_margin: 0.5
safety_buffer_longitudinal: 1.0
use_conservative_buffer_longitudinal: true
lower_distance_for_polygon_expansion: 30.0 # [m]
upper_distance_for_polygon_expansion: 100.0 # [m]
# For target object filtering
target_filtering:
# avoidance target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: true # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# detection range
object_check_goal_distance: 20.0 # [m]
object_check_return_pose_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
object_check_shiftable_ratio: 0.6 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]
# lost object compensation
object_last_seen_threshold: 2.0
# detection area generation parameters
detection_area:
static: false # [-]
min_forward_distance: 50.0 # [m]
max_forward_distance: 150.0 # [m]
backward_distance: 10.0 # [m]
# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
avoidance_for_ambiguous_vehicle:
enable: false # [-]
closest_distance_to_wait_and_see: 10.0 # [m]
condition:
time_threshold: 1.0 # [s]
distance_threshold: 1.0 # [m]
ignore_area:
traffic_light:
front_distance: 100.0 # [m]
crosswalk:
front_distance: 30.0 # [m]
behind_distance: 30.0 # [m]
# params for filtering objects that are in intersection
intersection:
yaw_deviation: 0.349 # [rad] (default 20.0deg)
# For safety check
safety_check:
# safety check target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: false # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# safety check configuration
enable: true # [-]
check_current_lane: false # [-]
check_shift_side_lane: true # [-]
check_other_side_lane: false # [-]
check_unavoidable_object: false # [-]
check_other_object: true # [-]
# collision check parameters
check_all_predicted_path: false # [-]
safety_check_backward_distance: 100.0 # [m]
hysteresis_factor_expand_rate: 1.5 # [-]
hysteresis_factor_safe_count: 10 # [-]
# predicted path parameters
min_velocity: 1.38 # [m/s]
max_velocity: 50.0 # [m/s]
time_resolution: 0.5 # [s]
time_horizon_for_front_object: 3.0 # [s]
time_horizon_for_rear_object: 10.0 # [s]
delay_until_departure: 0.0 # [s]
# rss parameters
expected_front_deceleration: -1.0 # [m/ss]
expected_rear_deceleration: -1.0 # [m/ss]
rear_vehicle_reaction_time: 2.0 # [s]
rear_vehicle_safety_time_margin: 1.0 # [s]
lateral_distance_max_threshold: 0.75 # [m]
longitudinal_distance_min_threshold: 3.0 # [m]
longitudinal_velocity_delta_time: 0.8 # [s]
# For avoidance maneuver
avoidance:
# avoidance lateral parameters
lateral:
lateral_execution_threshold: 0.09 # [m]
lateral_small_shift_threshold: 0.101 # [m]
lateral_avoid_check_threshold: 0.1 # [m]
soft_road_shoulder_margin: 0.3 # [m]
hard_road_shoulder_margin: 0.3 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
max_deviation_from_lane: 0.5 # [m]
# approve the next shift line after reaching this percentage of the current shift line length.
# this parameter should be within range of 0.0 to 1.0.
# this parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear.
# this feature can be disabled by setting this parameter to 1.0. (in that case, avoidance module creates return shift as soon as possible.)
ratio_for_return_shift_approval: 0.5 # [-]
# avoidance distance parameters
longitudinal:
min_prepare_time: 1.0 # [s]
max_prepare_time: 2.0 # [s]
min_prepare_distance: 1.0 # [m]
min_slow_down_speed: 1.38 # [m/s]
buf_slow_down_speed: 0.56 # [m/s]
nominal_avoidance_speed: 8.33 # [m/s]
# return dead line
return_dead_line:
goal:
enable: true # [-]
buffer: 30.0 # [m]
traffic_light:
enable: true # [-]
buffer: 3.0 # [m]
# For yield maneuver
yield:
enable: true # [-]
enable_during_shifting: false # [-]
# For stop maneuver
stop:
max_distance: 20.0 # [m]
stop_buffer: 1.0 # [m]
policy:
# policy for rtc request. select "per_shift_line" or "per_avoidance_maneuver".
# "per_shift_line": request approval for each shift line.
# "per_avoidance_maneuver": request approval for avoidance maneuver (avoid + return).
make_approval_request: "per_shift_line"
# policy for vehicle slow down behavior. select "best_effort" or "reliable".
# "best_effort": slow down deceleration & jerk are limited by constraints.
# but there is a possibility that the vehicle can't stop in front of the vehicle.
# "reliable": insert stop or slow down point with ignoring decel/jerk constraints.
# make it possible to increase chance to avoid but uncomfortable deceleration maybe happen.
deceleration: "best_effort" # [-]
# policy for avoidance lateral margin. select "best_effort" or "reliable".
# "best_effort": output avoidance path with shorten lateral margin when there is no enough longitudinal
# margin to avoid.
# "reliable": module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid
# with expected lateral margin.
lateral_margin: "best_effort" # [-]
# if true, module doesn't wait deceleration and outputs avoidance path by best effort margin.
use_shorten_margin_immediately: true # [-]
constraints:
# lateral constraints
lateral:
velocity: [1.0, 1.38, 11.1] # [m/s]
max_accel_values: [0.5, 0.5, 0.5] # [m/ss]
min_jerk_values: [0.2, 0.2, 0.2] # [m/sss]
max_jerk_values: [1.0, 1.0, 1.0] # [m/sss]
# longitudinal constraints
longitudinal:
nominal_deceleration: -1.0 # [m/ss]
nominal_jerk: 0.5 # [m/sss]
max_deceleration: -1.5 # [m/ss]
max_jerk: 1.0 # [m/sss]
max_acceleration: 0.5 # [m/ss]
min_velocity_to_limit_max_acceleration: 2.78 # [m/ss]
shift_line_pipeline:
trim:
quantize_filter_threshold: 0.1
same_grad_filter_1_threshold: 0.1
same_grad_filter_2_threshold: 0.2
same_grad_filter_3_threshold: 0.5
sharp_shift_filter_threshold: 0.2