Skip to content

Commit e02dd60

Browse files
committed
feat(avoidance): consider ignore object in avoid margin calculation
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent c732823 commit e02dd60

File tree

6 files changed

+77
-43
lines changed

6 files changed

+77
-43
lines changed

planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp

+4-14
Original file line numberDiff line numberDiff line change
@@ -30,16 +30,6 @@
3030

3131
namespace behavior_path_planner
3232
{
33-
namespace
34-
{
35-
lanelet::BasicLineString3d toLineString3d(const std::vector<Point> & bound)
36-
{
37-
lanelet::BasicLineString3d ret{};
38-
std::for_each(
39-
bound.begin(), bound.end(), [&](const auto & p) { ret.emplace_back(p.x, p.y, p.z); });
40-
return ret;
41-
}
42-
} // namespace
4333
AvoidanceByLaneChange::AvoidanceByLaneChange(
4434
const std::shared_ptr<LaneChangeParameters> & parameters,
4535
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters)
@@ -172,10 +162,10 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData(
172162
// calc drivable bound
173163
const auto shorten_lanes =
174164
utils::cutOverlappedLanes(data.reference_path_rough, data.drivable_lanes);
175-
data.left_bound = toLineString3d(utils::calcBound(
176-
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, true));
177-
data.right_bound = toLineString3d(utils::calcBound(
178-
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, false));
165+
data.left_bound = utils::calcBound(
166+
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, true);
167+
data.right_bound = utils::calcBound(
168+
data.reference_path_rough, planner_data_, shorten_lanes, false, false, false, false);
179169

180170
// get related objects from dynamic_objects, and then separates them as target objects and non
181171
// target objects

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -541,9 +541,9 @@ struct AvoidancePlanningData
541541

542542
std::vector<DrivableLanes> drivable_lanes{};
543543

544-
lanelet::BasicLineString3d right_bound{};
544+
std::vector<Point> right_bound{};
545545

546-
lanelet::BasicLineString3d left_bound{};
546+
std::vector<Point> left_bound{};
547547

548548
bool safe{false};
549549

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -127,6 +127,10 @@ void filterTargetObjects(
127127
const std::shared_ptr<const PlannerData> & planner_data,
128128
const std::shared_ptr<AvoidanceParameters> & parameters);
129129

130+
void updateRoadShoulderDistance(
131+
AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
132+
const std::shared_ptr<AvoidanceParameters> & parameters);
133+
130134
void fillAdditionalInfoFromPoint(const AvoidancePlanningData & data, AvoidLineArray & lines);
131135

132136
void fillAdditionalInfoFromLongitudinal(const AvoidancePlanningData & data, AvoidLine & line);

planning/behavior_path_avoidance_module/src/debug.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -469,7 +469,7 @@ MarkerArray createDrivableBounds(
469469
createMarkerColor(r, g, b, 0.999));
470470

471471
for (const auto & p : data.right_bound) {
472-
marker.points.push_back(createPoint(p.x(), p.y(), p.z()));
472+
marker.points.push_back(p);
473473
}
474474

475475
msg.markers.push_back(marker);
@@ -482,7 +482,7 @@ MarkerArray createDrivableBounds(
482482
createMarkerColor(r, g, b, 0.999));
483483

484484
for (const auto & p : data.left_bound) {
485-
marker.points.push_back(createPoint(p.x(), p.y(), p.z()));
485+
marker.points.push_back(p);
486486
}
487487

488488
msg.markers.push_back(marker);

planning/behavior_path_avoidance_module/src/scene.cpp

+23-10
Original file line numberDiff line numberDiff line change
@@ -234,14 +234,14 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
234234
// calc drivable bound
235235
auto tmp_path = getPreviousModuleOutput().path;
236236
const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes);
237-
data.left_bound = toLineString3d(utils::calcBound(
237+
data.left_bound = utils::calcBound(
238238
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
239239
parameters_->use_hatched_road_markings, parameters_->use_intersection_areas,
240-
parameters_->use_freespace_areas, true));
241-
data.right_bound = toLineString3d(utils::calcBound(
240+
parameters_->use_freespace_areas, true);
241+
data.right_bound = utils::calcBound(
242242
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
243243
parameters_->use_hatched_road_markings, parameters_->use_intersection_areas,
244-
parameters_->use_freespace_areas, false));
244+
parameters_->use_freespace_areas, false);
245245

246246
// reference path
247247
if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
@@ -294,6 +294,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
294294
using utils::avoidance::filterTargetObjects;
295295
using utils::avoidance::getTargetLanelets;
296296
using utils::avoidance::separateObjectsByPath;
297+
using utils::avoidance::updateRoadShoulderDistance;
297298

298299
// Separate dynamic objects based on whether they are inside or outside of the expanded lanelets.
299300
constexpr double MARGIN = 10.0;
@@ -315,6 +316,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
315316

316317
// Filter out the objects to determine the ones to be avoided.
317318
filterTargetObjects(objects, data, forward_detection_range, planner_data_, parameters_);
319+
updateRoadShoulderDistance(data, planner_data_, parameters_);
318320

319321
// Calculate the distance needed to safely decelerate the ego vehicle to a stop line.
320322
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
@@ -929,10 +931,6 @@ BehaviorModuleOutput AvoidanceModule::plan()
929931
DrivableAreaInfo current_drivable_area_info;
930932
// generate drivable lanes
931933
current_drivable_area_info.drivable_lanes = avoid_data_.drivable_lanes;
932-
// generate obstacle polygons
933-
current_drivable_area_info.obstacles =
934-
utils::avoidance::generateObstaclePolygonsForDrivableArea(
935-
avoid_data_.target_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0);
936934
// expand hatched road markings
937935
current_drivable_area_info.enable_expanding_hatched_road_markings =
938936
parameters_->use_hatched_road_markings;
@@ -941,6 +939,21 @@ BehaviorModuleOutput AvoidanceModule::plan()
941939
parameters_->use_intersection_areas;
942940
// expand freespace areas
943941
current_drivable_area_info.enable_expanding_freespace_areas = parameters_->use_freespace_areas;
942+
// generate obstacle polygons
943+
if (parameters_->enable_bound_clipping) {
944+
ObjectDataArray clip_objects;
945+
// If avoidance is executed by both behavior and motion, only non-avoidable object will be
946+
// extracted from the drivable area.
947+
std::for_each(
948+
data.target_objects.begin(), data.target_objects.end(), [&](const auto & object) {
949+
if (!object.is_avoidable) clip_objects.push_back(object);
950+
});
951+
current_drivable_area_info.obstacles =
952+
utils::avoidance::generateObstaclePolygonsForDrivableArea(
953+
clip_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0);
954+
} else {
955+
current_drivable_area_info.obstacles.clear();
956+
}
944957

945958
output.drivable_area_info = utils::combineDrivableAreaInfo(
946959
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info);
@@ -1150,8 +1163,8 @@ bool AvoidanceModule::isValidShiftLine(
11501163
const size_t end_idx = shift_lines.back().end_idx;
11511164

11521165
const auto path = shifter_for_validate.getReferencePath();
1153-
const auto left_bound = lanelet::utils::to2D(avoid_data_.left_bound);
1154-
const auto right_bound = lanelet::utils::to2D(avoid_data_.right_bound);
1166+
const auto left_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.left_bound));
1167+
const auto right_bound = lanelet::utils::to2D(toLineString3d(avoid_data_.right_bound));
11551168
for (size_t i = start_idx; i <= end_idx; ++i) {
11561169
const auto p = getPoint(path.points.at(i));
11571170
lanelet::BasicPoint2d basic_point{p.x, p.y};

planning/behavior_path_avoidance_module/src/utils.cpp

+42-15
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "behavior_path_avoidance_module/data_structs.hpp"
1818
#include "behavior_path_avoidance_module/utils.hpp"
19+
#include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
1920
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
2021
#include "behavior_path_planner_common/utils/path_utils.hpp"
2122
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
@@ -893,13 +894,8 @@ double getRoadShoulderDistance(
893894

894895
std::vector<Point> intersects;
895896
for (size_t i = 1; i < bound.size(); i++) {
896-
const auto p1_bound =
897-
geometry_msgs::build<Point>().x(bound[i - 1].x()).y(bound[i - 1].y()).z(bound[i - 1].z());
898-
const auto p2_bound =
899-
geometry_msgs::build<Point>().x(bound[i].x()).y(bound[i].y()).z(bound[i].z());
900-
901897
const auto opt_intersect =
902-
tier4_autoware_utils::intersect(p1_object, p2_object, p1_bound, p2_bound);
898+
tier4_autoware_utils::intersect(p1_object, p2_object, bound.at(i - 1), bound.at(i));
903899

904900
if (!opt_intersect) {
905901
continue;
@@ -1184,24 +1180,21 @@ std::vector<DrivableAreaInfo::Obstacle> generateObstaclePolygonsForDrivableArea(
11841180
{
11851181
std::vector<DrivableAreaInfo::Obstacle> obstacles_for_drivable_area;
11861182

1187-
if (objects.empty() || !parameters->enable_bound_clipping) {
1183+
if (objects.empty()) {
11881184
return obstacles_for_drivable_area;
11891185
}
11901186

11911187
for (const auto & object : objects) {
1192-
// If avoidance is executed by both behavior and motion, only non-avoidable object will be
1193-
// extracted from the drivable area.
1194-
if (!parameters->disable_path_update) {
1195-
if (object.is_avoidable) {
1196-
continue;
1197-
}
1198-
}
1199-
12001188
// check if avoid marin is calculated
12011189
if (!object.avoid_margin.has_value()) {
12021190
continue;
12031191
}
12041192

1193+
// check original polygon
1194+
if (object.envelope_poly.outer().empty()) {
1195+
continue;
1196+
}
1197+
12051198
const auto object_type = utils::getHighestProbLabel(object.object.classification);
12061199
const auto object_parameter = parameters->object_parameters.at(object_type);
12071200

@@ -1615,6 +1608,40 @@ void compensateDetectionLost(
16151608
}
16161609
}
16171610

1611+
void updateRoadShoulderDistance(
1612+
AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
1613+
const std::shared_ptr<AvoidanceParameters> & parameters)
1614+
{
1615+
ObjectDataArray clip_objects;
1616+
std::for_each(data.other_objects.begin(), data.other_objects.end(), [&](const auto & object) {
1617+
if (!filtering_utils::isMovingObject(object, parameters)) {
1618+
clip_objects.push_back(object);
1619+
}
1620+
});
1621+
for (auto & o : clip_objects) {
1622+
const auto & vehicle_width = planner_data->parameters.vehicle_width;
1623+
const auto object_type = utils::getHighestProbLabel(o.object.classification);
1624+
const auto object_parameter = parameters->object_parameters.at(object_type);
1625+
1626+
o.avoid_margin = object_parameter.safety_buffer_lateral + 0.5 * vehicle_width;
1627+
}
1628+
const auto extract_obstacles = generateObstaclePolygonsForDrivableArea(
1629+
clip_objects, parameters, planner_data->parameters.vehicle_width / 2.0);
1630+
1631+
auto tmp_path = data.reference_path;
1632+
tmp_path.left_bound = data.left_bound;
1633+
tmp_path.right_bound = data.right_bound;
1634+
utils::extractObstaclesFromDrivableArea(tmp_path, extract_obstacles);
1635+
1636+
data.left_bound = tmp_path.left_bound;
1637+
data.right_bound = tmp_path.right_bound;
1638+
1639+
for (auto & o : data.target_objects) {
1640+
o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data);
1641+
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);
1642+
}
1643+
}
1644+
16181645
void filterTargetObjects(
16191646
ObjectDataArray & objects, AvoidancePlanningData & data, const double forward_detection_range,
16201647
const std::shared_ptr<const PlannerData> & planner_data,

0 commit comments

Comments
 (0)