Skip to content

Commit f1deb04

Browse files
committed
fix(avoidance): rebuild prepare distance calculation/validation logic
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 5c08ea0 commit f1deb04

File tree

3 files changed

+22
-12
lines changed

3 files changed

+22
-12
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+13-4
Original file line numberDiff line numberDiff line change
@@ -97,16 +97,18 @@ class AvoidanceHelper
9797
return std::max(getEgoSpeed(), values.at(idx));
9898
}
9999

100-
double getMinimumPrepareDistance() const
100+
double getNominalPrepareDistance(const double velocity) const
101101
{
102102
const auto & p = parameters_;
103-
return std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance);
103+
const auto & values = p->velocity_map;
104+
const auto idx = getConstraintsMapIndex(velocity, values);
105+
return std::max(values.at(idx) * p->max_prepare_time, p->min_prepare_distance);
104106
}
105107

106108
double getNominalPrepareDistance() const
107109
{
108110
const auto & p = parameters_;
109-
return std::max(getEgoSpeed() * p->max_prepare_time, p->min_prepare_distance);
111+
return std::max(getAvoidanceEgoSpeed() * p->max_prepare_time, p->min_prepare_distance);
110112
}
111113

112114
double getNominalAvoidanceDistance(const double shift_length) const
@@ -298,6 +300,13 @@ class AvoidanceHelper
298300
return std::numeric_limits<double>::max();
299301
}
300302

303+
bool isEnoughPrepareDistance(const double prepare_distance) const
304+
{
305+
const auto & p = parameters_;
306+
return prepare_distance >
307+
std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance);
308+
}
309+
301310
bool isComfortable(const AvoidLineArray & shift_lines) const
302311
{
303312
const auto JERK_BUFFER = 0.1; // [m/sss]
@@ -328,7 +337,7 @@ class AvoidanceHelper
328337
const auto desire_shift_length =
329338
getShiftLength(object, is_object_on_right, object.avoid_margin.value());
330339

331-
const auto prepare_distance = getMinimumPrepareDistance();
340+
const auto prepare_distance = getNominalPrepareDistance(0.0);
332341
const auto constant_distance = getFrontConstantDistance(object);
333342
const auto avoidance_distance = getMinAvoidanceDistance(desire_shift_length);
334343

planning/behavior_path_avoidance_module/src/scene.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -413,9 +413,9 @@ bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const
413413
const auto registered_lines = path_shifter_.getShiftLines();
414414
if (!registered_lines.empty()) {
415415
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);
416-
const auto to_shift_start_point = motion_utils::calcSignedArcLength(
416+
const auto prepare_distance = motion_utils::calcSignedArcLength(
417417
path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx);
418-
if (to_shift_start_point < helper_->getMinimumPrepareDistance()) {
418+
if (!helper_->isEnoughPrepareDistance(prepare_distance)) {
419419
RCLCPP_DEBUG(
420420
getLogger(),
421421
"Distance to shift start point is less than minimum prepare distance. The distance is not "
@@ -1403,10 +1403,11 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const
14031403
const auto avoidance_distance = helper_->getMinAvoidanceDistance(
14041404
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin));
14051405
const auto constant_distance = helper_->getFrontConstantDistance(object);
1406+
const auto prepare_distance = helper_->getNominalPrepareDistance(0.0);
14061407

14071408
return object.longitudinal -
14081409
std::min(
1409-
avoidance_distance + constant_distance + p->min_prepare_distance + p->stop_buffer,
1410+
avoidance_distance + constant_distance + prepare_distance + p->stop_buffer,
14101411
p->stop_max_distance);
14111412
}
14121413

@@ -1435,7 +1436,7 @@ void AvoidanceModule::insertReturnDeadLine(
14351436
const auto buffer = std::max(0.0, to_shifted_path_end - to_reference_path_end);
14361437

14371438
const auto min_return_distance =
1438-
helper_->getMinAvoidanceDistance(shift_length) + helper_->getMinimumPrepareDistance();
1439+
helper_->getMinAvoidanceDistance(shift_length) + helper_->getNominalPrepareDistance(0.0);
14391440
const auto to_stop_line = data.to_return_point - min_return_distance - buffer;
14401441

14411442
// If we don't need to consider deceleration constraints, insert a deceleration point

planning/behavior_path_avoidance_module/src/shift_line_generator.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -935,7 +935,7 @@ void ShiftLineGenerator::applySmallShiftFilter(
935935
continue;
936936
}
937937

938-
if (s.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) {
938+
if (!helper_->isEnoughPrepareDistance(s.start_longitudinal)) {
939939
continue;
940940
}
941941

@@ -1179,13 +1179,13 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine(
11791179
std::max(nominal_prepare_distance - last_sl_distance, 0.0);
11801180

11811181
double prepare_distance_scaled = std::max(
1182-
helper_->getMinimumPrepareDistance(), std::max(nominal_prepare_distance, last_sl_distance));
1182+
helper_->getNominalPrepareDistance(), std::max(nominal_prepare_distance, last_sl_distance));
11831183
double avoid_distance_scaled = nominal_avoid_distance;
11841184
if (remaining_distance < prepare_distance_scaled + avoid_distance_scaled) {
11851185
const auto scale = (remaining_distance - last_sl_distance) /
11861186
std::max(nominal_avoid_distance + variable_prepare_distance, 0.1);
11871187
prepare_distance_scaled = std::max(
1188-
helper_->getMinimumPrepareDistance(), last_sl_distance + scale * nominal_prepare_distance);
1188+
helper_->getNominalPrepareDistance(), last_sl_distance + scale * nominal_prepare_distance);
11891189
avoid_distance_scaled *= scale;
11901190
}
11911191

@@ -1298,7 +1298,7 @@ AvoidLineArray ShiftLineGenerator::findNewShiftLine(
12981298
const auto & candidate = shift_lines.at(i);
12991299

13001300
// prevent sudden steering.
1301-
if (candidate.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) {
1301+
if (!helper_->isEnoughPrepareDistance(candidate.start_longitudinal)) {
13021302
break;
13031303
}
13041304

0 commit comments

Comments
 (0)