-
Notifications
You must be signed in to change notification settings - Fork 630
/
util.cpp
1156 lines (976 loc) · 45.9 KB
/
util.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 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 "behavior_path_planner/util/lane_change/util.hpp"
#include "behavior_path_planner/parameters.hpp"
#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/util/lane_change/lane_change_module_data.hpp"
#include "behavior_path_planner/util/lane_change/lane_change_path.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"
#include "behavior_path_planner/utilities.hpp"
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>
#include <lanelet2_core/LaneletMap.h>
#include <tf2/utils.h>
#include <tf2_ros/transform_listener.h>
#include <algorithm>
#include <limits>
#include <memory>
#include <string>
#include <vector>
namespace
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using geometry_msgs::msg::Pose;
using route_handler::RouteHandler;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
std::vector<std::vector<int64_t>> getSortedLaneIds(
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes, const double rough_shift_length)
{
std::vector<std::vector<int64_t>> sorted_lane_ids{};
sorted_lane_ids.reserve(target_lanes.size());
const auto get_sorted_lane_ids = [&](const lanelet::ConstLanelet & target_lane) {
const auto routing_graph_ptr = route_handler.getRoutingGraphPtr();
lanelet::ConstLanelet lane;
if (rough_shift_length < 0.0) {
// lane change to the left, so I wan to take the lane right to target
const auto has_target_right = routing_graph_ptr->right(target_lane);
if (has_target_right) {
lane = *has_target_right;
}
} else if (rough_shift_length > 0.0) {
const auto has_target_left = routing_graph_ptr->left(target_lane);
if (has_target_left) {
lane = *has_target_left;
}
} else {
lane = target_lane;
}
const auto find_same_id = std::find_if(
current_lanes.cbegin(), current_lanes.cend(),
[&lane](const lanelet::ConstLanelet & orig) { return orig.id() == lane.id(); });
if (find_same_id == current_lanes.cend()) {
return std::vector{target_lane.id()};
}
if (target_lane.id() > find_same_id->id()) {
return std::vector{find_same_id->id(), target_lane.id()};
}
return std::vector{target_lane.id(), find_same_id->id()};
};
std::transform(
target_lanes.cbegin(), target_lanes.cend(), std::back_inserter(sorted_lane_ids),
get_sorted_lane_ids);
return sorted_lane_ids;
}
std::vector<int64_t> replaceWithSortedIds(
const std::vector<int64_t> & original_lane_ids,
const std::vector<std::vector<int64_t>> & sorted_lane_ids)
{
for (const auto original_id : original_lane_ids) {
for (const auto & sorted_id : sorted_lane_ids) {
if (std::find(sorted_id.cbegin(), sorted_id.cend(), original_id) != sorted_id.cend()) {
return sorted_id;
}
}
}
return original_lane_ids;
}
} // namespace
namespace behavior_path_planner::lane_change_utils
{
using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
using lanelet::ArcCoordinates;
using util::getHighestProbLabel;
inline double calcLaneChangeResampleInterval(
const double lane_changing_distance, const double lane_changing_speed)
{
constexpr auto min_resampling_points{30.0};
constexpr auto resampling_dt{0.2};
return std::max(
lane_changing_distance / min_resampling_points, lane_changing_speed * resampling_dt);
}
PathWithLaneId combineReferencePath(const PathWithLaneId & path1, const PathWithLaneId & path2)
{
PathWithLaneId path;
path.points.insert(path.points.end(), path1.points.begin(), path1.points.end());
// skip overlapping point
path.points.insert(path.points.end(), next(path2.points.begin()), path2.points.end());
return path;
}
bool isPathInLanelets(
const PathWithLaneId & path, const lanelet::ConstLanelets & original_lanelets,
const lanelet::ConstLanelets & target_lanelets)
{
const auto current_lane_poly = lanelet::utils::getPolygonFromArcLength(
original_lanelets, 0, std::numeric_limits<double>::max());
const auto target_lane_poly =
lanelet::utils::getPolygonFromArcLength(target_lanelets, 0, std::numeric_limits<double>::max());
const auto current_lane_poly_2d = lanelet::utils::to2D(current_lane_poly).basicPolygon();
const auto target_lane_poly_2d = lanelet::utils::to2D(target_lane_poly).basicPolygon();
for (const auto & pt : path.points) {
const lanelet::BasicPoint2d ll_pt(pt.point.pose.position.x, pt.point.pose.position.y);
const auto is_in_current = boost::geometry::covered_by(ll_pt, current_lane_poly_2d);
if (is_in_current) {
continue;
}
const auto is_in_target = boost::geometry::covered_by(ll_pt, target_lane_poly_2d);
if (!is_in_target) {
return false;
}
}
return true;
}
std::optional<LaneChangePath> constructCandidatePath(
const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment,
const PathWithLaneId & target_lane_reference_path, const ShiftLine & shift_line,
const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets,
const std::vector<std::vector<int64_t>> & sorted_lane_ids, const double acceleration,
const LaneChangePhaseInfo distance, const LaneChangePhaseInfo speed,
const LaneChangeParameters & lane_change_param)
{
PathShifter path_shifter;
path_shifter.setPath(target_lane_reference_path);
path_shifter.addShiftLine(shift_line);
ShiftedPath shifted_path;
// offset front side
bool offset_back = false;
const auto lane_changing_speed = speed.lane_changing;
path_shifter.setVelocity(lane_changing_speed);
path_shifter.setLateralAccelerationLimit(std::abs(lane_change_param.lane_changing_lateral_acc));
if (!path_shifter.generate(&shifted_path, offset_back)) {
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"failed to generate shifted path.");
}
const auto prepare_distance = distance.prepare;
const auto lane_change_distance = distance.lane_changing;
LaneChangePath candidate_path;
candidate_path.acceleration = acceleration;
candidate_path.length.prepare = prepare_distance;
candidate_path.length.lane_changing = lane_change_distance;
candidate_path.duration.prepare = std::invoke([&]() {
const auto duration =
prepare_distance / std::max(lane_change_param.minimum_lane_change_velocity, speed.prepare);
return std::min(duration, lane_change_param.lane_change_prepare_duration);
});
candidate_path.duration.lane_changing = std::invoke([&]() {
const auto rounding_multiplier = 1.0 / lane_change_param.prediction_time_resolution;
return std::ceil((lane_change_distance / lane_changing_speed) * rounding_multiplier) /
rounding_multiplier;
});
candidate_path.shift_line = shift_line;
candidate_path.reference_lanelets = original_lanelets;
candidate_path.target_lanelets = target_lanelets;
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("constructCandidatePath"),
"prepare_distance: %f, lane_change: %f", prepare_distance, lane_change_distance);
const PathPointWithLaneId & lane_changing_start_point = prepare_segment.points.back();
const PathPointWithLaneId & lane_changing_end_point = lane_changing_segment.points.front();
const Pose & lane_changing_end_pose = lane_changing_end_point.point.pose;
const auto lane_change_end_idx =
motion_utils::findNearestIndex(shifted_path.path.points, lane_changing_end_pose);
if (!lane_change_end_idx) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"lane change end idx not found on target path.");
return std::nullopt;
}
for (size_t i = 0; i < shifted_path.path.points.size(); ++i) {
auto & point = shifted_path.path.points.at(i);
if (i < *lane_change_end_idx) {
point.lane_ids = replaceWithSortedIds(point.lane_ids, sorted_lane_ids);
point.point.longitudinal_velocity_mps = std::min(
point.point.longitudinal_velocity_mps,
lane_changing_start_point.point.longitudinal_velocity_mps);
continue;
}
point.point.longitudinal_velocity_mps =
std::min(point.point.longitudinal_velocity_mps, static_cast<float>(lane_changing_speed));
const auto nearest_idx =
motion_utils::findNearestIndex(lane_changing_segment.points, point.point.pose);
point.lane_ids = lane_changing_segment.points.at(*nearest_idx).lane_ids;
}
// check candidate path is in lanelet
if (!isPathInLanelets(shifted_path.path, original_lanelets, target_lanelets)) {
return std::nullopt;
}
candidate_path.path = combineReferencePath(prepare_segment, shifted_path.path);
candidate_path.shifted_path = shifted_path;
return std::optional<LaneChangePath>{candidate_path};
}
#ifdef USE_OLD_ARCHITECTURE
std::pair<bool, bool> getLaneChangePaths(
const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets,
const lanelet::ConstLanelets & target_lanelets, const Pose & pose, const Twist & twist,
const PredictedObjects::ConstSharedPtr dynamic_objects,
const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter,
const double check_distance, LaneChangePaths * candidate_paths,
std::unordered_map<std::string, CollisionCheckDebug> * debug_data)
#else
std::pair<bool, bool> getLaneChangePaths(
const PathWithLaneId & original_path, const RouteHandler & route_handler,
const lanelet::ConstLanelets & original_lanelets, const lanelet::ConstLanelets & target_lanelets,
const Pose & pose, const Twist & twist, const PredictedObjects::ConstSharedPtr dynamic_objects,
const BehaviorPathPlannerParameters & common_parameter, const LaneChangeParameters & parameter,
const double check_distance, LaneChangePaths * candidate_paths,
std::unordered_map<std::string, CollisionCheckDebug> * debug_data)
#endif
{
debug_data->clear();
if (original_lanelets.empty() || target_lanelets.empty()) {
return {false, false};
}
Pose ego_pose_before_collision{};
// rename parameter
const auto backward_path_length = common_parameter.backward_path_length;
const auto forward_path_length = common_parameter.forward_path_length;
const auto prepare_duration = parameter.lane_change_prepare_duration;
const auto minimum_prepare_distance = common_parameter.minimum_lane_change_prepare_distance;
const auto minimum_lane_change_velocity = parameter.minimum_lane_change_velocity;
const auto maximum_deceleration = parameter.maximum_deceleration;
const auto lane_change_sampling_num = parameter.lane_change_sampling_num;
// get velocity
const auto current_velocity = twist.linear.x;
const auto acceleration_resolution = std::abs(maximum_deceleration) / lane_change_sampling_num;
const auto target_distance =
util::getArcLengthToTargetLanelet(original_lanelets, target_lanelets.front(), pose);
const auto num_to_preferred_lane =
std::abs(route_handler.getNumLaneToPreferredLane(target_lanelets.back()));
const auto goal_pose = route_handler.getGoalPose();
const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanelets.back());
const auto end_of_lane_dist = std::invoke([&]() {
const auto required_dist = util::calcLaneChangeBuffer(common_parameter, num_to_preferred_lane);
if (is_goal_in_route) {
return util::getSignedDistance(pose, route_handler.getGoalPose(), original_lanelets) -
required_dist;
}
return util::getDistanceToEndOfLane(pose, original_lanelets) - required_dist;
});
const auto required_total_min_distance =
util::calcLaneChangeBuffer(common_parameter, num_to_preferred_lane);
[[maybe_unused]] const auto arc_position_from_current =
lanelet::utils::getArcCoordinates(original_lanelets, pose);
const auto arc_position_from_target = lanelet::utils::getArcCoordinates(target_lanelets, pose);
const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanelets);
const auto sorted_lane_ids = getSortedLaneIds(
route_handler, original_lanelets, target_lanelets, arc_position_from_target.distance);
constexpr auto ignore_unknown{true};
const auto lateral_buffer = calcLateralBufferForFiltering(common_parameter.vehicle_width, 0.5);
LaneChangeTargetObjectIndices dynamic_object_indices;
candidate_paths->reserve(lane_change_sampling_num);
for (double acceleration = 0.0; acceleration >= -maximum_deceleration;
acceleration -= acceleration_resolution) {
const double prepare_speed = current_velocity + acceleration * prepare_duration;
// skip if velocity becomes less than zero before starting lane change
if (prepare_speed < 0.0) {
break;
}
// get path on original lanes
const double prepare_distance = std::max(
current_velocity * prepare_duration + 0.5 * acceleration * std::pow(prepare_duration, 2),
minimum_prepare_distance);
if (prepare_distance < target_distance) {
break;
}
#ifdef USE_OLD_ARCHITECTURE
const auto prepare_segment = getPrepareSegment(
route_handler, original_lanelets, arc_position_from_current.length, backward_path_length,
prepare_distance, std::max(prepare_speed, minimum_lane_change_velocity));
#else
const auto prepare_segment = getPrepareSegment(
original_path, original_lanelets, pose, backward_path_length, prepare_distance,
std::max(prepare_speed, minimum_lane_change_velocity));
#endif
const auto estimated_shift_length = lanelet::utils::getLateralDistanceToClosestLanelet(
target_lanelets, prepare_segment.points.front().point.pose);
const auto [lane_changing_speed, lane_changing_distance] = calcLaneChangingSpeedAndDistance(
prepare_speed, estimated_shift_length, acceleration, end_of_lane_dist, common_parameter,
parameter);
const auto lc_dist = LaneChangePhaseInfo{prepare_distance, lane_changing_distance};
const auto lane_changing_segment = getLaneChangingSegment(
route_handler, target_lanelets, forward_path_length, arc_position_from_target.length,
target_lane_length, lc_dist, lane_changing_speed, required_total_min_distance);
if (prepare_segment.points.empty() || lane_changing_segment.points.empty()) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"reference path is empty!! something wrong...");
continue;
}
const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose;
const auto resample_interval =
calcLaneChangeResampleInterval(lane_changing_distance, lane_changing_speed);
const auto target_lane_reference_path = getReferencePathFromTargetLane(
route_handler, target_lanelets, lane_changing_start_pose, target_lane_length,
lc_dist.lane_changing, required_total_min_distance, forward_path_length, resample_interval,
is_goal_in_route);
if (target_lane_reference_path.points.empty()) {
continue;
}
const auto shift_line = getLaneChangingShiftLine(
prepare_segment, lane_changing_segment, target_lanelets, target_lane_reference_path);
const auto lc_speed = LaneChangePhaseInfo{prepare_speed, lane_changing_speed};
const auto candidate_path = constructCandidatePath(
prepare_segment, lane_changing_segment, target_lane_reference_path, shift_line,
original_lanelets, target_lanelets, sorted_lane_ids, acceleration, lc_dist, lc_speed,
parameter);
if (!candidate_path) {
continue;
}
const auto is_valid = hasEnoughDistance(
*candidate_path, original_lanelets, target_lanelets, pose, goal_pose, route_handler,
common_parameter.minimum_lane_change_length);
if (!is_valid) {
continue;
}
if (candidate_paths->empty()) {
// only compute dynamic object indices once
const auto backward_lanes = lane_change_utils::getExtendedTargetLanesForCollisionCheck(
route_handler, target_lanelets.front(), pose, check_distance);
dynamic_object_indices = filterObjectIndices(
{*candidate_path}, *dynamic_objects, backward_lanes, pose,
common_parameter.forward_path_length, lateral_buffer, ignore_unknown);
}
candidate_paths->push_back(*candidate_path);
const auto current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
candidate_path->path.points, pose, common_parameter.ego_nearest_dist_threshold,
common_parameter.ego_nearest_yaw_threshold);
const auto is_safe = isLaneChangePathSafe(
*candidate_path, dynamic_objects, dynamic_object_indices, pose, current_seg_idx, twist,
common_parameter, parameter, common_parameter.expected_front_deceleration,
common_parameter.expected_rear_deceleration, ego_pose_before_collision, *debug_data,
acceleration);
if (is_valid && is_safe) {
return {true, true};
}
}
if (candidate_paths->empty()) {
return {false, false};
}
return {true, false};
}
bool hasEnoughDistance(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes,
[[maybe_unused]] const lanelet::ConstLanelets & target_lanes, const Pose & current_pose,
const Pose & goal_pose, const RouteHandler & route_handler,
const double minimum_lane_change_length)
{
const double lane_change_total_distance = path.length.sum();
const int num = std::abs(route_handler.getNumLaneToPreferredLane(target_lanes.back()));
const auto overall_graphs = route_handler.getOverallGraphPtr();
const double lane_change_required_distance =
static_cast<double>(num) * minimum_lane_change_length;
if (
lane_change_total_distance + lane_change_required_distance >
util::getDistanceToEndOfLane(current_pose, current_lanes)) {
return false;
}
if (
route_handler.isInGoalRouteSection(current_lanes.back()) &&
lane_change_total_distance + lane_change_required_distance >
util::getSignedDistance(current_pose, goal_pose, current_lanes)) {
return false;
}
// return is there is no target lanes. Else continue checking
if (target_lanes.empty()) {
return true;
}
if (
lane_change_total_distance + lane_change_required_distance >
util::getDistanceToEndOfLane(current_pose, target_lanes)) {
return false;
}
return true;
}
bool isLaneChangePathSafe(
const LaneChangePath & lane_change_path, const PredictedObjects::ConstSharedPtr dynamic_objects,
const LaneChangeTargetObjectIndices & dynamic_objects_indices, const Pose & current_pose,
const size_t current_seg_idx, const Twist & current_twist,
const BehaviorPathPlannerParameters & common_parameters,
const LaneChangeParameters & lane_change_parameters, const double front_decel,
const double rear_decel, Pose & ego_pose_before_collision,
std::unordered_map<std::string, CollisionCheckDebug> & debug_data, const double acceleration)
{
if (dynamic_objects == nullptr) {
return true;
}
const auto & path = lane_change_path.path;
if (path.points.empty()) {
return false;
}
const double time_resolution = lane_change_parameters.prediction_time_resolution;
const auto check_at_prepare_phase =
lane_change_parameters.enable_collision_check_at_prepare_phase;
const double check_start_time = check_at_prepare_phase ? 0.0 : lane_change_path.duration.prepare;
const double check_end_time = lane_change_path.duration.sum();
const double min_lc_speed{lane_change_parameters.minimum_lane_change_velocity};
const auto vehicle_predicted_path = util::convertToPredictedPath(
path, current_twist, current_pose, static_cast<double>(current_seg_idx), check_end_time,
time_resolution, acceleration, min_lc_speed);
const auto & vehicle_info = common_parameters.vehicle_info;
auto in_lane_object_indices = dynamic_objects_indices.target_lane;
in_lane_object_indices.insert(
in_lane_object_indices.end(), dynamic_objects_indices.current_lane.begin(),
dynamic_objects_indices.current_lane.end());
RCLCPP_DEBUG(
rclcpp::get_logger("lane_change"), "number of object -> total: %lu, in lane: %lu, others: %lu",
dynamic_objects->objects.size(), in_lane_object_indices.size(),
dynamic_objects_indices.other_lane.size());
const auto assignDebugData = [](const PredictedObject & obj) {
CollisionCheckDebug debug;
const auto key = util::getUuidStr(obj);
debug.current_pose = obj.kinematics.initial_pose_with_covariance.pose;
debug.current_twist = obj.kinematics.initial_twist_with_covariance.twist;
return std::make_pair(key, debug);
};
const auto appendDebugInfo =
[&debug_data](std::pair<std::string, CollisionCheckDebug> & obj, bool && is_allowed) {
const auto & key = obj.first;
auto & element = obj.second;
element.allow_lane_change = is_allowed;
if (debug_data.find(key) != debug_data.end()) {
debug_data[key] = element;
} else {
debug_data.insert(obj);
}
};
const auto reserve_size =
static_cast<size_t>((check_end_time - check_start_time) / time_resolution);
std::vector<double> check_durations{};
std::vector<std::pair<Pose, tier4_autoware_utils::Polygon2d>> interpolated_ego{};
check_durations.reserve(reserve_size);
interpolated_ego.reserve(reserve_size);
{
Pose expected_ego_pose = current_pose;
for (double t = check_start_time; t < check_end_time; t += time_resolution) {
std::string failed_reason;
tier4_autoware_utils::Polygon2d ego_polygon;
[[maybe_unused]] const auto get_ego_info = util::getEgoExpectedPoseAndConvertToPolygon(
current_pose, vehicle_predicted_path, ego_polygon, t, vehicle_info, expected_ego_pose,
failed_reason);
check_durations.push_back(t);
interpolated_ego.emplace_back(expected_ego_pose, ego_polygon);
}
}
for (const auto & i : in_lane_object_indices) {
const auto & obj = dynamic_objects->objects.at(i);
auto current_debug_data = assignDebugData(obj);
const auto predicted_paths =
util::getPredictedPathFromObj(obj, lane_change_parameters.use_all_predicted_path);
for (const auto & obj_path : predicted_paths) {
if (!util::isSafeInLaneletCollisionCheck(
interpolated_ego, current_twist, check_durations, lane_change_path.duration.prepare,
obj, obj_path, common_parameters,
lane_change_parameters.prepare_phase_ignore_target_speed_thresh, front_decel,
rear_decel, ego_pose_before_collision, current_debug_data.second)) {
appendDebugInfo(current_debug_data, false);
return false;
}
}
appendDebugInfo(current_debug_data, true);
}
if (!lane_change_parameters.use_predicted_path_outside_lanelet) {
return true;
}
for (const auto & i : dynamic_objects_indices.other_lane) {
const auto & obj = dynamic_objects->objects.at(i);
auto current_debug_data = assignDebugData(obj);
current_debug_data.second.ego_predicted_path.push_back(vehicle_predicted_path);
const auto predicted_paths =
util::getPredictedPathFromObj(obj, lane_change_parameters.use_all_predicted_path);
if (!util::isSafeInFreeSpaceCollisionCheck(
interpolated_ego, current_twist, check_durations, lane_change_path.duration.prepare, obj,
common_parameters, lane_change_parameters.prepare_phase_ignore_target_speed_thresh,
front_decel, rear_decel, current_debug_data.second)) {
appendDebugInfo(current_debug_data, false);
return false;
}
appendDebugInfo(current_debug_data, true);
}
return true;
}
ShiftLine getLaneChangingShiftLine(
const PathWithLaneId & prepare_segment, const PathWithLaneId & lane_changing_segment,
const lanelet::ConstLanelets & target_lanes, const PathWithLaneId & reference_path)
{
const Pose & lane_changing_start_pose = prepare_segment.points.back().point.pose;
const Pose & lane_changing_end_pose = lane_changing_segment.points.front().point.pose;
ShiftLine shift_line;
shift_line.end_shift_length =
lanelet::utils::getLateralDistanceToClosestLanelet(target_lanes, lane_changing_start_pose);
shift_line.start = lane_changing_start_pose;
shift_line.end = lane_changing_end_pose;
shift_line.start_idx =
motion_utils::findNearestIndex(reference_path.points, lane_changing_start_pose.position);
shift_line.end_idx =
motion_utils::findNearestIndex(reference_path.points, lane_changing_end_pose.position);
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("getLaneChangingShiftLine"),
"shift_line distance: %f",
util::getSignedDistance(shift_line.start, shift_line.end, target_lanes));
return shift_line;
}
PathWithLaneId getPrepareSegment(
const RouteHandler & route_handler, const lanelet::ConstLanelets & original_lanelets,
const double arc_length_from_current, const double backward_path_length,
const double prepare_distance, const double prepare_speed)
{
if (original_lanelets.empty()) {
return PathWithLaneId();
}
const double s_start = arc_length_from_current - backward_path_length;
const double s_end = arc_length_from_current + prepare_distance;
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("getPrepareSegment"),
"start: %f, end: %f", s_start, s_end);
PathWithLaneId prepare_segment =
route_handler.getCenterLinePath(original_lanelets, s_start, s_end);
prepare_segment.points.back().point.longitudinal_velocity_mps = std::min(
prepare_segment.points.back().point.longitudinal_velocity_mps,
static_cast<float>(prepare_speed));
return prepare_segment;
}
PathWithLaneId getPrepareSegment(
const PathWithLaneId & original_path, const lanelet::ConstLanelets & original_lanelets,
const Pose & current_pose, const double backward_path_length, const double prepare_distance,
const double prepare_speed)
{
if (original_lanelets.empty()) {
return PathWithLaneId();
}
auto prepare_segment = original_path;
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prepare_segment.points, current_pose, 3.0, 1.0);
util::clipPathLength(prepare_segment, current_seg_idx, prepare_distance, backward_path_length);
prepare_segment.points.back().point.longitudinal_velocity_mps = std::min(
prepare_segment.points.back().point.longitudinal_velocity_mps,
static_cast<float>(prepare_speed));
return prepare_segment;
}
std::pair<double, double> calcLaneChangingSpeedAndDistance(
const double velocity, const double shift_length, const double deceleration,
const double min_total_lc_len, const BehaviorPathPlannerParameters & com_param,
const LaneChangeParameters & lc_param)
{
const auto required_time = PathShifter::calcShiftTimeFromJerkAndJerk(
shift_length, lc_param.lane_changing_lateral_jerk, lc_param.lane_changing_lateral_acc);
const auto lane_changing_average_speed =
std::max(velocity + deceleration * 0.5 * required_time, lc_param.minimum_lane_change_velocity);
const auto expected_dist = lane_changing_average_speed * required_time;
const auto lane_changing_distance =
(expected_dist < min_total_lc_len) ? expected_dist : com_param.minimum_lane_change_length;
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("calcLaneChangingSpeedAndDistance"),
"required_time: %f [s] average_speed: %f [m/s], lane_changing_distance : %f [m]", required_time,
lane_changing_average_speed, lane_changing_distance);
return {lane_changing_average_speed, lane_changing_distance};
}
PathWithLaneId getLaneChangingSegment(
const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanelets,
const double forward_path_length, const double arc_length_from_target,
const double target_lane_length, const LaneChangePhaseInfo dist_prepare_to_lc_end,
const double lane_changing_speed, const double total_required_min_dist)
{
const double s_start = std::invoke([&arc_length_from_target, &dist_prepare_to_lc_end,
&target_lane_length, &total_required_min_dist]() {
const double dist_from_current_pose = arc_length_from_target + dist_prepare_to_lc_end.sum();
const double end_of_lane_dist_without_buffer = target_lane_length - total_required_min_dist;
return std::min(dist_from_current_pose, end_of_lane_dist_without_buffer);
});
const double s_end =
std::invoke([&s_start, &forward_path_length, &target_lane_length, &total_required_min_dist]() {
const double dist_from_start = s_start + forward_path_length;
const double dist_from_end = target_lane_length - total_required_min_dist;
return std::max(
std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits<double>::epsilon());
});
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("getLaneChangingSegment"),
"start: %f, end: %f", s_start, s_end);
PathWithLaneId lane_changing_segment =
route_handler.getCenterLinePath(target_lanelets, s_start, s_end);
for (auto & point : lane_changing_segment.points) {
point.point.longitudinal_velocity_mps =
std::min(point.point.longitudinal_velocity_mps, static_cast<float>(lane_changing_speed));
}
return lane_changing_segment;
}
PathWithLaneId getReferencePathFromTargetLane(
const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes,
const Pose & lane_changing_start_pose, const double target_lane_length,
const double lane_changing_distance, const double min_total_lane_changing_distance,
const double forward_path_length, const double resample_interval, const bool is_goal_in_route)
{
const ArcCoordinates lane_change_start_arc_position =
lanelet::utils::getArcCoordinates(target_lanes, lane_changing_start_pose);
const double s_start = lane_change_start_arc_position.length;
const double s_end = std::invoke([&]() {
const auto dist_from_lc_start = s_start + lane_changing_distance + forward_path_length;
if (is_goal_in_route) {
const auto goal_arc_coordinates =
lanelet::utils::getArcCoordinates(target_lanes, route_handler.getGoalPose());
const auto dist_to_goal = goal_arc_coordinates.length - min_total_lane_changing_distance;
return std::min(dist_from_lc_start, dist_to_goal);
}
const auto dist_from_end = target_lane_length - min_total_lane_changing_distance;
return std::min(dist_from_lc_start, dist_from_end);
});
RCLCPP_DEBUG(
rclcpp::get_logger("behavior_path_planner")
.get_child("lane_change")
.get_child("util")
.get_child("getReferencePathFromTargetLane"),
"start: %f, end: %f", s_start, s_end);
const auto lane_changing_reference_path =
route_handler.getCenterLinePath(target_lanes, s_start, s_end);
return util::resamplePathWithSpline(
lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_distance});
}
bool isEgoWithinOriginalLane(
const lanelet::ConstLanelets & current_lanes, const Pose & current_pose,
const BehaviorPathPlannerParameters & common_param)
{
const auto lane_length = lanelet::utils::getLaneletLength2d(current_lanes);
const auto lane_poly = lanelet::utils::getPolygonFromArcLength(current_lanes, 0, lane_length);
const auto vehicle_poly =
util::getVehiclePolygon(current_pose, common_param.vehicle_width, common_param.base_link2front);
return boost::geometry::within(
lanelet::utils::to2D(vehicle_poly).basicPolygon(),
lanelet::utils::to2D(lane_poly).basicPolygon());
}
void get_turn_signal_info(
const LaneChangePath & lane_change_path, TurnSignalInfo * turn_signal_info)
{
turn_signal_info->desired_start_point = lane_change_path.turn_signal_info.desired_start_point;
turn_signal_info->required_start_point = lane_change_path.turn_signal_info.required_start_point;
turn_signal_info->required_end_point = lane_change_path.turn_signal_info.required_end_point;
turn_signal_info->desired_end_point = lane_change_path.turn_signal_info.desired_end_point;
}
std::vector<DrivableLanes> generateDrivableLanes(
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & lane_change_lanes)
{
size_t current_lc_idx = 0;
std::vector<DrivableLanes> drivable_lanes(current_lanes.size());
for (size_t i = 0; i < current_lanes.size(); ++i) {
const auto & current_lane = current_lanes.at(i);
drivable_lanes.at(i).left_lane = current_lane;
drivable_lanes.at(i).right_lane = current_lane;
const auto left_lane = route_handler.getLeftLanelet(current_lane);
const auto right_lane = route_handler.getRightLanelet(current_lane);
if (!left_lane && !right_lane) {
continue;
}
for (size_t lc_idx = current_lc_idx; lc_idx < lane_change_lanes.size(); ++lc_idx) {
const auto & lc_lane = lane_change_lanes.at(lc_idx);
if (left_lane && lc_lane.id() == left_lane->id()) {
drivable_lanes.at(i).left_lane = lc_lane;
current_lc_idx = lc_idx;
break;
}
if (right_lane && lc_lane.id() == right_lane->id()) {
drivable_lanes.at(i).right_lane = lc_lane;
current_lc_idx = lc_idx;
break;
}
}
}
for (size_t i = current_lc_idx + 1; i < lane_change_lanes.size(); ++i) {
const auto & lc_lane = lane_change_lanes.at(i);
DrivableLanes drivable_lane;
drivable_lane.left_lane = lc_lane;
drivable_lane.right_lane = lc_lane;
drivable_lanes.push_back(drivable_lane);
}
return drivable_lanes;
}
std::optional<LaneChangePath> getAbortPaths(
const std::shared_ptr<const PlannerData> & planner_data, const LaneChangePath & selected_path,
[[maybe_unused]] const Pose & ego_pose_before_collision,
const BehaviorPathPlannerParameters & common_param,
[[maybe_unused]] const LaneChangeParameters & lane_change_param)
{
const auto & route_handler = planner_data->route_handler;
const auto current_speed = planner_data->self_odometry->twist.twist.linear.x;
const auto current_pose = planner_data->self_odometry->pose.pose;
const auto reference_lanelets = selected_path.reference_lanelets;
const auto ego_nearest_dist_threshold = planner_data->parameters.ego_nearest_dist_threshold;
const auto ego_nearest_yaw_threshold = planner_data->parameters.ego_nearest_yaw_threshold;
const double minimum_lane_change_length = util::calcLaneChangeBuffer(common_param, 1);
const auto & lane_changing_path = selected_path.path;
const auto lane_changing_end_pose_idx = std::invoke([&]() {
constexpr double s_start = 0.0;
const double s_end =
lanelet::utils::getLaneletLength2d(reference_lanelets) - minimum_lane_change_length;
const auto ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end);
return motion_utils::findFirstNearestIndexWithSoftConstraints(
lane_changing_path.points, ref.points.back().point.pose, ego_nearest_dist_threshold,
ego_nearest_yaw_threshold);
});
const auto ego_pose_idx = motion_utils::findFirstNearestIndexWithSoftConstraints(
lane_changing_path.points, current_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold);
const auto get_abort_idx_and_distance = [&](const double param_time) {
double turning_point_dist{0.0};
if (ego_pose_idx > lane_changing_end_pose_idx) {
return std::make_pair(ego_pose_idx, turning_point_dist);
}
constexpr auto min_speed{2.77};
const auto desired_distance = std::max(min_speed, current_speed) * param_time;
const auto & points = lane_changing_path.points;
size_t idx{0};
for (idx = ego_pose_idx; idx < lane_changing_end_pose_idx; ++idx) {
const auto dist_to_ego =
util::getSignedDistance(current_pose, points.at(idx).point.pose, reference_lanelets);
turning_point_dist = dist_to_ego;
if (dist_to_ego > desired_distance) {
break;
}
}
return std::make_pair(idx, turning_point_dist);
};
const auto abort_delta_time = lane_change_param.abort_delta_time;
const auto [abort_start_idx, abort_start_dist] = get_abort_idx_and_distance(abort_delta_time);
const auto [abort_return_idx, abort_return_dist] =
get_abort_idx_and_distance(abort_delta_time * 2);
if (abort_start_idx >= abort_return_idx) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"abort start idx and return idx is equal. can't compute abort path.");
return std::nullopt;
}
if (!hasEnoughDistanceToLaneChangeAfterAbort(
*route_handler, reference_lanelets, current_pose, abort_return_dist, common_param)) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"insufficient distance to abort.");
return std::nullopt;
}
const auto abort_start_pose = lane_changing_path.points.at(abort_start_idx).point.pose;
const auto abort_return_pose = lane_changing_path.points.at(abort_return_idx).point.pose;
const auto arc_position =
lanelet::utils::getArcCoordinates(reference_lanelets, abort_return_pose);
const PathWithLaneId reference_lane_segment = std::invoke([&]() {
const double minimum_lane_change_length =
common_param.backward_length_buffer_for_end_of_lane + common_param.minimum_lane_change_length;
const double s_start = arc_position.length;
double s_end =
lanelet::utils::getLaneletLength2d(reference_lanelets) - minimum_lane_change_length;
if (route_handler->isInGoalRouteSection(selected_path.target_lanelets.back())) {
const auto goal_arc_coordinates = lanelet::utils::getArcCoordinates(
selected_path.target_lanelets, route_handler->getGoalPose());
s_end = std::min(s_end, goal_arc_coordinates.length) - minimum_lane_change_length;
}
PathWithLaneId ref = route_handler->getCenterLinePath(reference_lanelets, s_start, s_end);
ref.points.back().point.longitudinal_velocity_mps = std::min(
ref.points.back().point.longitudinal_velocity_mps,
static_cast<float>(lane_change_param.minimum_lane_change_velocity));
return ref;
});
ShiftLine shift_line;
shift_line.start = abort_start_pose;
shift_line.end = abort_return_pose;
shift_line.end_shift_length = -arc_position.distance;
shift_line.start_idx = abort_start_idx;
shift_line.end_idx = abort_return_idx;
PathShifter path_shifter;
path_shifter.setPath(lane_changing_path);
path_shifter.addShiftLine(shift_line);
const auto lateral_jerk = behavior_path_planner::PathShifter::calcJerkFromLatLonDistance(
shift_line.end_shift_length, abort_start_dist, current_speed);
if (lateral_jerk > lane_change_param.abort_max_lateral_jerk) {
return std::nullopt;
}
ShiftedPath shifted_path;
// offset front side
// bool offset_back = false;
if (!path_shifter.generate(&shifted_path)) {
RCLCPP_ERROR_STREAM(
rclcpp::get_logger("behavior_path_planner").get_child("lane_change").get_child("util"),
"failed to generate abort shifted path.");
}
PathWithLaneId start_to_abort_return_pose;
start_to_abort_return_pose.points.insert(
start_to_abort_return_pose.points.end(), shifted_path.path.points.begin(),
shifted_path.path.points.begin() + abort_return_idx);
start_to_abort_return_pose.points.insert(
start_to_abort_return_pose.points.end(), reference_lane_segment.points.begin(),
reference_lane_segment.points.end());
auto abort_path = selected_path;
abort_path.shifted_path = shifted_path;
abort_path.path = start_to_abort_return_pose;
abort_path.shift_line = shift_line;
return std::optional<LaneChangePath>{abort_path};
}
double getLateralShift(const LaneChangePath & path)
{
const auto start_idx = path.shift_line.start_idx;
const auto end_idx = path.shift_line.end_idx;
return path.shifted_path.shift_length.at(end_idx) - path.shifted_path.shift_length.at(start_idx);
}
bool hasEnoughDistanceToLaneChangeAfterAbort(
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
const Pose & current_pose, const double abort_return_dist,