Skip to content

Commit 34e3743

Browse files
maxime-clemTomohitoAndo
authored andcommitted
fix(out_of_lane): ignore overlaps over all lanelets crossed by the ego path (autowarefoundation#6334)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 3e02320 commit 34e3743

File tree

5 files changed

+45
-26
lines changed

5 files changed

+45
-26
lines changed

planning/behavior_velocity_out_of_lane_module/src/footprint.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <lanelet2_core/geometry/Polygon.h>
2323
#include <tf2/utils.h>
2424

25+
#include <algorithm>
2526
#include <vector>
2627

2728
namespace behavior_velocity_planner::out_of_lane
@@ -59,14 +60,19 @@ std::vector<lanelet::BasicPolygon2d> calculate_path_footprints(
5960
const auto base_footprint = make_base_footprint(params);
6061
std::vector<lanelet::BasicPolygon2d> path_footprints;
6162
path_footprints.reserve(ego_data.path.points.size());
62-
for (auto i = ego_data.first_path_idx; i < ego_data.path.points.size(); ++i) {
63+
double length = 0.0;
64+
const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) +
65+
params.front_offset + params.extra_front_offset;
66+
for (auto i = ego_data.first_path_idx; i < ego_data.path.points.size() && length < range; ++i) {
6367
const auto & path_pose = ego_data.path.points[i].point.pose;
6468
const auto angle = tf2::getYaw(path_pose.orientation);
6569
const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle);
6670
lanelet::BasicPolygon2d footprint;
6771
for (const auto & p : rotated_footprint.outer())
6872
footprint.emplace_back(p.x() + path_pose.position.x, p.y() + path_pose.position.y);
6973
path_footprints.push_back(footprint);
74+
if (i + 1 < ego_data.path.points.size())
75+
length += tier4_autoware_utils::calcDistance2d(path_pose, ego_data.path.points[i + 1].point);
7076
}
7177
return path_footprints;
7278
}

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp

+20-19
Original file line numberDiff line numberDiff line change
@@ -23,15 +23,28 @@
2323

2424
namespace behavior_velocity_planner::out_of_lane
2525
{
26+
lanelet::ConstLanelets calculate_path_lanelets(
27+
const EgoData & ego_data, const route_handler::RouteHandler & route_handler)
28+
{
29+
const auto lanelet_map_ptr = route_handler.getLaneletMapPtr();
30+
lanelet::ConstLanelets path_lanelets =
31+
planning_utils::getLaneletsOnPath(ego_data.path, lanelet_map_ptr, ego_data.pose);
32+
lanelet::BasicLineString2d path_ls;
33+
for (const auto & p : ego_data.path.points)
34+
path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y);
35+
for (const auto & dist_lanelet :
36+
lanelet::geometry::findWithin2d(lanelet_map_ptr->laneletLayer, path_ls)) {
37+
if (!contains_lanelet(path_lanelets, dist_lanelet.second.id()))
38+
path_lanelets.push_back(dist_lanelet.second);
39+
}
40+
return path_lanelets;
41+
}
42+
2643
lanelet::ConstLanelets calculate_ignored_lanelets(
2744
const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets,
2845
const route_handler::RouteHandler & route_handler, const PlannerParam & params)
2946
{
3047
lanelet::ConstLanelets ignored_lanelets;
31-
// ignore lanelets that follows path lanelets
32-
for (const auto & path_lanelet : path_lanelets)
33-
for (const auto & following : route_handler.getRoutingGraphPtr()->following(path_lanelet))
34-
if (!contains_lanelet(path_lanelets, following.id())) ignored_lanelets.push_back(following);
3548
// ignore lanelets directly behind ego
3649
const auto behind =
3750
planning_utils::calculateOffsetPoint2d(ego_data.pose, params.rear_offset, 0.0);
@@ -54,26 +67,14 @@ lanelet::ConstLanelets calculate_other_lanelets(
5467
const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y);
5568
const auto lanelets_within_range = lanelet::geometry::findWithin2d(
5669
route_handler.getLaneletMapPtr()->laneletLayer, ego_point,
57-
std::max(params.slow_dist_threshold, params.stop_dist_threshold));
58-
const auto is_overlapped_by_path_lanelets = [&](const auto & l) {
59-
for (const auto & path_ll : path_lanelets) {
60-
if (
61-
boost::geometry::overlaps(
62-
path_ll.polygon2d().basicPolygon(), l.polygon2d().basicPolygon()) ||
63-
boost::geometry::within(path_ll.polygon2d().basicPolygon(), l.polygon2d().basicPolygon()) ||
64-
boost::geometry::within(l.polygon2d().basicPolygon(), path_ll.polygon2d().basicPolygon())) {
65-
return true;
66-
}
67-
}
68-
return false;
69-
};
70+
std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset +
71+
params.extra_front_offset);
7072
for (const auto & ll : lanelets_within_range) {
7173
if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road")
7274
continue;
7375
const auto is_path_lanelet = contains_lanelet(path_lanelets, ll.second.id());
7476
const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id());
75-
if (!is_path_lanelet && !is_ignored_lanelet && !is_overlapped_by_path_lanelets(ll.second))
76-
other_lanelets.push_back(ll.second);
77+
if (!is_path_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second);
7778
}
7879
return other_lanelets;
7980
}

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp

+8
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,14 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane
3333
return l.id() == id;
3434
}) != lanelets.end();
3535
};
36+
37+
/// @brief calculate lanelets crossed by the ego path
38+
/// @details calculated from the ids of the path msg, the lanelets containing path points
39+
/// @param [in] ego_data data about the ego vehicle
40+
/// @param [in] route_handler route handler
41+
/// @return lanelets crossed by the ego vehicle
42+
lanelet::ConstLanelets calculate_path_lanelets(
43+
const EgoData & ego_data, const route_handler::RouteHandler & route_handler);
3644
/// @brief calculate lanelets that should be ignored
3745
/// @param [in] ego_data data about the ego vehicle
3846
/// @param [in] path_lanelets lanelets driven by the ego vehicle

planning/behavior_velocity_out_of_lane_module/src/overlapping_range.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ Overlap calculate_overlap(
3434
Overlap overlap;
3535
const auto & left_bound = lanelet.leftBound2d().basicLineString();
3636
const auto & right_bound = lanelet.rightBound2d().basicLineString();
37+
// TODO(Maxime): these intersects (for each path footprint, for each lanelet) are too expensive
3738
const auto overlap_left = boost::geometry::intersects(path_footprint, left_bound);
3839
const auto overlap_right = boost::geometry::intersects(path_footprint, right_bound);
3940

planning/behavior_velocity_out_of_lane_module/src/scene_out_of_lane.cpp

+9-6
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
6161
ego_data.pose = planner_data_->current_odometry->pose;
6262
ego_data.path.points = path->points;
6363
ego_data.first_path_idx =
64-
motion_utils::findNearestSegmentIndex(ego_data.path.points, ego_data.pose.position);
64+
motion_utils::findNearestSegmentIndex(path->points, ego_data.pose.position);
6565
motion_utils::removeOverlapPoints(ego_data.path.points);
6666
ego_data.velocity = planner_data_->current_velocity->twist.linear.x;
6767
ego_data.max_decel = -planner_data_->max_stop_acceleration_threshold;
@@ -70,13 +70,13 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
7070
const auto path_footprints = calculate_path_footprints(ego_data, params_);
7171
const auto calculate_path_footprints_us = stopwatch.toc("calculate_path_footprints");
7272
// Calculate lanelets to ignore and consider
73-
const auto path_lanelets = planning_utils::getLaneletsOnPath(
74-
ego_data.path, planner_data_->route_handler_->getLaneletMapPtr(),
75-
planner_data_->current_odometry->pose);
73+
stopwatch.tic("calculate_lanelets");
74+
const auto path_lanelets = calculate_path_lanelets(ego_data, *planner_data_->route_handler_);
7675
const auto ignored_lanelets =
7776
calculate_ignored_lanelets(ego_data, path_lanelets, *planner_data_->route_handler_, params_);
7877
const auto other_lanelets = calculate_other_lanelets(
7978
ego_data, path_lanelets, ignored_lanelets, *planner_data_->route_handler_, params_);
79+
const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets");
8080

8181
debug_data_.footprints = path_footprints;
8282
debug_data_.path_lanelets = path_lanelets;
@@ -93,6 +93,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
9393
});
9494
if (overlapped_lanelet_it != other_lanelets.end()) {
9595
debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it);
96+
// TODO(Maxime): we may want to just add the overlapped lane to the ignored lanelets
9697
RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module ()\n");
9798
return true;
9899
}
@@ -178,13 +179,15 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
178179
RCLCPP_DEBUG(
179180
logger_,
180181
"Total time = %2.2fus\n"
182+
"\tcalculate_lanelets = %2.0fus\n"
181183
"\tcalculate_path_footprints = %2.0fus\n"
182184
"\tcalculate_overlapping_ranges = %2.0fus\n"
183185
"\tcalculate_decisions = %2.0fus\n"
184186
"\tcalc_slowdown_points = %2.0fus\n"
185187
"\tinsert_slowdown_points = %2.0fus\n",
186-
total_time_us, calculate_path_footprints_us, calculate_overlapping_ranges_us,
187-
calculate_decisions_us, calc_slowdown_points_us, insert_slowdown_points_us);
188+
total_time_us, calculate_lanelets_us, calculate_path_footprints_us,
189+
calculate_overlapping_ranges_us, calculate_decisions_us, calc_slowdown_points_us,
190+
insert_slowdown_points_us);
188191
return true;
189192
}
190193

0 commit comments

Comments
 (0)