Skip to content

Commit c0eca40

Browse files
committed
fix(avoidance): don't slow down if avoidance is NOT definitely necessary during unsafe condition
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent ededdcd commit c0eca40

File tree

4 files changed

+29
-44
lines changed

4 files changed

+29
-44
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -213,9 +213,6 @@ struct AvoidanceParameters
213213
size_t hysteresis_factor_safe_count;
214214
double hysteresis_factor_expand_rate{0.0};
215215

216-
// keep target velocity in yield maneuver
217-
double yield_velocity{0.0};
218-
219216
// maximum stop distance
220217
double stop_max_distance{0.0};
221218

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

-6
Original file line numberDiff line numberDiff line change
@@ -282,12 +282,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
282282
getOrDeclareParameter<double>(*node, ns + "traffic_light.buffer");
283283
}
284284

285-
// yield
286-
{
287-
const std::string ns = "avoidance.yield.";
288-
p.yield_velocity = getOrDeclareParameter<double>(*node, ns + "yield_velocity");
289-
}
290-
291285
// stop
292286
{
293287
const std::string ns = "avoidance.stop.";

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

-7
Original file line numberDiff line numberDiff line change
@@ -235,13 +235,6 @@ class AvoidanceModule : public SceneModuleInterface
235235
*/
236236
void insertPrepareVelocity(ShiftedPath & shifted_path) const;
237237

238-
/**
239-
* @brief insert decel point in output path in order to yield. the ego decelerates within
240-
* accel/jerk constraints.
241-
* @param target path.
242-
*/
243-
void insertYieldVelocity(ShiftedPath & shifted_path) const;
244-
245238
/**
246239
* @brief calculate stop distance based on object's overhang.
247240
* @param stop distance.

planning/behavior_path_avoidance_module/src/scene.cpp

+29-28
Original file line numberDiff line numberDiff line change
@@ -657,7 +657,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif
657657
break;
658658
}
659659
case AvoidanceState::YIELD: {
660-
insertYieldVelocity(path);
661660
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
662661
break;
663662
}
@@ -1570,24 +1569,6 @@ void AvoidanceModule::insertStopPoint(
15701569
getEgoPosition(), stop_distance - MARGIN, 0.0, shifted_path.path, stop_pose_);
15711570
}
15721571

1573-
void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const
1574-
{
1575-
const auto & p = parameters_;
1576-
const auto & data = avoid_data_;
1577-
1578-
if (data.target_objects.empty()) {
1579-
return;
1580-
}
1581-
1582-
if (helper_->isShifted()) {
1583-
return;
1584-
}
1585-
1586-
const auto decel_distance = helper_->getFeasibleDecelDistance(p->yield_velocity, false);
1587-
utils::avoidance::insertDecelPoint(
1588-
getEgoPosition(), decel_distance, p->yield_velocity, shifted_path.path, slow_pose_);
1589-
}
1590-
15911572
void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
15921573
{
15931574
const auto & data = avoid_data_;
@@ -1607,34 +1588,54 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
16071588
return;
16081589
}
16091590

1610-
const auto object = data.target_objects.front();
1591+
const auto itr = std::find_if(
1592+
data.target_objects.begin(), data.target_objects.end(),
1593+
[](const auto & o) { return o.avoid_required; });
1594+
1595+
const auto object = [&]() -> std::optional<ObjectData> {
1596+
if (!data.yield_required) {
1597+
return data.target_objects.front();
1598+
}
1599+
1600+
if (itr == data.target_objects.end()) {
1601+
return std::nullopt;
1602+
}
1603+
1604+
return *itr;
1605+
}();
1606+
1607+
// do nothing if it can't avoid at the moment and avoidance is NOT definitely necessary.
1608+
if (!object.has_value()) {
1609+
return;
1610+
}
16111611

16121612
const auto enough_space =
1613-
object.is_avoidable || object.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
1613+
object.value().is_avoidable || object.value().reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
16141614
if (!enough_space) {
16151615
return;
16161616
}
16171617

16181618
// calculate shift length for front object.
16191619
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
1620-
const auto object_type = utils::getHighestProbLabel(object.object.classification);
1620+
const auto object_type = utils::getHighestProbLabel(object.value().object.classification);
16211621
const auto object_parameter = parameters_->object_parameters.at(object_type);
1622-
const auto avoid_margin = object_parameter.safety_buffer_lateral * object.distance_factor +
1623-
object_parameter.avoid_margin_lateral + 0.5 * vehicle_width;
1624-
const auto shift_length =
1625-
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin);
1622+
const auto avoid_margin =
1623+
object_parameter.safety_buffer_lateral * object.value().distance_factor +
1624+
object_parameter.avoid_margin_lateral + 0.5 * vehicle_width;
1625+
const auto shift_length = helper_->getShiftLength(
1626+
object.value(), utils::avoidance::isOnRight(object.value()), avoid_margin);
16261627

16271628
// check slow down feasibility
16281629
const auto min_avoid_distance = helper_->getMinAvoidanceDistance(shift_length);
1629-
const auto distance_to_object = object.longitudinal;
1630+
const auto distance_to_object = object.value().longitudinal;
16301631
const auto remaining_distance = distance_to_object - min_avoid_distance;
16311632
const auto decel_distance = helper_->getFeasibleDecelDistance(parameters_->velocity_map.front());
16321633
if (remaining_distance < decel_distance) {
16331634
return;
16341635
}
16351636

16361637
// decide slow down lower limit.
1637-
const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed;
1638+
const auto lower_speed = object.value().avoid_required ? 0.0 : parameters_->min_slow_down_speed;
16381639

16391640
// insert slow down speed.
16401641
const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk(

0 commit comments

Comments
 (0)