Skip to content

Commit db38f04

Browse files
authored
perf(route_handler): simplify queries on the road and shoulder lanelets (#6885)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 2c9a936 commit db38f04

File tree

9 files changed

+258
-264
lines changed

9 files changed

+258
-264
lines changed

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+8-19
Original file line numberDiff line numberDiff line change
@@ -447,12 +447,10 @@ bool GoalPlannerModule::isExecutionRequested() const
447447

448448
// check that goal is in current neighbor shoulder lane
449449
const bool goal_is_in_current_shoulder_lanes = std::invoke([&]() {
450-
lanelet::ConstLanelet neighbor_shoulder_lane{};
451450
for (const auto & lane : current_lanes) {
452-
const bool has_shoulder_lane =
453-
left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane, &neighbor_shoulder_lane)
454-
: route_handler->getRightShoulderLanelet(lane, &neighbor_shoulder_lane);
455-
if (has_shoulder_lane && lanelet::utils::isInLanelet(goal_pose, neighbor_shoulder_lane)) {
451+
const auto shoulder_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane)
452+
: route_handler->getRightShoulderLanelet(lane);
453+
if (shoulder_lane && lanelet::utils::isInLanelet(goal_pose, *shoulder_lane)) {
456454
return true;
457455
}
458456
}
@@ -1897,20 +1895,11 @@ bool GoalPlannerModule::isCrossingPossible(
18971895
// Lambda function to get the neighboring lanelet based on left_side_parking_
18981896
auto getNeighboringLane =
18991897
[&](const lanelet::ConstLanelet & lane) -> std::optional<lanelet::ConstLanelet> {
1900-
lanelet::ConstLanelet neighboring_lane{};
1901-
if (left_side_parking_) {
1902-
if (route_handler->getLeftShoulderLanelet(lane, &neighboring_lane)) {
1903-
return neighboring_lane;
1904-
} else {
1905-
return route_handler->getLeftLanelet(lane);
1906-
}
1907-
} else {
1908-
if (route_handler->getRightShoulderLanelet(lane, &neighboring_lane)) {
1909-
return neighboring_lane;
1910-
} else {
1911-
return route_handler->getRightLanelet(lane);
1912-
}
1913-
}
1898+
const auto neighboring_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane)
1899+
: route_handler->getRightShoulderLanelet(lane);
1900+
if (neighboring_lane) return neighboring_lane;
1901+
return left_side_parking_ ? route_handler->getLeftLanelet(lane)
1902+
: route_handler->getRightLanelet(lane);
19141903
};
19151904

19161905
// Iterate through start_lane_sequence to find a path to end_lane_sequence

planning/behavior_path_goal_planner_module/src/util.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -55,12 +55,11 @@ lanelet::ConstLanelets getPullOverLanes(
5555
// todo(kosuek55): automatically calculates this distance.
5656
const double backward_distance_with_buffer = backward_distance + 100;
5757

58-
lanelet::ConstLanelet target_shoulder_lane{};
59-
if (route_handler::RouteHandler::getPullOverTarget(
60-
route_handler.getShoulderLanelets(), goal_pose, &target_shoulder_lane)) {
58+
const auto target_shoulder_lane = route_handler.getPullOverTarget(goal_pose);
59+
if (target_shoulder_lane) {
6160
// pull over on shoulder lane
6261
return route_handler.getShoulderLaneletSequence(
63-
target_shoulder_lane, goal_pose, backward_distance_with_buffer, forward_distance);
62+
*target_shoulder_lane, goal_pose, backward_distance_with_buffer, forward_distance);
6463
}
6564

6665
lanelet::ConstLanelet closest_lane{};

planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -354,11 +354,9 @@ TargetObjectsOnLane createTargetObjectsOnLane(
354354
};
355355

356356
const auto update_left_shoulder_lanelet = [&](const lanelet::ConstLanelet & target_lane) {
357-
lanelet::ConstLanelet neighbor_shoulder_lane{};
358-
const bool shoulder_lane_is_found =
359-
route_handler->getLeftShoulderLanelet(target_lane, &neighbor_shoulder_lane);
360-
if (shoulder_lane_is_found) {
361-
all_left_shoulder_lanelets.insert(all_left_shoulder_lanelets.end(), neighbor_shoulder_lane);
357+
const auto neighbor_shoulder_lane = route_handler->getLeftShoulderLanelet(target_lane);
358+
if (neighbor_shoulder_lane) {
359+
all_left_shoulder_lanelets.insert(all_left_shoulder_lanelets.end(), *neighbor_shoulder_lane);
362360
}
363361
};
364362

planning/behavior_path_planner_common/src/utils/path_utils.cpp

+4-7
Original file line numberDiff line numberDiff line change
@@ -645,15 +645,12 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptr<const PlannerDat
645645
const auto & modified_goal = planner_data->prev_modified_goal;
646646

647647
const Pose goal_pose = modified_goal ? modified_goal->pose : route_handler->getGoalPose();
648-
const auto shoulder_lanes = route_handler->getShoulderLanelets();
649648

650649
lanelet::ConstLanelet goal_lane;
651-
const bool is_failed_getting_lanelet = std::invoke([&]() {
652-
if (isInLanelets(goal_pose, shoulder_lanes)) {
653-
return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane);
654-
}
655-
return !route_handler->getGoalLanelet(&goal_lane);
656-
});
650+
const auto shoulder_goal_lanes = route_handler->getShoulderLaneletsAtPose(goal_pose);
651+
if (!shoulder_goal_lanes.empty()) goal_lane = shoulder_goal_lanes.front();
652+
const auto is_failed_getting_lanelet =
653+
shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane);
657654
if (is_failed_getting_lanelet) {
658655
return output;
659656
}

planning/behavior_path_planner_common/src/utils/utils.cpp

+6-23
Original file line numberDiff line numberDiff line change
@@ -496,15 +496,12 @@ bool isEgoOutOfRoute(
496496
const Pose & goal_pose = (modified_goal && modified_goal->uuid == route_handler->getRouteUuid())
497497
? modified_goal->pose
498498
: route_handler->getGoalPose();
499-
const auto shoulder_lanes = route_handler->getShoulderLanelets();
500499

501500
lanelet::ConstLanelet goal_lane;
502-
const bool is_failed_getting_lanelet = std::invoke([&]() {
503-
if (utils::isInLanelets(goal_pose, shoulder_lanes)) {
504-
return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane);
505-
}
506-
return !route_handler->getGoalLanelet(&goal_lane);
507-
});
501+
const auto shoulder_goal_lanes = route_handler->getShoulderLaneletsAtPose(goal_pose);
502+
if (!shoulder_goal_lanes.empty()) goal_lane = shoulder_goal_lanes.front();
503+
const auto is_failed_getting_lanelet =
504+
shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane);
508505
if (is_failed_getting_lanelet) {
509506
RCLCPP_WARN_STREAM(
510507
rclcpp::get_logger("behavior_path_planner").get_child("util"), "cannot find goal lanelet");
@@ -527,14 +524,7 @@ bool isEgoOutOfRoute(
527524

528525
// If ego vehicle is out of the closest lanelet, return true
529526
// Check if ego vehicle is in shoulder lane
530-
const bool is_in_shoulder_lane = std::invoke([&]() {
531-
lanelet::Lanelet closest_shoulder_lanelet;
532-
if (!lanelet::utils::query::getClosestLanelet(
533-
shoulder_lanes, self_pose, &closest_shoulder_lanelet)) {
534-
return false;
535-
}
536-
return lanelet::utils::isInLanelet(self_pose, closest_shoulder_lanelet);
537-
});
527+
const bool is_in_shoulder_lane = !route_handler->getShoulderLaneletsAtPose(self_pose).empty();
538528
// Check if ego vehicle is in road lane
539529
const bool is_in_road_lane = std::invoke([&]() {
540530
lanelet::ConstLanelet closest_road_lane;
@@ -1662,13 +1652,6 @@ bool isAllowedGoalModification(const std::shared_ptr<RouteHandler> & route_handl
16621652
bool checkOriginalGoalIsInShoulder(const std::shared_ptr<RouteHandler> & route_handler)
16631653
{
16641654
const Pose & goal_pose = route_handler->getOriginalGoalPose();
1665-
const auto shoulder_lanes = route_handler->getShoulderLanelets();
1666-
1667-
lanelet::ConstLanelet closest_shoulder_lane{};
1668-
if (lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane)) {
1669-
return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1);
1670-
}
1671-
1672-
return false;
1655+
return !route_handler->getShoulderLaneletsAtPose(goal_pose).empty();
16731656
}
16741657
} // namespace behavior_path_planner::utils

planning/behavior_path_start_planner_module/src/util.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -90,11 +90,10 @@ lanelet::ConstLanelets getPullOutLanes(
9090
const auto & route_handler = planner_data->route_handler;
9191
const auto start_pose = planner_data->route_handler->getOriginalStartPose();
9292

93-
lanelet::ConstLanelet current_shoulder_lane;
94-
if (route_handler->getPullOutStartLane(
95-
route_handler->getShoulderLanelets(), start_pose, vehicle_width, &current_shoulder_lane)) {
93+
const auto current_shoulder_lane = route_handler->getPullOutStartLane(start_pose, vehicle_width);
94+
if (current_shoulder_lane) {
9695
// pull out from shoulder lane
97-
return route_handler->getShoulderLaneletSequence(current_shoulder_lane, start_pose);
96+
return route_handler->getShoulderLaneletSequence(*current_shoulder_lane, start_pose);
9897
}
9998

10099
// pull out from road lane

planning/route_handler/include/route_handler/route_handler.hpp

+48-27
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include <lanelet2_core/Forward.h>
2828
#include <lanelet2_core/primitives/Lanelet.h>
2929
#include <lanelet2_routing/Forward.h>
30+
#include <lanelet2_routing/RoutingCost.h>
3031
#include <lanelet2_traffic_rules/TrafficRules.h>
3132

3233
#include <limits>
@@ -77,6 +78,7 @@ class RouteHandler
7778
lanelet::traffic_rules::TrafficRulesPtr getTrafficRulesPtr() const;
7879
std::shared_ptr<const lanelet::routing::RoutingGraphContainer> getOverallGraphPtr() const;
7980
lanelet::LaneletMapPtr getLaneletMapPtr() const;
81+
static bool isNoDrivableLane(const lanelet::ConstLanelet & llt);
8082

8183
// for routing
8284
bool planPathLaneletsBetweenCheckpoints(
@@ -324,9 +326,9 @@ class RouteHandler
324326
const double check_length) const;
325327
lanelet::routing::RelationType getRelation(
326328
const lanelet::ConstLanelet & prev_lane, const lanelet::ConstLanelet & next_lane) const;
327-
lanelet::ConstLanelets getShoulderLanelets() const;
328329
bool isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const;
329330
bool isRouteLanelet(const lanelet::ConstLanelet & lanelet) const;
331+
bool isRoadLanelet(const lanelet::ConstLanelet & lanelet) const;
330332
lanelet::ConstLanelets getPreferredLanelets() const;
331333

332334
// for path
@@ -341,33 +343,29 @@ class RouteHandler
341343
const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const;
342344
bool getLeftLaneChangeTargetExceptPreferredLane(
343345
const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const;
344-
static bool getPullOverTarget(
345-
const lanelet::ConstLanelets & lanelets, const Pose & goal_pose,
346-
lanelet::ConstLanelet * target_lanelet);
347-
static bool getPullOutStartLane(
348-
const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width,
349-
lanelet::ConstLanelet * target_lanelet);
346+
std::optional<lanelet::ConstLanelet> getPullOverTarget(const Pose & goal_pose) const;
347+
std::optional<lanelet::ConstLanelet> getPullOutStartLane(
348+
const Pose & pose, const double vehicle_width) const;
350349
double getLaneChangeableDistance(const Pose & current_pose, const Direction & direction) const;
351-
bool getLeftShoulderLanelet(
352-
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * left_lanelet) const;
353-
bool getRightShoulderLanelet(
354-
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const;
350+
lanelet::ConstLanelets getRoadLaneletsAtPose(const Pose & pose) const;
351+
std::optional<lanelet::ConstLanelet> getLeftShoulderLanelet(
352+
const lanelet::ConstLanelet & lanelet) const;
353+
std::optional<lanelet::ConstLanelet> getRightShoulderLanelet(
354+
const lanelet::ConstLanelet & lanelet) const;
355+
lanelet::ConstLanelets getShoulderLaneletsAtPose(const Pose & pose) const;
355356
lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const;
356357
bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const;
357-
lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const;
358358

359359
private:
360360
// MUST
361361
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;
362362
lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_;
363363
std::shared_ptr<const lanelet::routing::RoutingGraphContainer> overall_graphs_ptr_;
364364
lanelet::LaneletMapPtr lanelet_map_ptr_;
365-
lanelet::ConstLanelets road_lanelets_;
366365
lanelet::ConstLanelets route_lanelets_;
367366
lanelet::ConstLanelets preferred_lanelets_;
368367
lanelet::ConstLanelets start_lanelets_;
369368
lanelet::ConstLanelets goal_lanelets_;
370-
lanelet::ConstLanelets shoulder_lanelets_;
371369
std::shared_ptr<LaneletRoute> route_ptr_{nullptr};
372370

373371
rclcpp::Logger logger_{rclcpp::get_logger("route_handler")};
@@ -409,19 +407,18 @@ class RouteHandler
409407
const lanelet::ConstLanelet & lanelet,
410408
const double min_length = std::numeric_limits<double>::max(),
411409
const bool only_route_lanes = true) const;
412-
bool getFollowingShoulderLanelet(
413-
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * following_lanelet) const;
410+
std::optional<lanelet::ConstLanelet> getFollowingShoulderLanelet(
411+
const lanelet::ConstLanelet & lanelet) const;
414412
lanelet::ConstLanelets getShoulderLaneletSequenceAfter(
415413
const lanelet::ConstLanelet & lanelet,
416414
const double min_length = std::numeric_limits<double>::max()) const;
417-
bool getPreviousShoulderLanelet(
418-
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * prev_lanelet) const;
415+
std::optional<lanelet::ConstLanelet> getPreviousShoulderLanelet(
416+
const lanelet::ConstLanelet & lanelet) const;
419417
lanelet::ConstLanelets getShoulderLaneletSequenceUpTo(
420418
const lanelet::ConstLanelet & lanelet,
421419
const double min_length = std::numeric_limits<double>::max()) const;
422420
lanelet::ConstLanelets getPreviousLaneletSequence(
423421
const lanelet::ConstLanelets & lanelet_sequence) const;
424-
lanelet::ConstLanelets getClosestLaneletSequence(const Pose & pose) const;
425422
lanelet::ConstLanelets getLaneChangeTargetLanes(const Pose & pose) const;
426423
lanelet::ConstLanelets getLaneSequenceUpTo(const lanelet::ConstLanelet & lanelet) const;
427424
lanelet::ConstLanelets getLaneSequenceAfter(const lanelet::ConstLanelet & lanelet) const;
@@ -441,17 +438,41 @@ class RouteHandler
441438
*/
442439
bool hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const;
443440
/**
444-
* @brief Searches for a path between start and goal lanelets that does not include any
445-
* no_drivable_lane. If there is more than one path fount, the function returns the shortest path
446-
* that does not include any no_drivable_lane.
441+
* @brief Searches for the shortest path between start and goal lanelets that does not include any
442+
* no_drivable_lane.
447443
* @param start_lanelet start lanelet
448444
* @param goal_lanelet goal lanelet
449-
* @param drivable_lane_path output path that does not include no_drivable_lane.
450-
* @return true if a path without any no_drivable_lane found, false if this path is not found.
445+
* @return the lanelet path (if found)
451446
*/
452-
bool findDrivableLanePath(
453-
const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet,
454-
lanelet::routing::LaneletPath & drivable_lane_path) const;
447+
std::optional<lanelet::routing::LaneletPath> findDrivableLanePath(
448+
const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet) const;
455449
};
450+
451+
/// @brief custom routing cost with infinity cost for no drivable lanes
452+
class RoutingCostDrivable : public lanelet::routing::RoutingCostDistance
453+
{
454+
public:
455+
RoutingCostDrivable() : lanelet::routing::RoutingCostDistance(10.0) {}
456+
inline double getCostSucceeding(
457+
const lanelet::traffic_rules::TrafficRules & trafficRules,
458+
const lanelet::ConstLaneletOrArea & from, const lanelet::ConstLaneletOrArea & to) const
459+
{
460+
if (
461+
(from.isLanelet() && RouteHandler::isNoDrivableLane(*from.lanelet())) ||
462+
(to.isLanelet() && RouteHandler::isNoDrivableLane(*to.lanelet())))
463+
return std::numeric_limits<double>::infinity();
464+
return lanelet::routing::RoutingCostDistance::getCostSucceeding(trafficRules, from, to);
465+
}
466+
inline double getCostLaneChange(
467+
const lanelet::traffic_rules::TrafficRules & trafficRules, const lanelet::ConstLanelets & from,
468+
const lanelet::ConstLanelets & to) const noexcept
469+
{
470+
if (
471+
std::any_of(from.begin(), from.end(), RouteHandler::isNoDrivableLane) ||
472+
std::any_of(to.begin(), to.end(), RouteHandler::isNoDrivableLane))
473+
return std::numeric_limits<double>::infinity();
474+
return lanelet::routing::RoutingCostDistance::getCostLaneChange(trafficRules, from, to);
475+
}
476+
}; // class RoutingCostDrivable
456477
} // namespace route_handler
457478
#endif // ROUTE_HANDLER__ROUTE_HANDLER_HPP_

0 commit comments

Comments
 (0)