Skip to content

Commit f3712af

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 46ac827 commit f3712af

File tree

4 files changed

+27
-43
lines changed

4 files changed

+27
-43
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -216,9 +216,6 @@ struct AvoidanceParameters
216216
size_t hysteresis_factor_safe_count;
217217
double hysteresis_factor_expand_rate{0.0};
218218

219-
// keep target velocity in yield maneuver
220-
double yield_velocity{0.0};
221-
222219
// maximum stop distance
223220
double stop_max_distance{0.0};
224221

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

-6
Original file line numberDiff line numberDiff line change
@@ -292,12 +292,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
292292
getOrDeclareParameter<double>(*node, ns + "traffic_light.buffer");
293293
}
294294

295-
// yield
296-
{
297-
const std::string ns = "avoidance.yield.";
298-
p.yield_velocity = getOrDeclareParameter<double>(*node, ns + "yield_velocity");
299-
}
300-
301295
// stop
302296
{
303297
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
@@ -233,13 +233,6 @@ class AvoidanceModule : public SceneModuleInterface
233233
*/
234234
void insertPrepareVelocity(ShiftedPath & shifted_path) const;
235235

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

planning/behavior_path_avoidance_module/src/scene.cpp

+27-27
Original file line numberDiff line numberDiff line change
@@ -692,7 +692,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif
692692
break;
693693
}
694694
case AvoidanceState::YIELD: {
695-
insertYieldVelocity(path);
696695
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
697696
break;
698697
}
@@ -1611,24 +1610,6 @@ void AvoidanceModule::insertStopPoint(
16111610
getEgoPosition(), stop_distance - MARGIN, 0.0, shifted_path.path, stop_pose_);
16121611
}
16131612

1614-
void AvoidanceModule::insertYieldVelocity(ShiftedPath & shifted_path) const
1615-
{
1616-
const auto & p = parameters_;
1617-
const auto & data = avoid_data_;
1618-
1619-
if (data.target_objects.empty()) {
1620-
return;
1621-
}
1622-
1623-
if (helper_->isShifted()) {
1624-
return;
1625-
}
1626-
1627-
const auto decel_distance = helper_->getFeasibleDecelDistance(p->yield_velocity, false);
1628-
utils::avoidance::insertDecelPoint(
1629-
getEgoPosition(), decel_distance, p->yield_velocity, shifted_path.path, slow_pose_);
1630-
}
1631-
16321613
void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
16331614
{
16341615
const auto & data = avoid_data_;
@@ -1648,34 +1629,53 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
16481629
return;
16491630
}
16501631

1651-
const auto object = data.target_objects.front();
1632+
const auto itr = std::find_if(
1633+
data.target_objects.begin(), data.target_objects.end(),
1634+
[](const auto & o) { return o.avoid_required; });
1635+
1636+
const auto object = [&]() -> std::optional<ObjectData> {
1637+
if (!data.yield_required) {
1638+
return data.target_objects.front();
1639+
}
1640+
1641+
if (itr == data.target_objects.end()) {
1642+
return std::nullopt;
1643+
}
1644+
1645+
return *itr;
1646+
}();
1647+
1648+
// do nothing if it can't avoid at the moment and avoidance is NOT definitely necessary.
1649+
if (!object.has_value()) {
1650+
return;
1651+
}
16521652

16531653
const auto enough_space =
1654-
object.is_avoidable || object.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
1654+
object.value().is_avoidable || object.value().reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
16551655
if (!enough_space) {
16561656
return;
16571657
}
16581658

16591659
// calculate shift length for front object.
16601660
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
1661-
const auto object_type = utils::getHighestProbLabel(object.object.classification);
1661+
const auto object_type = utils::getHighestProbLabel(object.value().object.classification);
16621662
const auto object_parameter = parameters_->object_parameters.at(object_type);
1663-
const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor +
1663+
const auto avoid_margin = object_parameter.lateral_hard_margin * object.value().distance_factor +
16641664
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
1665-
const auto shift_length =
1666-
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin);
1665+
const auto shift_length = helper_->getShiftLength(
1666+
object.value(), utils::avoidance::isOnRight(object.value()), avoid_margin);
16671667

16681668
// check slow down feasibility
16691669
const auto min_avoid_distance = helper_->getMinAvoidanceDistance(shift_length);
1670-
const auto distance_to_object = object.longitudinal;
1670+
const auto distance_to_object = object.value().longitudinal;
16711671
const auto remaining_distance = distance_to_object - min_avoid_distance;
16721672
const auto decel_distance = helper_->getFeasibleDecelDistance(parameters_->velocity_map.front());
16731673
if (remaining_distance < decel_distance) {
16741674
return;
16751675
}
16761676

16771677
// decide slow down lower limit.
1678-
const auto lower_speed = object.avoid_required ? 0.0 : parameters_->min_slow_down_speed;
1678+
const auto lower_speed = object.value().avoid_required ? 0.0 : parameters_->min_slow_down_speed;
16791679

16801680
// insert slow down speed.
16811681
const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk(

0 commit comments

Comments
 (0)