File tree 3 files changed +7
-2
lines changed
planning/behavior_path_avoidance_module
include/behavior_path_avoidance_module
3 files changed +7
-2
lines changed Original file line number Diff line number Diff line change 209
209
max_left_shift_length : 5.0
210
210
max_deviation_from_lane : 0.5 # [m]
211
211
# approve the next shift line after reaching this percentage of the current shift line length.
212
+ # this parameter should be within range of 0.0 to 1.0.
212
213
# this parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear.
213
- # this feature can be disabled by setting this parameter to 0 .0.
214
+ # this feature can be disabled by setting this parameter to 1 .0. (in that case, avoidance module creates return shift as soon as possible.)
214
215
ratio_for_return_shift_approval : 0.5 # [-]
215
216
# avoidance distance parameters
216
217
longitudinal :
Original file line number Diff line number Diff line change @@ -294,7 +294,7 @@ class AvoidanceHelper
294
294
295
295
// keep waiting the other side shift approval until the ego reaches shift length threshold.
296
296
const auto ego_shift_ratio = (current_shift_length - getEgoShift ()) / current_shift_length;
297
- return ego_shift_ratio < parameters_->ratio_for_return_shift_approval ;
297
+ return ego_shift_ratio < parameters_->ratio_for_return_shift_approval + 1e-3 ;
298
298
}
299
299
300
300
bool isShifted () const
Original file line number Diff line number Diff line change @@ -260,6 +260,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
260
260
getOrDeclareParameter<double >(*node, ns + " max_deviation_from_lane" );
261
261
p.ratio_for_return_shift_approval =
262
262
getOrDeclareParameter<double >(*node, ns + " ratio_for_return_shift_approval" );
263
+ if (p.ratio_for_return_shift_approval < 0.0 || p.ratio_for_return_shift_approval > 1.0 ) {
264
+ throw std::domain_error (
265
+ " ratio_for_return_shift_approval should be within range of 0.0 to 1.0" );
266
+ }
263
267
}
264
268
265
269
// avoidance maneuver (longitudinal)
You can’t perform that action at this time.
0 commit comments