Skip to content

Commit 38a377a

Browse files
committed
fix(avoidance): add param validation
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent a96fff6 commit 38a377a

File tree

3 files changed

+7
-2
lines changed

3 files changed

+7
-2
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -209,8 +209,9 @@
209209
max_left_shift_length: 5.0
210210
max_deviation_from_lane: 0.5 # [m]
211211
# 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.
212213
# 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.)
214215
ratio_for_return_shift_approval: 0.5 # [-]
215216
# avoidance distance parameters
216217
longitudinal:

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -294,7 +294,7 @@ class AvoidanceHelper
294294

295295
// keep waiting the other side shift approval until the ego reaches shift length threshold.
296296
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;
298298
}
299299

300300
bool isShifted() const

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -260,6 +260,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
260260
getOrDeclareParameter<double>(*node, ns + "max_deviation_from_lane");
261261
p.ratio_for_return_shift_approval =
262262
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+
}
263267
}
264268

265269
// avoidance maneuver (longitudinal)

0 commit comments

Comments
 (0)