@@ -657,7 +657,6 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif
657
657
break ;
658
658
}
659
659
case AvoidanceState::YIELD: {
660
- insertYieldVelocity (path);
661
660
insertWaitPoint (isBestEffort (parameters_->policy_deceleration ), path);
662
661
break ;
663
662
}
@@ -1570,24 +1569,6 @@ void AvoidanceModule::insertStopPoint(
1570
1569
getEgoPosition (), stop_distance - MARGIN, 0.0 , shifted_path.path , stop_pose_);
1571
1570
}
1572
1571
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
-
1591
1572
void AvoidanceModule::insertPrepareVelocity (ShiftedPath & shifted_path) const
1592
1573
{
1593
1574
const auto & data = avoid_data_;
@@ -1607,34 +1588,54 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const
1607
1588
return ;
1608
1589
}
1609
1590
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
+ }
1611
1611
1612
1612
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;
1614
1614
if (!enough_space) {
1615
1615
return ;
1616
1616
}
1617
1617
1618
1618
// calculate shift length for front object.
1619
1619
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 );
1621
1621
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);
1626
1627
1627
1628
// check slow down feasibility
1628
1629
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 ;
1630
1631
const auto remaining_distance = distance_to_object - min_avoid_distance;
1631
1632
const auto decel_distance = helper_->getFeasibleDecelDistance (parameters_->velocity_map .front ());
1632
1633
if (remaining_distance < decel_distance) {
1633
1634
return ;
1634
1635
}
1635
1636
1636
1637
// 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 ;
1638
1639
1639
1640
// insert slow down speed.
1640
1641
const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk (
0 commit comments