27
27
#include < lanelet2_core/Forward.h>
28
28
#include < lanelet2_core/primitives/Lanelet.h>
29
29
#include < lanelet2_routing/Forward.h>
30
+ #include < lanelet2_routing/RoutingCost.h>
30
31
#include < lanelet2_traffic_rules/TrafficRules.h>
31
32
32
33
#include < limits>
@@ -77,6 +78,7 @@ class RouteHandler
77
78
lanelet::traffic_rules::TrafficRulesPtr getTrafficRulesPtr () const ;
78
79
std::shared_ptr<const lanelet::routing::RoutingGraphContainer> getOverallGraphPtr () const ;
79
80
lanelet::LaneletMapPtr getLaneletMapPtr () const ;
81
+ static bool isNoDrivableLane (const lanelet::ConstLanelet & llt);
80
82
81
83
// for routing
82
84
bool planPathLaneletsBetweenCheckpoints (
@@ -324,9 +326,9 @@ class RouteHandler
324
326
const double check_length) const ;
325
327
lanelet::routing::RelationType getRelation (
326
328
const lanelet::ConstLanelet & prev_lane, const lanelet::ConstLanelet & next_lane) const ;
327
- lanelet::ConstLanelets getShoulderLanelets () const ;
328
329
bool isShoulderLanelet (const lanelet::ConstLanelet & lanelet) const ;
329
330
bool isRouteLanelet (const lanelet::ConstLanelet & lanelet) const ;
331
+ bool isRoadLanelet (const lanelet::ConstLanelet & lanelet) const ;
330
332
lanelet::ConstLanelets getPreferredLanelets () const ;
331
333
332
334
// for path
@@ -341,33 +343,29 @@ class RouteHandler
341
343
const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const ;
342
344
bool getLeftLaneChangeTargetExceptPreferredLane (
343
345
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 ;
350
349
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 ;
355
356
lanelet::ConstPolygon3d getIntersectionAreaById (const lanelet::Id id) const ;
356
357
bool isPreferredLane (const lanelet::ConstLanelet & lanelet) const ;
357
- lanelet::ConstLanelets getClosestLanelets (const geometry_msgs::msg::Pose & target_pose) const ;
358
358
359
359
private:
360
360
// MUST
361
361
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;
362
362
lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_;
363
363
std::shared_ptr<const lanelet::routing::RoutingGraphContainer> overall_graphs_ptr_;
364
364
lanelet::LaneletMapPtr lanelet_map_ptr_;
365
- lanelet::ConstLanelets road_lanelets_;
366
365
lanelet::ConstLanelets route_lanelets_;
367
366
lanelet::ConstLanelets preferred_lanelets_;
368
367
lanelet::ConstLanelets start_lanelets_;
369
368
lanelet::ConstLanelets goal_lanelets_;
370
- lanelet::ConstLanelets shoulder_lanelets_;
371
369
std::shared_ptr<LaneletRoute> route_ptr_{nullptr };
372
370
373
371
rclcpp::Logger logger_{rclcpp::get_logger (" route_handler" )};
@@ -409,19 +407,18 @@ class RouteHandler
409
407
const lanelet::ConstLanelet & lanelet,
410
408
const double min_length = std::numeric_limits<double >::max(),
411
409
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 ;
414
412
lanelet::ConstLanelets getShoulderLaneletSequenceAfter (
415
413
const lanelet::ConstLanelet & lanelet,
416
414
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 ;
419
417
lanelet::ConstLanelets getShoulderLaneletSequenceUpTo (
420
418
const lanelet::ConstLanelet & lanelet,
421
419
const double min_length = std::numeric_limits<double >::max()) const ;
422
420
lanelet::ConstLanelets getPreviousLaneletSequence (
423
421
const lanelet::ConstLanelets & lanelet_sequence) const ;
424
- lanelet::ConstLanelets getClosestLaneletSequence (const Pose & pose) const ;
425
422
lanelet::ConstLanelets getLaneChangeTargetLanes (const Pose & pose) const ;
426
423
lanelet::ConstLanelets getLaneSequenceUpTo (const lanelet::ConstLanelet & lanelet) const ;
427
424
lanelet::ConstLanelets getLaneSequenceAfter (const lanelet::ConstLanelet & lanelet) const ;
@@ -441,17 +438,41 @@ class RouteHandler
441
438
*/
442
439
bool hasNoDrivableLaneInPath (const lanelet::routing::LaneletPath & path) const ;
443
440
/* *
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.
447
443
* @param start_lanelet start lanelet
448
444
* @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)
451
446
*/
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 ;
455
449
};
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
456
477
} // namespace route_handler
457
478
#endif // ROUTE_HANDLER__ROUTE_HANDLER_HPP_
0 commit comments