forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathroute_handler.cpp
2255 lines (1994 loc) · 79.2 KB
/
route_handler.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2021-2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "autoware/route_handler/route_handler.hpp"
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_utils/math/normalization.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/route_checker.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>
#include <autoware_planning_msgs/msg/lanelet_primitive.hpp>
#include <autoware_planning_msgs/msg/path.hpp>
#include <tier4_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_core/primitives/LaneletSequence.h>
#include <lanelet2_routing/Route.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <lanelet2_routing/RoutingGraphContainer.h>
#include <tf2/utils.h>
#include <algorithm>
#include <limits>
#include <memory>
#include <optional>
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <vector>
namespace autoware::route_handler
{
namespace
{
using autoware::universe_utils::createPoint;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware_planning_msgs::msg::LaneletPrimitive;
using autoware_planning_msgs::msg::Path;
using geometry_msgs::msg::Pose;
using lanelet::utils::to2D;
using tier4_planning_msgs::msg::PathPointWithLaneId;
using tier4_planning_msgs::msg::PathWithLaneId;
bool exists(const std::vector<LaneletPrimitive> & primitives, const int64_t & id)
{
for (const auto & p : primitives) {
if (p.id == id) {
return true;
}
}
return false;
}
template <typename T>
bool exists(const std::vector<T> & vectors, const T & item)
{
for (const auto & i : vectors) {
if (i == item) {
return true;
}
}
return false;
}
lanelet::ConstPoint3d get3DPointFrom2DArcLength(
const lanelet::ConstLanelets & lanelet_sequence, const double s)
{
double accumulated_distance2d = 0;
for (const auto & llt : lanelet_sequence) {
const auto & centerline = llt.centerline();
lanelet::ConstPoint3d prev_pt;
if (!centerline.empty()) {
prev_pt = centerline.front();
}
for (const auto & pt : centerline) {
const double distance2d = lanelet::geometry::distance2d(to2D(prev_pt), to2D(pt));
if (accumulated_distance2d + distance2d > s) {
const double ratio = (s - accumulated_distance2d) / distance2d;
const auto interpolated_pt = prev_pt.basicPoint() * (1 - ratio) + pt.basicPoint() * ratio;
return lanelet::ConstPoint3d{
lanelet::InvalId, interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z()};
}
accumulated_distance2d += distance2d;
prev_pt = pt;
}
}
return lanelet::ConstPoint3d{};
}
PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path)
{
PathWithLaneId filtered_path;
for (const auto & pt : input_path.points) {
if (filtered_path.points.empty()) {
filtered_path.points.push_back(pt);
continue;
}
constexpr double min_dist = 0.001;
if (
autoware::universe_utils::calcDistance3d(filtered_path.points.back().point, pt.point) <
min_dist) {
filtered_path.points.back().lane_ids.push_back(pt.lane_ids.front());
filtered_path.points.back().point.longitudinal_velocity_mps = std::min(
pt.point.longitudinal_velocity_mps,
filtered_path.points.back().point.longitudinal_velocity_mps);
} else {
filtered_path.points.push_back(pt);
}
}
filtered_path.left_bound = input_path.left_bound;
filtered_path.right_bound = input_path.right_bound;
return filtered_path;
}
std::string toString(const geometry_msgs::msg::Pose & pose)
{
std::stringstream ss;
ss << "(" << pose.position.x << ", " << pose.position.y << "," << pose.position.z << ")";
return ss.str();
}
bool isClose(
const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, const double epsilon)
{
return std::abs(p1.x - p2.x) < epsilon && std::abs(p1.y - p2.y) < epsilon;
}
PiecewiseReferencePoints convertWaypointsToReferencePoints(
const std::vector<geometry_msgs::msg::Point> & piecewise_waypoints)
{
PiecewiseReferencePoints piecewise_ref_points;
for (const auto & piecewise_waypoint : piecewise_waypoints) {
piecewise_ref_points.push_back(ReferencePoint{true, piecewise_waypoint});
}
return piecewise_ref_points;
}
template <typename T>
bool isIndexWithinVector(const std::vector<T> & vec, const int index)
{
return 0 <= index && index < static_cast<int>(vec.size());
}
template <typename T>
void removeIndicesFromVector(std::vector<T> & vec, std::vector<size_t> indices)
{
// sort indices in a descending order
std::sort(indices.begin(), indices.end(), std::greater<int>());
// remove indices from vector
for (const size_t index : indices) {
vec.erase(vec.begin() + index);
}
}
lanelet::ArcCoordinates calcArcCoordinates(
const lanelet::ConstLanelet & lanelet, const geometry_msgs::msg::Point & point)
{
return lanelet::geometry::toArcCoordinates(
to2D(lanelet.centerline()),
to2D(lanelet::utils::conversion::toLaneletPoint(point)).basicPoint());
}
} // namespace
RouteHandler::RouteHandler(const LaneletMapBin & map_msg)
{
setMap(map_msg);
route_ptr_ = nullptr;
}
void RouteHandler::setMap(const LaneletMapBin & map_msg)
{
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(
map_msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
const auto traffic_rules = lanelet::traffic_rules::TrafficRulesFactory::create(
lanelet::Locations::Germany, lanelet::Participants::Vehicle);
const auto pedestrian_rules = lanelet::traffic_rules::TrafficRulesFactory::create(
lanelet::Locations::Germany, lanelet::Participants::Pedestrian);
const lanelet::routing::RoutingGraphConstPtr vehicle_graph =
lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *traffic_rules);
const lanelet::routing::RoutingGraphConstPtr pedestrian_graph =
lanelet::routing::RoutingGraph::build(*lanelet_map_ptr_, *pedestrian_rules);
const lanelet::routing::RoutingGraphContainer overall_graphs({vehicle_graph, pedestrian_graph});
overall_graphs_ptr_ =
std::make_shared<const lanelet::routing::RoutingGraphContainer>(overall_graphs);
lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
is_map_msg_ready_ = true;
is_handler_ready_ = false;
setLaneletsFromRouteMsg();
}
bool RouteHandler::isRouteLooped(const RouteSections & route_sections)
{
std::set<lanelet::Id> lane_primitives;
for (const auto & route_section : route_sections) {
for (const auto & primitive : route_section.primitives) {
if (lane_primitives.find(primitive.id) != lane_primitives.end()) {
return true; // find duplicated id
}
lane_primitives.emplace(primitive.id);
}
}
return false;
}
void RouteHandler::setRoute(const LaneletRoute & route_msg)
{
if (!isRouteLooped(route_msg.segments)) {
// if get not modified route but new route, reset original start pose
if (!route_ptr_ || route_ptr_->uuid != route_msg.uuid) {
original_start_pose_ = route_msg.start_pose;
original_goal_pose_ = route_msg.goal_pose;
}
route_ptr_ = std::make_shared<LaneletRoute>(route_msg);
is_handler_ready_ = false;
setLaneletsFromRouteMsg();
} else {
RCLCPP_ERROR(
logger_,
"Loop detected within route! Currently, no loop is allowed for route! Using previous route");
}
}
bool RouteHandler::isHandlerReady() const
{
return is_handler_ready_;
}
void RouteHandler::setRouteLanelets(const lanelet::ConstLanelets & path_lanelets)
{
if (!path_lanelets.empty()) {
const auto & first_lanelet = path_lanelets.front();
start_lanelets_ = lanelet::utils::query::getAllNeighbors(routing_graph_ptr_, first_lanelet);
const auto & last_lanelet = path_lanelets.back();
goal_lanelets_ = lanelet::utils::query::getAllNeighbors(routing_graph_ptr_, last_lanelet);
}
// set route lanelets
std::unordered_set<lanelet::Id> route_lanelets_id;
std::unordered_set<lanelet::Id> candidate_lanes_id;
for (const auto & lane : path_lanelets) {
route_lanelets_id.insert(lane.id());
const auto right_relations = routing_graph_ptr_->rightRelations(lane);
for (const auto & right_relation : right_relations) {
if (right_relation.relationType == lanelet::routing::RelationType::Right) {
route_lanelets_id.insert(right_relation.lanelet.id());
} else if (right_relation.relationType == lanelet::routing::RelationType::AdjacentRight) {
candidate_lanes_id.insert(right_relation.lanelet.id());
}
}
const auto left_relations = routing_graph_ptr_->leftRelations(lane);
for (const auto & left_relation : left_relations) {
if (left_relation.relationType == lanelet::routing::RelationType::Left) {
route_lanelets_id.insert(left_relation.lanelet.id());
} else if (left_relation.relationType == lanelet::routing::RelationType::AdjacentLeft) {
candidate_lanes_id.insert(left_relation.lanelet.id());
}
}
}
// check if candidates are really part of route
for (const auto & candidate_id : candidate_lanes_id) {
lanelet::ConstLanelet lanelet = lanelet_map_ptr_->laneletLayer.get(candidate_id);
auto previous_lanelets = routing_graph_ptr_->previous(lanelet);
bool is_connected_to_main_lanes_prev = false;
bool is_connected_to_candidate_prev = true;
if (exists(start_lanelets_, lanelet)) {
is_connected_to_candidate_prev = false;
}
while (!previous_lanelets.empty() && is_connected_to_candidate_prev &&
!is_connected_to_main_lanes_prev) {
is_connected_to_candidate_prev = false;
for (const auto & prev_lanelet : previous_lanelets) {
if (route_lanelets_id.find(prev_lanelet.id()) != route_lanelets_id.end()) {
is_connected_to_main_lanes_prev = true;
break;
}
if (exists(start_lanelets_, prev_lanelet)) {
break;
}
if (candidate_lanes_id.find(prev_lanelet.id()) != candidate_lanes_id.end()) {
is_connected_to_candidate_prev = true;
previous_lanelets = routing_graph_ptr_->previous(prev_lanelet);
break;
}
}
}
auto following_lanelets = routing_graph_ptr_->following(lanelet);
bool is_connected_to_main_lanes_next = false;
bool is_connected_to_candidate_next = true;
if (exists(goal_lanelets_, lanelet)) {
is_connected_to_candidate_next = false;
}
while (!following_lanelets.empty() && is_connected_to_candidate_next &&
!is_connected_to_main_lanes_next) {
is_connected_to_candidate_next = false;
for (const auto & next_lanelet : following_lanelets) {
if (route_lanelets_id.find(next_lanelet.id()) != route_lanelets_id.end()) {
is_connected_to_main_lanes_next = true;
break;
}
if (exists(goal_lanelets_, next_lanelet)) {
break;
}
if (candidate_lanes_id.find(next_lanelet.id()) != candidate_lanes_id.end()) {
is_connected_to_candidate_next = true;
following_lanelets = routing_graph_ptr_->following(next_lanelet);
break;
}
}
}
if (is_connected_to_main_lanes_next && is_connected_to_main_lanes_prev) {
route_lanelets_id.insert(candidate_id);
}
}
route_lanelets_.clear();
route_lanelets_.reserve(route_lanelets_id.size());
for (const auto & id : route_lanelets_id) {
route_lanelets_.push_back(lanelet_map_ptr_->laneletLayer.get(id));
}
is_handler_ready_ = true;
}
void RouteHandler::clearRoute()
{
route_lanelets_.clear();
preferred_lanelets_.clear();
start_lanelets_.clear();
goal_lanelets_.clear();
route_ptr_ = nullptr;
is_handler_ready_ = false;
}
void RouteHandler::setLaneletsFromRouteMsg()
{
if (!route_ptr_ || !is_map_msg_ready_) {
return;
}
route_lanelets_.clear();
preferred_lanelets_.clear();
const bool is_route_valid = lanelet::utils::route::isRouteValid(*route_ptr_, lanelet_map_ptr_);
if (!is_route_valid) {
return;
}
size_t primitive_size{0};
for (const auto & route_section : route_ptr_->segments) {
primitive_size += route_section.primitives.size();
}
route_lanelets_.reserve(primitive_size);
for (const auto & route_section : route_ptr_->segments) {
for (const auto & primitive : route_section.primitives) {
const auto id = primitive.id;
const auto & llt = lanelet_map_ptr_->laneletLayer.get(id);
route_lanelets_.push_back(llt);
if (id == route_section.preferred_primitive.id) {
preferred_lanelets_.push_back(llt);
}
}
}
goal_lanelets_.clear();
start_lanelets_.clear();
if (!route_ptr_->segments.empty()) {
goal_lanelets_.reserve(route_ptr_->segments.back().primitives.size());
for (const auto & primitive : route_ptr_->segments.back().primitives) {
const auto id = primitive.id;
const auto & llt = lanelet_map_ptr_->laneletLayer.get(id);
goal_lanelets_.push_back(llt);
}
start_lanelets_.reserve(route_ptr_->segments.front().primitives.size());
for (const auto & primitive : route_ptr_->segments.front().primitives) {
const auto id = primitive.id;
const auto & llt = lanelet_map_ptr_->laneletLayer.get(id);
start_lanelets_.push_back(llt);
}
}
is_handler_ready_ = true;
}
lanelet::ConstPolygon3d RouteHandler::getIntersectionAreaById(const lanelet::Id id) const
{
return lanelet_map_ptr_->polygonLayer.get(id);
}
Header RouteHandler::getRouteHeader() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getRouteHeader: Route has not been set yet");
return Header();
}
return route_ptr_->header;
}
UUID RouteHandler::getRouteUuid() const
{
if (!route_ptr_) {
RCLCPP_WARN_SKIPFIRST(logger_, "[Route Handler] getRouteUuid: Route has not been set yet");
return UUID();
}
return route_ptr_->uuid;
}
bool RouteHandler::isAllowedGoalModification() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getRouteUuid: Route has not been set yet");
return false;
}
return route_ptr_->allow_modification;
}
std::vector<lanelet::ConstLanelet> RouteHandler::getLanesBeforePose(
const geometry_msgs::msg::Pose & pose, const double length) const
{
lanelet::ConstLanelet pose_lanelet;
if (!getClosestLaneletWithinRoute(pose, &pose_lanelet)) {
return std::vector<lanelet::ConstLanelet>{};
}
const double min_preceding_length = length;
const auto preceding_lanes_vec = lanelet::utils::query::getPrecedingLaneletSequences(
routing_graph_ptr_, pose_lanelet, min_preceding_length);
if (preceding_lanes_vec.empty()) {
return std::vector<lanelet::ConstLanelet>{};
}
return preceding_lanes_vec.front();
}
std::vector<lanelet::ConstLanelet> RouteHandler::getLanesAfterGoal(
const double vehicle_length) const
{
lanelet::ConstLanelet goal_lanelet;
if (!getGoalLanelet(&goal_lanelet)) {
return std::vector<lanelet::ConstLanelet>{};
}
const double min_succeeding_length = vehicle_length * 2;
const auto succeeding_lanes_vec = lanelet::utils::query::getSucceedingLaneletSequences(
routing_graph_ptr_, goal_lanelet, min_succeeding_length);
if (succeeding_lanes_vec.empty()) {
return std::vector<lanelet::ConstLanelet>{};
}
return succeeding_lanes_vec.front();
}
lanelet::ConstLanelets RouteHandler::getRouteLanelets() const
{
return route_lanelets_;
}
lanelet::ConstLanelets RouteHandler::getPreferredLanelets() const
{
return preferred_lanelets_;
}
Pose RouteHandler::getStartPose() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getStartPose: Route has not been set yet");
return Pose();
}
return route_ptr_->start_pose;
}
Pose RouteHandler::getOriginalStartPose() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getOriginalStartPose: Route has not been set yet");
return Pose();
}
return original_start_pose_;
}
Pose RouteHandler::getGoalPose() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getGoalPose: Route has not been set yet");
return Pose();
}
return route_ptr_->goal_pose;
}
Pose RouteHandler::getOriginalGoalPose() const
{
if (!route_ptr_) {
RCLCPP_WARN(logger_, "[Route Handler] getOriginalGoalPose: Route has not been set yet");
return Pose();
}
return original_goal_pose_;
}
lanelet::Id RouteHandler::getGoalLaneId() const
{
if (!route_ptr_ || route_ptr_->segments.empty()) {
return lanelet::InvalId;
}
return route_ptr_->segments.back().preferred_primitive.id;
}
bool RouteHandler::getGoalLanelet(lanelet::ConstLanelet * goal_lanelet) const
{
const lanelet::Id goal_lane_id = getGoalLaneId();
for (const auto & llt : route_lanelets_) {
if (llt.id() == goal_lane_id) {
*goal_lanelet = llt;
return true;
}
}
return false;
}
bool RouteHandler::isInGoalRouteSection(const lanelet::ConstLanelet & lanelet) const
{
if (!route_ptr_ || route_ptr_->segments.empty()) {
return false;
}
return exists(route_ptr_->segments.back().primitives, lanelet.id());
}
lanelet::ConstLanelets RouteHandler::getLaneletsFromIds(const lanelet::Ids & ids) const
{
lanelet::ConstLanelets lanelets;
lanelets.reserve(ids.size());
for (const auto & id : ids) {
lanelets.push_back(lanelet_map_ptr_->laneletLayer.get(id));
}
return lanelets;
}
lanelet::ConstLanelet RouteHandler::getLaneletsFromId(const lanelet::Id id) const
{
return lanelet_map_ptr_->laneletLayer.get(id);
}
bool RouteHandler::isDeadEndLanelet(const lanelet::ConstLanelet & lanelet) const
{
lanelet::ConstLanelet next_lanelet;
return !getNextLaneletWithinRoute(lanelet, &next_lanelet);
}
lanelet::ConstLanelets RouteHandler::getLaneChangeableNeighbors(
const lanelet::ConstLanelet & lanelet) const
{
return lanelet::utils::query::getLaneChangeableNeighbors(routing_graph_ptr_, lanelet);
}
lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter(
const lanelet::ConstLanelet & lanelet, const double min_length, const bool only_route_lanes) const
{
lanelet::ConstLanelets lanelet_sequence_forward;
if (only_route_lanes && !exists(route_lanelets_, lanelet)) {
return lanelet_sequence_forward;
}
double length = 0;
lanelet::ConstLanelet current_lanelet = lanelet;
while (rclcpp::ok() && length < min_length) {
lanelet::ConstLanelet next_lanelet;
if (!getNextLaneletWithinRoute(current_lanelet, &next_lanelet)) {
if (only_route_lanes) {
break;
}
const auto next_lanes = getNextLanelets(current_lanelet);
if (next_lanes.empty()) {
break;
}
next_lanelet = next_lanes.front();
}
// loop check
if (lanelet.id() == next_lanelet.id()) {
break;
}
lanelet_sequence_forward.push_back(next_lanelet);
current_lanelet = next_lanelet;
length +=
static_cast<double>(boost::geometry::length(next_lanelet.centerline().basicLineString()));
}
return lanelet_sequence_forward;
}
lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo(
const lanelet::ConstLanelet & lanelet, const double min_length, const bool only_route_lanes) const
{
lanelet::ConstLanelets lanelet_sequence_backward;
if (only_route_lanes && !exists(route_lanelets_, lanelet)) {
return lanelet_sequence_backward;
}
lanelet::ConstLanelet current_lanelet = lanelet;
double length = 0;
lanelet::ConstLanelets previous_lanelets;
auto checkForLoop =
[&lanelet](const lanelet::ConstLanelets & lanelets_to_check, const bool is_route_lanelets) {
if (is_route_lanelets) {
return std::none_of(
lanelets_to_check.begin(), lanelets_to_check.end(),
[lanelet](auto & prev_llt) { return lanelet.id() != prev_llt.id(); });
}
return std::any_of(
lanelets_to_check.begin(), lanelets_to_check.end(),
[lanelet](auto & prev_llt) { return lanelet.id() == prev_llt.id(); });
};
auto isNewLanelet = [&lanelet,
&lanelet_sequence_backward](const lanelet::ConstLanelet & lanelet_to_check) {
if (lanelet.id() == lanelet_to_check.id()) return false;
return std::none_of(
lanelet_sequence_backward.begin(), lanelet_sequence_backward.end(),
[&lanelet_to_check](auto & backward) { return (backward.id() == lanelet_to_check.id()); });
};
while (rclcpp::ok() && length < min_length) {
previous_lanelets.clear();
bool is_route_lanelets = true;
if (!getPreviousLaneletsWithinRoute(current_lanelet, &previous_lanelets)) {
if (only_route_lanes) break;
previous_lanelets = getPreviousLanelets(current_lanelet);
if (previous_lanelets.empty()) break;
is_route_lanelets = false;
}
if (checkForLoop(previous_lanelets, is_route_lanelets)) break;
for (const auto & prev_lanelet : previous_lanelets) {
if (!isNewLanelet(prev_lanelet) || exists(goal_lanelets_, prev_lanelet)) continue;
lanelet_sequence_backward.push_back(prev_lanelet);
length +=
static_cast<double>(boost::geometry::length(prev_lanelet.centerline().basicLineString()));
current_lanelet = prev_lanelet;
break;
}
}
std::reverse(lanelet_sequence_backward.begin(), lanelet_sequence_backward.end());
return lanelet_sequence_backward;
}
lanelet::ConstLanelets RouteHandler::getLaneletSequence(
const lanelet::ConstLanelet & lanelet, const double backward_distance,
const double forward_distance, const bool only_route_lanes) const
{
Pose current_pose{};
current_pose.orientation.w = 1;
if (!lanelet.centerline().empty()) {
current_pose.position = lanelet::utils::conversion::toGeomMsgPt(lanelet.centerline().front());
}
lanelet::ConstLanelets lanelet_sequence;
if (only_route_lanes && !exists(route_lanelets_, lanelet)) {
return lanelet_sequence;
}
const lanelet::ConstLanelets lanelet_sequence_forward = std::invoke([&]() {
if (only_route_lanes) {
return getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes);
} else if (isShoulderLanelet(lanelet)) {
return getShoulderLaneletSequenceAfter(lanelet, forward_distance);
}
return lanelet::ConstLanelets{};
});
const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() {
const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose);
if (arc_coordinate.length < backward_distance) {
if (only_route_lanes) {
return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes);
} else if (isShoulderLanelet(lanelet)) {
return getShoulderLaneletSequenceUpTo(lanelet, backward_distance);
}
}
return lanelet::ConstLanelets{};
});
// loop check
if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) {
if (lanelet_sequence_backward.back().id() == lanelet_sequence_forward.front().id()) {
return lanelet_sequence_forward;
}
}
lanelet_sequence.insert(
lanelet_sequence.end(), lanelet_sequence_backward.begin(), lanelet_sequence_backward.end());
lanelet_sequence.push_back(lanelet);
lanelet_sequence.insert(
lanelet_sequence.end(), lanelet_sequence_forward.begin(), lanelet_sequence_forward.end());
return lanelet_sequence;
}
lanelet::ConstLanelets RouteHandler::getLaneletSequence(
const lanelet::ConstLanelet & lanelet, const Pose & current_pose, const double backward_distance,
const double forward_distance, const bool only_route_lanes) const
{
if (only_route_lanes && !exists(route_lanelets_, lanelet)) {
return {};
}
lanelet::ConstLanelets lanelet_sequence_forward =
getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes);
lanelet::ConstLanelets lanelet_sequence = std::invoke([&]() {
const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose);
if (arc_coordinate.length < backward_distance) {
return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes);
}
return lanelet::ConstLanelets{};
});
// loop check
if (!lanelet_sequence_forward.empty() && !lanelet_sequence.empty()) {
if (lanelet_sequence.back().id() == lanelet_sequence_forward.front().id()) {
return lanelet_sequence_forward;
}
}
lanelet_sequence.push_back(lanelet);
std::move(
lanelet_sequence_forward.begin(), lanelet_sequence_forward.end(),
std::back_inserter(lanelet_sequence));
return lanelet_sequence;
}
lanelet::ConstLanelets RouteHandler::getRoadLaneletsAtPose(const Pose & pose) const
{
lanelet::ConstLanelets road_lanelets_at_pose;
const lanelet::BasicPoint2d p{pose.position.x, pose.position.y};
const auto lanelets_at_pose = lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p));
for (const auto & lanelet_at_pose : lanelets_at_pose) {
// confirm that the pose is inside the lanelet since "search" does an approximation with boxes
const auto is_pose_inside_lanelet = lanelet::geometry::inside(lanelet_at_pose, p);
if (is_pose_inside_lanelet && isRoadLanelet(lanelet_at_pose))
road_lanelets_at_pose.push_back(lanelet_at_pose);
}
return road_lanelets_at_pose;
}
std::optional<lanelet::ConstLanelet> RouteHandler::getFollowingShoulderLanelet(
const lanelet::ConstLanelet & lanelet) const
{
bool found = false;
const auto & search_point = lanelet.centerline().back().basicPoint2d();
const auto next_lanelet = lanelet_map_ptr_->laneletLayer.nearestUntil(
search_point, [&](const auto & bbox, const auto & ll) {
if (isShoulderLanelet(ll) && lanelet::geometry::follows(lanelet, ll)) found = true;
// stop search once next shoulder lanelet is found, or the bbox does not touch the search
// point
return found || lanelet::geometry::distance2d(bbox, search_point) > 1e-3;
});
if (found && next_lanelet.has_value()) return *next_lanelet;
return std::nullopt;
}
std::optional<lanelet::ConstLanelet> RouteHandler::getLeftShoulderLanelet(
const lanelet::ConstLanelet & lanelet) const
{
for (const auto & other_lanelet :
lanelet_map_ptr_->laneletLayer.findUsages(lanelet.leftBound())) {
if (other_lanelet.rightBound() == lanelet.leftBound() && isShoulderLanelet(other_lanelet))
return other_lanelet;
}
return std::nullopt;
}
std::optional<lanelet::ConstLanelet> RouteHandler::getRightShoulderLanelet(
const lanelet::ConstLanelet & lanelet) const
{
for (const auto & other_lanelet :
lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound())) {
if (other_lanelet.leftBound() == lanelet.rightBound() && isShoulderLanelet(other_lanelet))
return other_lanelet;
}
return std::nullopt;
}
lanelet::ConstLanelets RouteHandler::getShoulderLaneletsAtPose(const Pose & pose) const
{
lanelet::ConstLanelets lanelets_at_pose;
const lanelet::BasicPoint2d p{pose.position.x, pose.position.y};
const auto candidates_at_pose = lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p));
for (const auto & candidate : candidates_at_pose) {
// confirm that the pose is inside the lanelet since "search" does an approximation with boxes
const auto is_pose_inside_lanelet = lanelet::geometry::inside(candidate, p);
if (is_pose_inside_lanelet && isShoulderLanelet(candidate))
lanelets_at_pose.push_back(candidate);
}
return lanelets_at_pose;
}
lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceAfter(
const lanelet::ConstLanelet & lanelet, const double min_length) const
{
lanelet::ConstLanelets lanelet_sequence_forward;
if (!isShoulderLanelet(lanelet)) return lanelet_sequence_forward;
double length = 0;
lanelet::ConstLanelet current_lanelet = lanelet;
std::set<lanelet::Id> searched_ids{};
while (rclcpp::ok() && length < min_length) {
const auto next_lanelet = getFollowingShoulderLanelet(current_lanelet);
if (!next_lanelet) break;
lanelet_sequence_forward.push_back(*next_lanelet);
if (searched_ids.find(next_lanelet->id()) != searched_ids.end()) {
// loop shoulder detected
break;
}
searched_ids.insert(next_lanelet->id());
current_lanelet = *next_lanelet;
length +=
static_cast<double>(boost::geometry::length(next_lanelet->centerline().basicLineString()));
}
return lanelet_sequence_forward;
}
std::optional<lanelet::ConstLanelet> RouteHandler::getPreviousShoulderLanelet(
const lanelet::ConstLanelet & lanelet) const
{
bool found = false;
const auto & search_point = lanelet.centerline().front().basicPoint2d();
const auto previous_lanelet = lanelet_map_ptr_->laneletLayer.nearestUntil(
search_point, [&](const auto & bbox, const auto & ll) {
if (isShoulderLanelet(ll) && lanelet::geometry::follows(ll, lanelet)) found = true;
// stop search once prev shoulder lanelet is found, or the bbox does not touch the search
// point
return found || lanelet::geometry::distance2d(bbox, search_point) > 1e-3;
});
if (found && previous_lanelet.has_value()) return *previous_lanelet;
return std::nullopt;
}
lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceUpTo(
const lanelet::ConstLanelet & lanelet, const double min_length) const
{
lanelet::ConstLanelets lanelet_sequence_backward;
if (!isShoulderLanelet(lanelet)) return lanelet_sequence_backward;
double length = 0;
lanelet::ConstLanelet current_lanelet = lanelet;
std::set<lanelet::Id> searched_ids{};
while (rclcpp::ok() && length < min_length) {
const auto prev_lanelet = getPreviousShoulderLanelet(current_lanelet);
if (!prev_lanelet) break;
lanelet_sequence_backward.insert(lanelet_sequence_backward.begin(), *prev_lanelet);
if (searched_ids.find(prev_lanelet->id()) != searched_ids.end()) {
// loop shoulder detected
break;
}
searched_ids.insert(prev_lanelet->id());
current_lanelet = *prev_lanelet;
length +=
static_cast<double>(boost::geometry::length(prev_lanelet->centerline().basicLineString()));
}
return lanelet_sequence_backward;
}
lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequence(
const lanelet::ConstLanelet & lanelet, const Pose & pose, const double backward_distance,
const double forward_distance) const
{
lanelet::ConstLanelets lanelet_sequence;
if (!isShoulderLanelet(lanelet)) {
return lanelet_sequence;
}
lanelet::ConstLanelets lanelet_sequence_forward =
getShoulderLaneletSequenceAfter(lanelet, forward_distance);
const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() {
const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, pose);
if (arc_coordinate.length < backward_distance) {
return getShoulderLaneletSequenceUpTo(lanelet, backward_distance);
}
return lanelet::ConstLanelets{};
});
// loop check
if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) {
if (lanelet_sequence_backward.back().id() == lanelet_sequence_forward.front().id()) {
return lanelet_sequence_forward;
}
}
lanelet_sequence.insert(
lanelet_sequence.end(), lanelet_sequence_backward.begin(), lanelet_sequence_backward.end());
lanelet_sequence.push_back(lanelet);
lanelet_sequence.insert(
lanelet_sequence.end(), lanelet_sequence_forward.begin(), lanelet_sequence_forward.end());
return lanelet_sequence;
}
bool RouteHandler::getClosestLaneletWithinRoute(
const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const
{
return lanelet::utils::query::getClosestLanelet(route_lanelets_, search_pose, closest_lanelet);
}
bool RouteHandler::getClosestPreferredLaneletWithinRoute(
const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet) const
{
return lanelet::utils::query::getClosestLanelet(
preferred_lanelets_, search_pose, closest_lanelet);
}
bool RouteHandler::getClosestLaneletWithConstrainsWithinRoute(
const Pose & search_pose, lanelet::ConstLanelet * closest_lanelet, const double dist_threshold,
const double yaw_threshold) const
{
return lanelet::utils::query::getClosestLaneletWithConstrains(
route_lanelets_, search_pose, closest_lanelet, dist_threshold, yaw_threshold);
}
bool RouteHandler::getClosestRouteLaneletFromLanelet(
const Pose & search_pose, const lanelet::ConstLanelet & reference_lanelet,
lanelet::ConstLanelet * closest_lanelet, const double dist_threshold,
const double yaw_threshold) const
{
lanelet::ConstLanelets previous_lanelets, next_lanelets, lanelet_sequence;
if (getPreviousLaneletsWithinRoute(reference_lanelet, &previous_lanelets)) {
lanelet_sequence = previous_lanelets;
}
lanelet_sequence.push_back(reference_lanelet);
if (getNextLaneletsWithinRoute(reference_lanelet, &next_lanelets)) {
lanelet_sequence.insert(lanelet_sequence.end(), next_lanelets.begin(), next_lanelets.end());
}
if (lanelet::utils::query::getClosestLaneletWithConstrains(
lanelet_sequence, search_pose, closest_lanelet, dist_threshold, yaw_threshold)) {
return true;
}
return false;
}
bool RouteHandler::getNextLaneletsWithinRoute(
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelets * next_lanelets) const
{
if (exists(goal_lanelets_, lanelet)) {
return false;
}
const auto start_lane_id = route_ptr_->segments.front().preferred_primitive.id;
const auto following_lanelets = routing_graph_ptr_->following(lanelet);
next_lanelets->clear();
for (const auto & llt : following_lanelets) {
if (start_lane_id != llt.id() && exists(route_lanelets_, llt)) {
next_lanelets->push_back(llt);
}
}
return !(next_lanelets->empty());
}
bool RouteHandler::getNextLaneletWithinRoute(
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * next_lanelet) const
{
lanelet::ConstLanelets next_lanelets{};
if (getNextLaneletsWithinRoute(lanelet, &next_lanelets)) {
*next_lanelet = next_lanelets.front();
return true;
}
return false;
}
lanelet::ConstLanelets RouteHandler::getNextLanelets(const lanelet::ConstLanelet & lanelet) const
{
return routing_graph_ptr_->following(lanelet);
}
bool RouteHandler::getPreviousLaneletsWithinRoute(
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelets * prev_lanelets) const