Skip to content

Commit 8cd2176

Browse files
authored
Merge pull request #1163 from tier4/hotfix/v0.20.2/avoidance
feat(avoidance): wait next shift approval until the ego reaches shift length threshold (autowarefoundation#6501)
2 parents fb3c149 + 3eb0312 commit 8cd2176

File tree

5 files changed

+45
-1
lines changed

5 files changed

+45
-1
lines changed

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+5
Original file line numberDiff line numberDiff line change
@@ -207,6 +207,11 @@
207207
max_right_shift_length: 5.0
208208
max_left_shift_length: 5.0
209209
max_deviation_from_lane: 0.5 # [m]
210+
# approve the next shift line after reaching this percentage of the current shift line length.
211+
# this parameter should be within range of 0.0 to 1.0.
212+
# 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 1.0. (in that case, avoidance module creates return shift as soon as possible.)
214+
ratio_for_return_shift_approval: 0.5 # [-]
210215
# avoidance distance parameters
211216
longitudinal:
212217
min_prepare_time: 1.0 # [s]

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -276,6 +276,9 @@ struct AvoidanceParameters
276276
// use for judge if the ego is shifting or not.
277277
double lateral_avoid_check_threshold{0.0};
278278

279+
// use for return shift approval.
280+
double ratio_for_return_shift_approval{0.0};
281+
279282
// For shift line generation process. The continuous shift length is quantized by this value.
280283
double quantize_filter_threshold{0.0};
281284

@@ -542,6 +545,8 @@ struct AvoidancePlanningData
542545

543546
bool valid{false};
544547

548+
bool ready{false};
549+
545550
bool success{false};
546551

547552
bool comfortable{false};

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+27
Original file line numberDiff line numberDiff line change
@@ -270,6 +270,33 @@ class AvoidanceHelper
270270
});
271271
}
272272

273+
bool isReady(const AvoidLineArray & new_shift_lines, const double current_shift_length) const
274+
{
275+
if (std::abs(current_shift_length) < 1e-3) {
276+
return true;
277+
}
278+
279+
if (new_shift_lines.empty()) {
280+
return true;
281+
}
282+
283+
const auto front_shift_relative_length = new_shift_lines.front().getRelativeLength();
284+
285+
// same direction shift.
286+
if (current_shift_length > 0.0 && front_shift_relative_length > 0.0) {
287+
return true;
288+
}
289+
290+
// same direction shift.
291+
if (current_shift_length < 0.0 && front_shift_relative_length < 0.0) {
292+
return true;
293+
}
294+
295+
// keep waiting the other side shift approval until the ego reaches shift length threshold.
296+
const auto ego_shift_ratio = (current_shift_length - getEgoShift()) / current_shift_length;
297+
return ego_shift_ratio < parameters_->ratio_for_return_shift_approval + 1e-3;
298+
}
299+
273300
bool isShifted() const
274301
{
275302
return std::abs(getEgoShift()) > parameters_->lateral_avoid_check_threshold;

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -256,6 +256,12 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
256256
p.max_left_shift_length = getOrDeclareParameter<double>(*node, ns + "max_left_shift_length");
257257
p.max_deviation_from_lane =
258258
getOrDeclareParameter<double>(*node, ns + "max_deviation_from_lane");
259+
p.ratio_for_return_shift_approval =
260+
getOrDeclareParameter<double>(*node, ns + "ratio_for_return_shift_approval");
261+
if (p.ratio_for_return_shift_approval < 0.0 || p.ratio_for_return_shift_approval > 1.0) {
262+
throw std::domain_error(
263+
"ratio_for_return_shift_approval should be within range of 0.0 to 1.0");
264+
}
259265
}
260266

261267
// avoidance maneuver (longitudinal)

planning/behavior_path_avoidance_module/src/scene.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ bool AvoidanceModule::isExecutionRequested() const
133133
bool AvoidanceModule::isExecutionReady() const
134134
{
135135
DEBUG_PRINT("AVOIDANCE isExecutionReady");
136-
return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid;
136+
return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid && avoid_data_.ready;
137137
}
138138

139139
bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & data) const
@@ -513,6 +513,7 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de
513513
*/
514514
data.comfortable = helper_->isComfortable(data.new_shift_line);
515515
data.safe = isSafePath(data.candidate_path, debug);
516+
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength());
516517
}
517518

518519
void AvoidanceModule::fillEgoStatus(

0 commit comments

Comments
 (0)