Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit afb0f60

Browse files
danielsanchezarankyoichi-sugahara
andauthoredApr 8, 2024
feat(lane departure check,start planner): update lane departure check (cherry pick 8bdb542 and 0042c20) (autowarefoundation#1220)
* feat(lane_departure_checker,start_planner): add check for path within lanes for bvspm (autowarefoundation#6366) * WIP add new methods for lane departure checker Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * add lanelet polygon check for lane departure Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * use new checkPathWillLeaveLane function Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * working solution, fix union bug Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * Add check fo backwards path Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * delete departure check lanes Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * add lane departure check to geometric pullout Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * merge all union polygon Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * pre-commit changes Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * move the cheap/fast check first to possibly boost performance Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * declare missing function Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix(lane_departure_checker): empty lanelet polygon (autowarefoundation#6588) * fix union sometimes returning empty polygon Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix union of polygons Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * fix back launcher Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * cherry pick 8bdb542 and 0042c20 from universe Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> * remove unused methods Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> --------- Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com> Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> Co-authored-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 213c263 commit afb0f60

File tree

11 files changed

+210
-63
lines changed

11 files changed

+210
-63
lines changed
 

‎common/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <boost/geometry/core/cs.hpp>
1919
#include <boost/geometry/geometries/geometries.hpp>
2020
#include <boost/geometry/geometries/register/point.hpp>
21+
#include <boost/geometry/geometries/register/ring.hpp>
2122

2223
#define EIGEN_MPL2_ONLY
2324
#include <Eigen/Core>
@@ -98,5 +99,6 @@ BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLIN
9899
tier4_autoware_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT
99100
BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT
100101
tier4_autoware_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT
102+
BOOST_GEOMETRY_REGISTER_RING(tier4_autoware_utils::LinearRing2d) // NOLINT
101103

102104
#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_

‎control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp

+20-1
Original file line numberDiff line numberDiff line change
@@ -29,14 +29,20 @@
2929
#include <geometry_msgs/msg/twist_stamped.hpp>
3030
#include <nav_msgs/msg/odometry.hpp>
3131

32+
#include <boost/geometry/algorithms/envelope.hpp>
33+
#include <boost/geometry/algorithms/union.hpp>
3234
#include <boost/geometry/index/rtree.hpp>
33-
#include <boost/optional.hpp>
3435

3536
#include <lanelet2_core/LaneletMap.h>
37+
#include <lanelet2_core/geometry/BoundingBox.h>
38+
#include <lanelet2_core/geometry/LaneletMap.h>
39+
#include <lanelet2_core/geometry/LineString.h>
40+
#include <lanelet2_core/geometry/Polygon.h>
3641

3742
#include <map>
3843
#include <memory>
3944
#include <string>
45+
#include <utility>
4046
#include <vector>
4147

4248
namespace lane_departure_checker
@@ -112,6 +118,19 @@ class LaneDepartureChecker
112118
bool checkPathWillLeaveLane(
113119
const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path) const;
114120

121+
std::vector<std::pair<double, lanelet::Lanelet>> getLaneletsFromPath(
122+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;
123+
124+
std::optional<tier4_autoware_utils::Polygon2d> getFusedLaneletPolygonForPath(
125+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;
126+
127+
bool checkPathWillLeaveLane(
128+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;
129+
130+
PathWithLaneId cropPointsOutsideOfLanes(
131+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path,
132+
const size_t end_index);
133+
115134
static bool isOutOfLane(
116135
const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint);
117136

‎control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

+95
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ using motion_utils::calcArcLength;
3434
using tier4_autoware_utils::LinearRing2d;
3535
using tier4_autoware_utils::LineString2d;
3636
using tier4_autoware_utils::MultiPoint2d;
37+
using tier4_autoware_utils::MultiPolygon2d;
3738
using tier4_autoware_utils::Point2d;
3839

3940
namespace
@@ -92,6 +93,7 @@ lanelet::ConstLanelets getCandidateLanelets(
9293

9394
return candidate_lanelets;
9495
}
96+
9597
} // namespace
9698

9799
namespace lane_departure_checker
@@ -298,6 +300,98 @@ bool LaneDepartureChecker::willLeaveLane(
298300
return false;
299301
}
300302

303+
std::vector<std::pair<double, lanelet::Lanelet>> LaneDepartureChecker::getLaneletsFromPath(
304+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
305+
{
306+
// Get Footprint Hull basic polygon
307+
std::vector<LinearRing2d> vehicle_footprints = createVehicleFootprints(path);
308+
LinearRing2d footprint_hull = createHullFromFootprints(vehicle_footprints);
309+
auto to_basic_polygon = [](const LinearRing2d & footprint_hull) -> lanelet::BasicPolygon2d {
310+
lanelet::BasicPolygon2d basic_polygon;
311+
for (const auto & point : footprint_hull) {
312+
Eigen::Vector2d p(point.x(), point.y());
313+
basic_polygon.push_back(p);
314+
}
315+
return basic_polygon;
316+
};
317+
lanelet::BasicPolygon2d footprint_hull_basic_polygon = to_basic_polygon(footprint_hull);
318+
319+
// Find all lanelets that intersect the footprint hull
320+
return lanelet::geometry::findWithin2d(
321+
lanelet_map_ptr->laneletLayer, footprint_hull_basic_polygon, 0.0);
322+
}
323+
324+
std::optional<tier4_autoware_utils::Polygon2d> LaneDepartureChecker::getFusedLaneletPolygonForPath(
325+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
326+
{
327+
const auto lanelets_distance_pair = getLaneletsFromPath(lanelet_map_ptr, path);
328+
auto to_polygon2d = [](const lanelet::BasicPolygon2d & poly) -> tier4_autoware_utils::Polygon2d {
329+
tier4_autoware_utils::Polygon2d p;
330+
auto & outer = p.outer();
331+
332+
for (const auto & p : poly) {
333+
tier4_autoware_utils::Point2d p2d(p.x(), p.y());
334+
outer.push_back(p2d);
335+
}
336+
boost::geometry::correct(p);
337+
return p;
338+
};
339+
340+
// Fuse lanelets into a single BasicPolygon2d
341+
auto fused_lanelets = [&]() -> std::optional<tier4_autoware_utils::Polygon2d> {
342+
if (lanelets_distance_pair.empty()) return std::nullopt;
343+
tier4_autoware_utils::MultiPolygon2d lanelet_unions;
344+
tier4_autoware_utils::MultiPolygon2d result;
345+
346+
for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) {
347+
const auto & route_lanelet = lanelets_distance_pair.at(i).second;
348+
const auto & p = route_lanelet.polygon2d().basicPolygon();
349+
tier4_autoware_utils::Polygon2d poly = to_polygon2d(p);
350+
boost::geometry::union_(lanelet_unions, poly, result);
351+
lanelet_unions = result;
352+
result.clear();
353+
}
354+
355+
if (lanelet_unions.empty()) return std::nullopt;
356+
return lanelet_unions.front();
357+
}();
358+
359+
return fused_lanelets;
360+
}
361+
362+
bool LaneDepartureChecker::checkPathWillLeaveLane(
363+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
364+
{
365+
// check if the footprint is not fully contained within the fused lanelets polygon
366+
const std::vector<LinearRing2d> vehicle_footprints = createVehicleFootprints(path);
367+
const auto fused_lanelets_polygon = getFusedLaneletPolygonForPath(lanelet_map_ptr, path);
368+
if (!fused_lanelets_polygon) return true;
369+
return !std::all_of(
370+
vehicle_footprints.begin(), vehicle_footprints.end(),
371+
[&fused_lanelets_polygon](const auto & footprint) {
372+
return boost::geometry::within(footprint, fused_lanelets_polygon.value());
373+
});
374+
}
375+
376+
PathWithLaneId LaneDepartureChecker::cropPointsOutsideOfLanes(
377+
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path, const size_t end_index)
378+
{
379+
PathWithLaneId temp_path;
380+
const auto fused_lanelets_polygon = getFusedLaneletPolygonForPath(lanelet_map_ptr, path);
381+
if (path.points.empty() || !fused_lanelets_polygon) return temp_path;
382+
const auto vehicle_footprints = createVehicleFootprints(path);
383+
size_t idx = 0;
384+
std::for_each(vehicle_footprints.begin(), vehicle_footprints.end(), [&](const auto & footprint) {
385+
if (idx > end_index || boost::geometry::within(footprint, fused_lanelets_polygon.value())) {
386+
temp_path.points.push_back(path.points.at(idx));
387+
}
388+
++idx;
389+
});
390+
PathWithLaneId cropped_path = path;
391+
cropped_path.points = temp_path.points;
392+
return cropped_path;
393+
}
394+
301395
bool LaneDepartureChecker::isOutOfLane(
302396
const lanelet::ConstLanelets & candidate_lanelets, const LinearRing2d & vehicle_footprint)
303397
{
@@ -364,4 +458,5 @@ bool LaneDepartureChecker::willCrossBoundary(
364458
}
365459
return false;
366460
}
461+
367462
} // namespace lane_departure_checker

‎planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "behavior_path_planner_common/data_manager.hpp"
1919
#include "behavior_path_planner_common/parameters.hpp"
2020

21+
#include <lane_departure_checker/lane_departure_checker.hpp>
2122
#include <rclcpp/rclcpp.hpp>
2223
#include <tier4_autoware_utils/ros/marker_helper.hpp>
2324

@@ -78,7 +79,8 @@ class GeometricParallelParking
7879
const bool left_side_parking);
7980
bool planPullOut(
8081
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
81-
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start);
82+
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
83+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
8284
void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; }
8385
void setPlannerData(const std::shared_ptr<const PlannerData> & planner_data)
8486
{
@@ -121,7 +123,8 @@ class GeometricParallelParking
121123
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
122124
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
123125
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
124-
const double lane_departure_margin, const double arc_path_interval);
126+
const double lane_departure_margin, const double arc_path_interval,
127+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
125128
PathWithLaneId generateArcPath(
126129
const Pose & center, const double radius, const double start_yaw, double end_yaw,
127130
const double arc_path_interval, const bool is_left_turn, const bool is_forward);

‎planning/behavior_path_planner_common/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@
4747
<depend>freespace_planning_algorithms</depend>
4848
<depend>geometry_msgs</depend>
4949
<depend>interpolation</depend>
50+
<depend>lane_departure_checker</depend>
5051
<depend>lanelet2_extension</depend>
5152
<depend>libboost-dev</depend>
5253
<depend>libopencv-dev</depend>

‎planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp

+24-4
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
132132
: parameters_.backward_parking_path_interval;
133133
auto arc_paths = planOneTrial(
134134
start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking,
135-
end_pose_offset, lane_departure_margin, arc_path_interval);
135+
end_pose_offset, lane_departure_margin, arc_path_interval, {});
136136
if (arc_paths.empty()) {
137137
return std::vector<PathWithLaneId>{};
138138
}
@@ -238,7 +238,8 @@ bool GeometricParallelParking::planPullOver(
238238

239239
bool GeometricParallelParking::planPullOut(
240240
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
241-
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start)
241+
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
242+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
242243
{
243244
constexpr bool is_forward = false; // parking backward means pull_out forward
244245
constexpr double start_pose_offset = 0.0; // start_pose is current_pose
@@ -258,7 +259,7 @@ bool GeometricParallelParking::planPullOut(
258259
auto arc_paths = planOneTrial(
259260
*end_pose, start_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_start,
260261
start_pose_offset, parameters_.pull_out_lane_departure_margin,
261-
parameters_.pull_out_path_interval);
262+
parameters_.pull_out_path_interval, lane_departure_checker);
262263
if (arc_paths.empty()) {
263264
// not found path
264265
continue;
@@ -378,7 +379,8 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
378379
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
379380
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
380381
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
381-
const double lane_departure_margin, const double arc_path_interval)
382+
const double lane_departure_margin, const double arc_path_interval,
383+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
382384
{
383385
clearPaths();
384386

@@ -512,6 +514,24 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
512514
setLaneIdsToPath(path_turn_first);
513515
setLaneIdsToPath(path_turn_second);
514516

517+
if (lane_departure_checker) {
518+
const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr();
519+
520+
const bool is_path_turn_first_outside_lanes =
521+
lane_departure_checker->checkPathWillLeaveLane(lanelet_map_ptr, path_turn_first);
522+
523+
if (is_path_turn_first_outside_lanes) {
524+
return std::vector<PathWithLaneId>{};
525+
}
526+
527+
const bool is_path_turn_second_outside_lanes =
528+
lane_departure_checker->checkPathWillLeaveLane(lanelet_map_ptr, path_turn_second);
529+
530+
if (is_path_turn_second_outside_lanes) {
531+
return std::vector<PathWithLaneId>{};
532+
}
533+
}
534+
515535
// generate arc path vector
516536
paths_.push_back(path_turn_first);
517537
paths_.push_back(path_turn_second);

‎planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/geometric_pull_out.hpp

+8-1
Original file line numberDiff line numberDiff line change
@@ -19,20 +19,27 @@
1919
#include "behavior_path_start_planner_module/pull_out_path.hpp"
2020
#include "behavior_path_start_planner_module/pull_out_planner_base.hpp"
2121

22+
#include <lane_departure_checker/lane_departure_checker.hpp>
23+
2224
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
2325

26+
#include <memory>
27+
2428
namespace behavior_path_planner
2529
{
2630
class GeometricPullOut : public PullOutPlannerBase
2731
{
2832
public:
29-
explicit GeometricPullOut(rclcpp::Node & node, const StartPlannerParameters & parameters);
33+
explicit GeometricPullOut(
34+
rclcpp::Node & node, const StartPlannerParameters & parameters,
35+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker);
3036

3137
PlannerType getPlannerType() override { return PlannerType::GEOMETRIC; };
3238
std::optional<PullOutPath> plan(const Pose & start_pose, const Pose & goal_pose) override;
3339

3440
GeometricParallelParking planner_;
3541
ParallelParkingParameters parallel_parking_parameters_;
42+
std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker_;
3643
};
3744
} // namespace behavior_path_planner
3845

‎planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -244,6 +244,7 @@ class StartPlannerModule : public SceneModuleInterface
244244
const std::vector<PoseWithVelocityStamped> & ego_predicted_path) const;
245245
bool isSafePath() const;
246246
void setDrivableAreaInfo(BehaviorModuleOutput & output) const;
247+
lanelet::ConstLanelets createDepartureCheckLanes() const;
247248

248249
// check if the goal is located behind the ego in the same route segment.
249250
bool isGoalBehindOfEgoInSameRouteSegment() const;

‎planning/behavior_path_start_planner_module/src/geometric_pull_out.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,12 @@ namespace behavior_path_planner
3030
{
3131
using start_planner_utils::getPullOutLanes;
3232

33-
GeometricPullOut::GeometricPullOut(rclcpp::Node & node, const StartPlannerParameters & parameters)
33+
GeometricPullOut::GeometricPullOut(
34+
rclcpp::Node & node, const StartPlannerParameters & parameters,
35+
const std::shared_ptr<lane_departure_checker::LaneDepartureChecker> lane_departure_checker)
3436
: PullOutPlannerBase{node, parameters},
35-
parallel_parking_parameters_{parameters.parallel_parking_parameters}
37+
parallel_parking_parameters_{parameters.parallel_parking_parameters},
38+
lane_departure_checker_(lane_departure_checker)
3639
{
3740
planner_.setParameters(parallel_parking_parameters_);
3841
}
@@ -55,8 +58,8 @@ std::optional<PullOutPath> GeometricPullOut::plan(const Pose & start_pose, const
5558
planner_.setTurningRadius(
5659
planner_data_->parameters, parallel_parking_parameters_.pull_out_max_steer_angle);
5760
planner_.setPlannerData(planner_data_);
58-
const bool found_valid_path =
59-
planner_.planPullOut(start_pose, goal_pose, road_lanes, pull_out_lanes, left_side_start);
61+
const bool found_valid_path = planner_.planPullOut(
62+
start_pose, goal_pose, road_lanes, pull_out_lanes, left_side_start, lane_departure_checker_);
6063
if (!found_valid_path) {
6164
return {};
6265
}

‎planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

+21-50
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,10 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
7373

7474
// get safe path
7575
for (auto & pull_out_path : pull_out_paths) {
76-
auto & shift_path =
77-
pull_out_path.partial_paths.front(); // shift path is not separate but only one.
78-
79-
// check lane_departure and collision with path between pull_out_start to pull_out_end
80-
PathWithLaneId path_start_to_end{};
76+
// shift path is not separate but only one.
77+
auto & shift_path = pull_out_path.partial_paths.front();
78+
// check lane_departure with path between pull_out_start to pull_out_end
79+
PathWithLaneId path_shift_start_to_end{};
8180
{
8281
const size_t pull_out_start_idx = findNearestIndex(shift_path.points, start_pose.position);
8382

@@ -93,63 +92,35 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
9392
return shift_path.points.size() - 1;
9493
}
9594
});
96-
path_start_to_end.points.insert(
97-
path_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx,
95+
path_shift_start_to_end.points.insert(
96+
path_shift_start_to_end.points.begin(), shift_path.points.begin() + pull_out_start_idx,
9897
shift_path.points.begin() + collision_check_end_idx + 1);
9998
}
10099

101-
// extract shoulder lanes from pull out lanes
102-
lanelet::ConstLanelets shoulder_lanes;
103-
std::copy_if(
104-
pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes),
105-
[&route_handler](const auto & pull_out_lane) {
106-
return route_handler->isShoulderLanelet(pull_out_lane);
107-
});
108-
const auto drivable_lanes =
109-
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
110-
const auto & dp = planner_data_->drivable_area_expansion_parameters;
111-
const auto expanded_lanes = utils::transformToLanelets(utils::expandLanelets(
112-
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
113-
dp.drivable_area_types_to_skip));
100+
// check lane departure
101+
// The method for lane departure checking verifies if the footprint of each point on the path is
102+
// contained within a lanelet using `boost::geometry::within`, which incurs a high computational
103+
// cost.
104+
const auto lanelet_map_ptr = planner_data_->route_handler->getLaneletMapPtr();
105+
if (
106+
parameters_.check_shift_path_lane_departure &&
107+
lane_departure_checker_->checkPathWillLeaveLane(lanelet_map_ptr, path_shift_start_to_end)) {
108+
continue;
109+
}
114110

115111
// crop backward path
116112
// removes points which are out of lanes up to the start pose.
117113
// this ensures that the backward_path stays within the drivable area when starting from a
118114
// narrow place.
115+
119116
const size_t start_segment_idx = motion_utils::findFirstNearestIndexWithSoftConstraints(
120117
shift_path.points, start_pose, common_parameters.ego_nearest_dist_threshold,
121118
common_parameters.ego_nearest_yaw_threshold);
122-
PathWithLaneId cropped_path{};
123-
for (size_t i = 0; i < shift_path.points.size(); ++i) {
124-
const Pose pose = shift_path.points.at(i).point.pose;
125-
const auto transformed_vehicle_footprint =
126-
transformVector(vehicle_footprint_, tier4_autoware_utils::pose2transform(pose));
127-
const bool is_out_of_lane =
128-
LaneDepartureChecker::isOutOfLane(expanded_lanes, transformed_vehicle_footprint);
129-
if (i <= start_segment_idx) {
130-
if (!is_out_of_lane) {
131-
cropped_path.points.push_back(shift_path.points.at(i));
132-
}
133-
} else {
134-
cropped_path.points.push_back(shift_path.points.at(i));
135-
}
136-
}
137-
shift_path.points = cropped_path.points;
138-
139-
// check lane departure
140-
if (
141-
parameters_.check_shift_path_lane_departure &&
142-
lane_departure_checker_->checkPathWillLeaveLane(expanded_lanes, path_start_to_end)) {
143-
continue;
144-
}
145-
146-
// check collision
147-
if (utils::checkCollisionBetweenPathFootprintsAndObjects(
148-
vehicle_footprint_, path_start_to_end, pull_out_lane_stop_objects,
149-
parameters_.collision_check_margin)) {
150-
continue;
151-
}
152119

120+
const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes(
121+
lanelet_map_ptr, shift_path, start_segment_idx);
122+
if (cropped_path.points.empty()) continue;
123+
shift_path.points = cropped_path.points;
153124
shift_path.header = planner_data_->route_handler->getRouteHeader();
154125

155126
return pull_out_path;

‎planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+26-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,8 @@ StartPlannerModule::StartPlannerModule(
6666
std::make_shared<ShiftPullOut>(node, *parameters, lane_departure_checker_));
6767
}
6868
if (parameters_->enable_geometric_pull_out) {
69-
start_planners_.push_back(std::make_shared<GeometricPullOut>(node, *parameters));
69+
start_planners_.push_back(
70+
std::make_shared<GeometricPullOut>(node, *parameters, lane_departure_checker_));
7071
}
7172
if (start_planners_.empty()) {
7273
RCLCPP_ERROR(getLogger(), "Not found enabled planner");
@@ -1289,6 +1290,30 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons
12891290
}
12901291
}
12911292

1293+
lanelet::ConstLanelets StartPlannerModule::createDepartureCheckLanes() const
1294+
{
1295+
const double backward_path_length =
1296+
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
1297+
const auto pull_out_lanes =
1298+
start_planner_utils::getPullOutLanes(planner_data_, backward_path_length);
1299+
if (pull_out_lanes.empty()) {
1300+
return lanelet::ConstLanelets{};
1301+
}
1302+
const auto road_lanes = utils::getExtendedCurrentLanes(
1303+
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
1304+
/*forward_only_in_route*/ true);
1305+
// extract shoulder lanes from pull out lanes
1306+
lanelet::ConstLanelets shoulder_lanes;
1307+
std::copy_if(
1308+
pull_out_lanes.begin(), pull_out_lanes.end(), std::back_inserter(shoulder_lanes),
1309+
[this](const auto & pull_out_lane) {
1310+
return planner_data_->route_handler->isShoulderLanelet(pull_out_lane);
1311+
});
1312+
const auto departure_check_lanes = utils::transformToLanelets(
1313+
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes));
1314+
return departure_check_lanes;
1315+
}
1316+
12921317
void StartPlannerModule::setDebugData() const
12931318
{
12941319
using marker_utils::createObjectsMarkerArray;

0 commit comments

Comments
 (0)
Please sign in to comment.