24
24
25
25
namespace behavior_velocity_planner ::out_of_lane
26
26
{
27
+
28
+ lanelet::ConstLanelets consecutive_lanelets (
29
+ const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet)
30
+ {
31
+ lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr ()->following (lanelet);
32
+ const auto previous = route_handler.getRoutingGraphPtr ()->previous (lanelet);
33
+ consecutives.insert (consecutives.end (), previous.begin (), previous.end ());
34
+ return consecutives;
35
+ }
36
+
37
+ lanelet::ConstLanelets get_missing_lane_change_lanelets (
38
+ lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler)
39
+ {
40
+ lanelet::ConstLanelets missing_lane_change_lanelets;
41
+ const auto & routing_graph = *route_handler.getRoutingGraphPtr ();
42
+ lanelet::ConstLanelets adjacents;
43
+ lanelet::ConstLanelets consecutives;
44
+ for (const auto & ll : path_lanelets) {
45
+ const auto consecutives_of_ll = consecutive_lanelets (route_handler, ll);
46
+ std::copy_if (
47
+ consecutives_of_ll.begin (), consecutives_of_ll.end (), std::back_inserter (consecutives),
48
+ [&](const auto & l) { return !contains_lanelet (consecutives, l.id ()); });
49
+ const auto adjacents_of_ll = routing_graph.besides (ll);
50
+ std::copy_if (
51
+ adjacents_of_ll.begin (), adjacents_of_ll.end (), std::back_inserter (adjacents),
52
+ [&](const auto & l) { return !contains_lanelet (adjacents, l.id ()); });
53
+ }
54
+ std::copy_if (
55
+ adjacents.begin (), adjacents.end (), std::back_inserter (missing_lane_change_lanelets),
56
+ [&](const auto & l) {
57
+ return !contains_lanelet (missing_lane_change_lanelets, l.id ()) &&
58
+ !contains_lanelet (path_lanelets, l.id ()) && contains_lanelet (consecutives, l.id ());
59
+ });
60
+ return missing_lane_change_lanelets;
61
+ }
62
+
63
+ lanelet::ConstLanelets calculate_path_lanelets (
64
+ const EgoData & ego_data, const route_handler::RouteHandler & route_handler)
65
+ {
66
+ const auto lanelet_map_ptr = route_handler.getLaneletMapPtr ();
67
+ lanelet::ConstLanelets path_lanelets;
68
+ lanelet::BasicLineString2d path_ls;
69
+ for (const auto & p : ego_data.path .points )
70
+ path_ls.emplace_back (p.point .pose .position .x , p.point .pose .position .y );
71
+ for (const auto & dist_lanelet :
72
+ lanelet::geometry::findWithin2d (lanelet_map_ptr->laneletLayer , path_ls)) {
73
+ if (!contains_lanelet (path_lanelets, dist_lanelet.second .id ()))
74
+ path_lanelets.push_back (dist_lanelet.second );
75
+ }
76
+ const auto missing_lanelets = get_missing_lane_change_lanelets (path_lanelets, route_handler);
77
+ path_lanelets.insert (path_lanelets.end (), missing_lanelets.begin (), missing_lanelets.end ());
78
+ return path_lanelets;
79
+ }
80
+
27
81
lanelet::ConstLanelets calculate_ignored_lanelets (
28
82
const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets,
29
83
const route_handler::RouteHandler & route_handler, const PlannerParam & params)
30
84
{
31
85
lanelet::ConstLanelets ignored_lanelets;
32
- // ignore lanelets that follows path lanelets
33
- for (const auto & path_lanelet : path_lanelets)
34
- for (const auto & following : route_handler.getRoutingGraphPtr ()->following (path_lanelet))
35
- if (!contains_lanelet (path_lanelets, following.id ())) ignored_lanelets.push_back (following);
36
86
// ignore lanelets directly behind ego
37
87
const auto behind =
38
88
planning_utils::calculateOffsetPoint2d (ego_data.pose , params.rear_offset , 0.0 );
@@ -55,26 +105,14 @@ lanelet::ConstLanelets calculate_other_lanelets(
55
105
const lanelet::BasicPoint2d ego_point (ego_data.pose .position .x , ego_data.pose .position .y );
56
106
const auto lanelets_within_range = lanelet::geometry::findWithin2d (
57
107
route_handler.getLaneletMapPtr ()->laneletLayer , ego_point,
58
- std::max (params.slow_dist_threshold , params.stop_dist_threshold ));
59
- const auto is_overlapped_by_path_lanelets = [&](const auto & l) {
60
- for (const auto & path_ll : path_lanelets) {
61
- if (
62
- boost::geometry::overlaps (
63
- path_ll.polygon2d ().basicPolygon (), l.polygon2d ().basicPolygon ()) ||
64
- boost::geometry::within (path_ll.polygon2d ().basicPolygon (), l.polygon2d ().basicPolygon ()) ||
65
- boost::geometry::within (l.polygon2d ().basicPolygon (), path_ll.polygon2d ().basicPolygon ())) {
66
- return true ;
67
- }
68
- }
69
- return false ;
70
- };
108
+ std::max (params.slow_dist_threshold , params.stop_dist_threshold ) + params.front_offset +
109
+ params.extra_front_offset );
71
110
for (const auto & ll : lanelets_within_range) {
72
111
if (std::string (ll.second .attributeOr (lanelet::AttributeName::Subtype, " none" )) != " road" )
73
112
continue ;
74
113
const auto is_path_lanelet = contains_lanelet (path_lanelets, ll.second .id ());
75
114
const auto is_ignored_lanelet = contains_lanelet (ignored_lanelets, ll.second .id ());
76
- if (!is_path_lanelet && !is_ignored_lanelet && !is_overlapped_by_path_lanelets (ll.second ))
77
- other_lanelets.push_back (ll.second );
115
+ if (!is_path_lanelet && !is_ignored_lanelet) other_lanelets.push_back (ll.second );
78
116
}
79
117
return other_lanelets;
80
118
}
0 commit comments