Skip to content

Commit 5b597a7

Browse files
committed
fix(avoidance): the module ignored merging objects unexpectedly (autowarefoundation#6601)
* feat(avoidance): output overhang lanelet Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): avoid merging vehicle if it's NOT on ego lane. Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): add flag to identify ambiguous vehicle Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(avoidance): add helper function Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * refactor(avoidance): rename param Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(avoidance): update comment Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent aad79a4 commit 5b597a7

File tree

9 files changed

+96
-60
lines changed

9 files changed

+96
-60
lines changed

planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
132132
}
133133

134134
{
135-
const std::string ns = "avoidance.target_filtering.force_avoidance.";
135+
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
136136
p.enable_force_avoidance_for_stopped_vehicle =
137137
getOrDeclareParameter<bool>(*node, ns + "enable");
138138
p.threshold_time_force_avoidance_for_stopped_vehicle =

planning/behavior_path_avoidance_module/config/avoidance.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,7 @@
154154
backward_distance: 10.0 # [m]
155155

156156
# params for avoidance of vehicle type objects that are ambiguous as to whether they are parked.
157-
force_avoidance:
157+
avoidance_for_ambiguous_vehicle:
158158
enable: false # [-]
159159
time_threshold: 1.0 # [s]
160160
distance_threshold: 1.0 # [m]

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+8-1
Original file line numberDiff line numberDiff line change
@@ -381,7 +381,8 @@ struct ObjectData // avoidance target
381381
rclcpp::Time last_move;
382382
double stop_time{0.0};
383383

384-
// store the information of the lanelet which the object's overhang is currently occupying
384+
// It is one of the ego driving lanelets (closest lanelet to the object) and used in the logic to
385+
// check whether the object is on the ego lane.
385386
lanelet::ConstLanelet overhang_lanelet;
386387

387388
// the position at the detected moment
@@ -417,6 +418,12 @@ struct ObjectData // avoidance target
417418
// is parked vehicle on road shoulder
418419
bool is_parked{false};
419420

421+
// is driving on ego current lane
422+
bool is_on_ego_lane{false};
423+
424+
// is ambiguous stopped vehicle.
425+
bool is_ambiguous{false};
426+
420427
// object direction.
421428
Direction direction{Direction::NONE};
422429

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp

+19
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "behavior_path_avoidance_module/data_structs.hpp"
1919
#include "behavior_path_avoidance_module/utils.hpp"
20+
#include "behavior_path_planner_common/utils/utils.hpp"
2021

2122
#include <motion_utils/distance/distance.hpp>
2223

@@ -134,6 +135,24 @@ class AvoidanceHelper
134135
shift_length, getLateralMaxJerkLimit(), getAvoidanceEgoSpeed());
135136
}
136137

138+
double getFrontConstantDistance(const ObjectData & object) const
139+
{
140+
const auto object_type = utils::getHighestProbLabel(object.object.classification);
141+
const auto object_parameter = parameters_->object_parameters.at(object_type);
142+
const auto & additional_buffer_longitudinal =
143+
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
144+
: 0.0;
145+
return object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal;
146+
}
147+
148+
double getRearConstantDistance(const ObjectData & object) const
149+
{
150+
const auto object_type = utils::getHighestProbLabel(object.object.classification);
151+
const auto object_parameter = parameters_->object_parameters.at(object_type);
152+
return object_parameter.safety_buffer_longitudinal + data_->parameters.base_link2rear +
153+
object.length;
154+
}
155+
137156
double getEgoShift() const
138157
{
139158
validate();

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node)
137137
}
138138

139139
{
140-
const std::string ns = "avoidance.target_filtering.force_avoidance.";
140+
const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle.";
141141
p.enable_force_avoidance_for_stopped_vehicle =
142142
getOrDeclareParameter<bool>(*node, ns + "enable");
143143
p.threshold_time_force_avoidance_for_stopped_vehicle =

planning/behavior_path_avoidance_module/src/debug.cpp

+23-2
Original file line numberDiff line numberDiff line change
@@ -188,10 +188,25 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st
188188
return msg;
189189
}
190190

191+
MarkerArray createOverhangLaneletMarkerArray(const ObjectDataArray & objects, std::string && ns)
192+
{
193+
MarkerArray msg;
194+
msg.markers.reserve(objects.size());
195+
196+
for (const auto & object : objects) {
197+
appendMarkerArray(
198+
marker_utils::createLaneletsAreaMarkerArray(
199+
{object.overhang_lanelet}, std::string(ns), 0.0, 0.0, 1.0),
200+
&msg);
201+
}
202+
203+
return msg;
204+
}
205+
191206
MarkerArray avoidableObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns)
192207
{
193208
MarkerArray msg;
194-
msg.markers.reserve(objects.size() * 4);
209+
msg.markers.reserve(objects.size() * 5);
195210

196211
appendMarkerArray(
197212
createObjectsCubeMarkerArray(
@@ -202,14 +217,15 @@ MarkerArray avoidableObjectsMarkerArray(const ObjectDataArray & objects, std::st
202217
appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg);
203218
appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg);
204219
appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg);
220+
appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg);
205221

206222
return msg;
207223
}
208224

209225
MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std::string && ns)
210226
{
211227
MarkerArray msg;
212-
msg.markers.reserve(objects.size() * 4);
228+
msg.markers.reserve(objects.size() * 5);
213229

214230
appendMarkerArray(
215231
createObjectsCubeMarkerArray(
@@ -220,6 +236,7 @@ MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std::
220236
appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg);
221237
appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg);
222238
appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg);
239+
appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg);
223240

224241
return msg;
225242
}
@@ -451,6 +468,10 @@ MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const
451468
appendMarkerArray(
452469
createObjectInfoMarkerArray(filtered_objects, "others_" + convertToSnakeCase(ns) + "_info"),
453470
&msg);
471+
appendMarkerArray(
472+
createOverhangLaneletMarkerArray(
473+
filtered_objects, "others_" + convertToSnakeCase(ns) + "_overhang_lanelet"),
474+
&msg);
454475

455476
return msg;
456477
}

planning/behavior_path_avoidance_module/src/scene.cpp

+11-18
Original file line numberDiff line numberDiff line change
@@ -629,21 +629,16 @@ void AvoidanceModule::fillDebugData(
629629
const auto o_front = data.stop_target_object.value();
630630
const auto object_type = utils::getHighestProbLabel(o_front.object.classification);
631631
const auto object_parameter = parameters_->object_parameters.at(object_type);
632-
const auto & additional_buffer_longitudinal =
633-
object_parameter.use_conservative_buffer_longitudinal
634-
? planner_data_->parameters.base_link2front
635-
: 0.0;
632+
const auto constant_distance = helper_->getFrontConstantDistance(o_front);
636633
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
637634

638635
const auto max_avoid_margin = object_parameter.lateral_hard_margin * o_front.distance_factor +
639636
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
640637

641-
const auto variable = helper_->getSharpAvoidanceDistance(
638+
const auto avoidance_distance = helper_->getSharpAvoidanceDistance(
642639
helper_->getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin));
643-
const auto constant = helper_->getNominalPrepareDistance() +
644-
object_parameter.safety_buffer_longitudinal +
645-
additional_buffer_longitudinal;
646-
const auto total_avoid_distance = variable + constant;
640+
const auto prepare_distance = helper_->getNominalPrepareDistance();
641+
const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance;
647642

648643
dead_pose_ = calcLongitudinalOffsetPose(
649644
data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance);
@@ -1409,16 +1404,14 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const
14091404

14101405
const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor +
14111406
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
1412-
const auto variable = helper_->getMinAvoidanceDistance(
1407+
const auto avoidance_distance = helper_->getMinAvoidanceDistance(
14131408
helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin));
1414-
const auto & additional_buffer_longitudinal =
1415-
object_parameter.use_conservative_buffer_longitudinal
1416-
? planner_data_->parameters.base_link2front
1417-
: 0.0;
1418-
const auto constant = p->min_prepare_distance + object_parameter.safety_buffer_longitudinal +
1419-
additional_buffer_longitudinal + p->stop_buffer;
1420-
1421-
return object.longitudinal - std::min(variable + constant, p->stop_max_distance);
1409+
const auto constant_distance = helper_->getFrontConstantDistance(object);
1410+
1411+
return object.longitudinal -
1412+
std::min(
1413+
avoidance_distance + constant_distance + p->min_prepare_distance + p->stop_buffer,
1414+
p->stop_max_distance);
14221415
}
14231416

14241417
void AvoidanceModule::insertReturnDeadLine(

planning/behavior_path_avoidance_module/src/shift_line_generator.cpp

+9-20
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,6 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
123123
{
124124
// To be consistent with changes in the ego position, the current shift length is considered.
125125
const auto current_ego_shift = helper_->getEgoShift();
126-
const auto & base_link2rear = data_->parameters.base_link2rear;
127126

128127
// Calculate feasible shift length
129128
const auto get_shift_profile =
@@ -140,13 +139,10 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
140139

141140
// calculate remaining distance.
142141
const auto prepare_distance = helper_->getNominalPrepareDistance();
143-
const auto & additional_buffer_longitudinal =
144-
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
145-
: 0.0;
146-
const auto constant = object_parameter.safety_buffer_longitudinal +
147-
additional_buffer_longitudinal + prepare_distance;
148-
const auto has_enough_distance = object.longitudinal > constant + nominal_avoid_distance;
149-
const auto remaining_distance = object.longitudinal - constant;
142+
const auto constant_distance = helper_->getFrontConstantDistance(object);
143+
const auto has_enough_distance =
144+
object.longitudinal > constant_distance + prepare_distance + nominal_avoid_distance;
145+
const auto remaining_distance = object.longitudinal - constant_distance - prepare_distance;
150146
const auto avoidance_distance =
151147
has_enough_distance ? nominal_avoid_distance : remaining_distance;
152148

@@ -278,11 +274,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
278274
}
279275
}
280276

281-
// use each object param
282-
const auto object_type = utils::getHighestProbLabel(o.object.classification);
283-
const auto object_parameter = parameters_->object_parameters.at(object_type);
277+
// calculate feasible shift length based on behavior policy
284278
const auto feasible_shift_profile = get_shift_profile(o, desire_shift_length);
285-
286279
if (!feasible_shift_profile.has_value()) {
287280
if (o.avoid_required && is_forward_object(o)) {
288281
break;
@@ -297,12 +290,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
297290

298291
AvoidLine al_avoid;
299292
{
300-
const auto & additional_buffer_longitudinal =
301-
object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front
302-
: 0.0;
303-
const auto offset =
304-
object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal;
305-
const auto to_shift_end = o.longitudinal - offset;
293+
const auto constant_distance = helper_->getFrontConstantDistance(o);
294+
const auto to_shift_end = o.longitudinal - constant_distance;
306295
const auto path_front_to_ego = data.arclength_from_ego.at(data.ego_closest_path_index);
307296

308297
// start point (use previous linear shift length as start shift length.)
@@ -338,8 +327,8 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
338327

339328
AvoidLine al_return;
340329
{
341-
const auto offset = object_parameter.safety_buffer_longitudinal + base_link2rear + o.length;
342-
const auto to_shift_start = o.longitudinal + offset;
330+
const auto constant_distance = helper_->getRearConstantDistance(o);
331+
const auto to_shift_start = o.longitudinal + constant_distance;
343332

344333
// start point
345334
al_return.start_shift_length = feasible_shift_profile.value().first;

planning/behavior_path_avoidance_module/src/utils.cpp

+23-16
Original file line numberDiff line numberDiff line change
@@ -445,6 +445,14 @@ bool isWithinIntersection(
445445
object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon())));
446446
}
447447

448+
bool isOnEgoLane(const ObjectData & object)
449+
{
450+
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
451+
return boost::geometry::within(
452+
lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(),
453+
object.overhang_lanelet.polygon2d().basicPolygon());
454+
}
455+
448456
bool isParallelToEgoLane(const ObjectData & object, const double threshold)
449457
{
450458
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
@@ -492,6 +500,10 @@ bool isParkedVehicle(
492500
using lanelet::utils::to2D;
493501
using lanelet::utils::conversion::toLaneletPoint;
494502

503+
if (object.is_within_intersection) {
504+
return false;
505+
}
506+
495507
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
496508
const auto centerline_pos =
497509
lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object_pos).position;
@@ -580,15 +592,11 @@ bool isParkedVehicle(
580592
return is_left_side_parked_vehicle || is_right_side_parked_vehicle;
581593
}
582594

583-
bool isForceAvoidanceTarget(
595+
bool isAmbiguousStoppedVehicle(
584596
ObjectData & object, const AvoidancePlanningData & data,
585597
const std::shared_ptr<const PlannerData> & planner_data,
586598
const std::shared_ptr<AvoidanceParameters> & parameters)
587599
{
588-
if (!parameters->enable_force_avoidance_for_stopped_vehicle) {
589-
return false;
590-
}
591-
592600
const auto stop_time_longer_than_threshold =
593601
object.stop_time > parameters->threshold_time_force_avoidance_for_stopped_vehicle;
594602

@@ -619,6 +627,10 @@ bool isForceAvoidanceTarget(
619627
return false;
620628
}
621629

630+
if (!object.is_on_ego_lane) {
631+
return true;
632+
}
633+
622634
const auto & ego_pose = planner_data->self_odometry->pose.pose;
623635

624636
// force avoidance for stopped vehicle
@@ -745,24 +757,17 @@ bool isSatisfiedWithVehicleCondition(
745757
const std::shared_ptr<const PlannerData> & planner_data,
746758
const std::shared_ptr<AvoidanceParameters> & parameters)
747759
{
748-
using boost::geometry::within;
749-
using lanelet::utils::to2D;
750-
using lanelet::utils::conversion::toLaneletPoint;
751-
752760
object.behavior = getObjectBehavior(object, parameters);
753-
object.is_within_intersection = isWithinIntersection(object, planner_data->route_handler);
761+
object.is_on_ego_lane = isOnEgoLane(object);
762+
object.is_ambiguous = isAmbiguousStoppedVehicle(object, data, planner_data, parameters);
754763

755764
// from here condition check for vehicle type objects.
756-
if (isForceAvoidanceTarget(object, data, planner_data, parameters)) {
765+
if (object.is_ambiguous && parameters->enable_force_avoidance_for_stopped_vehicle) {
757766
return true;
758767
}
759768

760769
// check vehicle shift ratio
761-
const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position;
762-
const auto on_ego_driving_lane = within(
763-
to2D(toLaneletPoint(object_pos)).basicPoint(),
764-
object.overhang_lanelet.polygon2d().basicPolygon());
765-
if (on_ego_driving_lane) {
770+
if (object.is_on_ego_lane) {
766771
if (object.is_parked) {
767772
return true;
768773
} else {
@@ -1722,6 +1727,8 @@ void filterTargetObjects(
17221727
}
17231728

17241729
if (filtering_utils::isVehicleTypeObject(o)) {
1730+
o.is_within_intersection =
1731+
filtering_utils::isWithinIntersection(o, planner_data->route_handler);
17251732
o.is_parked = filtering_utils::isParkedVehicle(o, planner_data->route_handler, parameters);
17261733
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);
17271734

0 commit comments

Comments
 (0)