forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathscene.cpp
2121 lines (1765 loc) · 84.2 KB
/
scene.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 2023 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_lane_change_module/scene.hpp"
#include "behavior_path_lane_change_module/utils/utils.hpp"
#include "behavior_path_planner_common/marker_utils/utils.hpp"
#include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp"
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
#include <lanelet2_core/geometry/Point.h>
#include <lanelet2_core/geometry/Polygon.h>
#include <algorithm>
#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>
namespace behavior_path_planner
{
using motion_utils::calcSignedArcLength;
using utils::traffic_light::getDistanceToNextTrafficLight;
NormalLaneChange::NormalLaneChange(
const std::shared_ptr<LaneChangeParameters> & parameters, LaneChangeModuleType type,
Direction direction)
: LaneChangeBase(parameters, type, direction)
{
stop_watch_.tic(getModuleTypeStr());
stop_watch_.tic("stop_time");
}
void NormalLaneChange::updateLaneChangeStatus()
{
updateStopTime();
const auto [found_valid_path, found_safe_path] = getSafePath(status_.lane_change_path);
// Update status
status_.current_lanes = status_.lane_change_path.info.current_lanes;
status_.target_lanes = status_.lane_change_path.info.target_lanes;
status_.is_valid_path = found_valid_path;
status_.is_safe = found_safe_path;
status_.lane_follow_lane_ids = utils::getIds(status_.current_lanes);
status_.lane_change_lane_ids = utils::getIds(status_.target_lanes);
const auto arclength_start =
lanelet::utils::getArcCoordinates(status_.target_lanes, getEgoPose());
status_.start_distance = arclength_start.length;
status_.lane_change_path.path.header = getRouteHeader();
}
std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path) const
{
const auto current_lanes = getCurrentLanes();
if (current_lanes.empty()) {
return {false, false};
}
const auto target_lanes = getLaneChangeLanes(current_lanes, direction_);
if (target_lanes.empty()) {
return {false, false};
}
// find candidate paths
LaneChangePaths valid_paths{};
const bool is_stuck = isVehicleStuck(current_lanes);
bool found_safe_path = getLaneChangePaths(
current_lanes, target_lanes, direction_, &valid_paths, lane_change_parameters_->rss_params,
is_stuck);
// if no safe path is found and ego is stuck, try to find a path with a small margin
if (!found_safe_path && is_stuck) {
found_safe_path = getLaneChangePaths(
current_lanes, target_lanes, direction_, &valid_paths,
lane_change_parameters_->rss_params_for_stuck, is_stuck);
}
debug_valid_path_ = valid_paths;
if (valid_paths.empty()) {
safe_path.info.current_lanes = current_lanes;
safe_path.info.target_lanes = target_lanes;
return {false, false};
}
if (found_safe_path) {
safe_path = valid_paths.back();
} else {
// force candidate
safe_path = valid_paths.front();
}
return {true, found_safe_path};
}
bool NormalLaneChange::isLaneChangeRequired()
{
status_.current_lanes = getCurrentLanes();
if (status_.current_lanes.empty()) {
return false;
}
status_.target_lanes = getLaneChangeLanes(status_.current_lanes, direction_);
return !status_.target_lanes.empty();
}
bool NormalLaneChange::isStoppedAtRedTrafficLight() const
{
return utils::traffic_light::isStoppedAtRedTrafficLightWithinDistance(
status_.current_lanes, status_.lane_change_path.path, planner_data_,
status_.lane_change_path.info.length.sum());
}
LaneChangePath NormalLaneChange::getLaneChangePath() const
{
return status_.lane_change_path;
}
BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const
{
BehaviorModuleOutput output;
if (isAbortState() && abort_path_) {
output.path = abort_path_->path;
output.reference_path = prev_module_reference_path_;
output.turn_signal_info = prev_turn_signal_info_;
extendOutputDrivableArea(output);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
return output;
}
const auto current_lanes = getCurrentLanes();
if (current_lanes.empty()) {
RCLCPP_WARN(logger_, "Current lanes not found!!! Something wrong.");
output.path = prev_module_path_;
output.reference_path = prev_module_reference_path_;
output.drivable_area_info = prev_drivable_area_info_;
output.turn_signal_info = prev_turn_signal_info_;
return output;
}
const auto terminal_path =
calcTerminalLaneChangePath(current_lanes, getLaneChangeLanes(current_lanes, direction_));
if (!terminal_path) {
RCLCPP_DEBUG(logger_, "Terminal path not found!!!");
output.path = prev_module_path_;
output.reference_path = prev_module_reference_path_;
output.drivable_area_info = prev_drivable_area_info_;
output.turn_signal_info = prev_turn_signal_info_;
return output;
}
output.path = terminal_path->path;
output.reference_path = prev_module_reference_path_;
output.turn_signal_info = updateOutputTurnSignal();
extendOutputDrivableArea(output);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
return output;
}
BehaviorModuleOutput NormalLaneChange::generateOutput()
{
BehaviorModuleOutput output;
if (!status_.is_valid_path) {
output.path = prev_module_path_;
output.reference_path = prev_module_reference_path_;
output.drivable_area_info = prev_drivable_area_info_;
output.turn_signal_info = prev_turn_signal_info_;
return output;
}
if (isAbortState() && abort_path_) {
output.path = abort_path_->path;
output.reference_path = prev_module_reference_path_;
output.turn_signal_info = prev_turn_signal_info_;
insertStopPoint(status_.current_lanes, output.path);
} else {
output.path = getLaneChangePath().path;
const auto found_extended_path = extendPath();
if (found_extended_path) {
output.path = utils::combinePath(output.path, *found_extended_path);
}
output.reference_path = getReferencePath();
output.turn_signal_info = updateOutputTurnSignal();
if (isStopState()) {
const auto current_velocity = getEgoVelocity();
const auto current_dist = calcSignedArcLength(
output.path.points, output.path.points.front().point.pose.position, getEgoPosition());
const auto stop_dist =
-(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc));
const auto stop_point = utils::insertStopPoint(stop_dist + current_dist, output.path);
setStopPose(stop_point.point.pose);
} else {
insertStopPoint(status_.target_lanes, output.path);
}
}
extendOutputDrivableArea(output);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
return output;
}
void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const
{
const auto & dp = planner_data_->drivable_area_expansion_parameters;
const auto drivable_lanes = utils::lane_change::generateDrivableLanes(
*getRouteHandler(), status_.current_lanes, status_.target_lanes);
const auto shorten_lanes = utils::cutOverlappedLanes(output.path, drivable_lanes);
const auto expanded_lanes = utils::expandLanelets(
shorten_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
dp.drivable_area_types_to_skip);
// for new architecture
DrivableAreaInfo current_drivable_area_info;
current_drivable_area_info.drivable_lanes = expanded_lanes;
output.drivable_area_info =
utils::combineDrivableAreaInfo(current_drivable_area_info, prev_drivable_area_info_);
}
void NormalLaneChange::insertStopPoint(
const lanelet::ConstLanelets & lanelets, PathWithLaneId & path)
{
if (lanelets.empty()) {
return;
}
const auto & route_handler = getRouteHandler();
if (route_handler->getNumLaneToPreferredLane(lanelets.back()) == 0) {
return;
}
const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back());
const double lane_change_buffer =
utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0);
const auto getDistanceAlongLanelet = [&](const geometry_msgs::msg::Pose & target) {
return utils::getSignedDistance(path.points.front().point.pose, target, lanelets);
};
// If lanelets.back() is in goal route section, get distance to goal.
// Otherwise, get distance to end of lane.
double distance_to_terminal = 0.0;
if (route_handler->isInGoalRouteSection(lanelets.back())) {
const auto goal = route_handler->getGoalPose();
distance_to_terminal = getDistanceAlongLanelet(goal);
} else {
distance_to_terminal = utils::getDistanceToEndOfLane(path.points.front().point.pose, lanelets);
}
const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane;
const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes);
double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer;
const auto is_valid_start_point = std::invoke([&]() -> bool {
auto lc_start_point = lanelet::utils::conversion::toLaneletPoint(
status_.lane_change_path.info.lane_changing_start.position);
const auto target_neighbor_preferred_lane_poly_2d =
utils::lane_change::getTargetNeighborLanesPolygon(
*route_handler, status_.current_lanes, type_);
return boost::geometry::covered_by(
lanelet::traits::to2D(lc_start_point), target_neighbor_preferred_lane_poly_2d);
});
if (!is_valid_start_point) {
const auto stop_point = utils::insertStopPoint(stopping_distance, path);
setStopPose(stop_point.point.pose);
return;
}
// calculate minimum distance from path front to the stationary object on the ego lane.
const auto distance_to_ego_lane_obj = [&]() -> double {
double distance_to_obj = distance_to_terminal;
const double distance_to_ego = getDistanceAlongLanelet(getEgoPose());
for (const auto & object : target_objects.current_lane) {
// check if stationary
const auto obj_v = std::abs(object.initial_twist.twist.linear.x);
if (obj_v > lane_change_parameters_->stop_velocity_threshold) {
continue;
}
// calculate distance from path front to the stationary object polygon on the ego lane.
const auto polygon =
tier4_autoware_utils::toPolygon2d(object.initial_pose.pose, object.shape).outer();
for (const auto & polygon_p : polygon) {
const auto p_fp = tier4_autoware_utils::toMsg(polygon_p.to_3d());
const auto lateral_fp = motion_utils::calcLateralOffset(path.points, p_fp);
// ignore if the point is around the ego path
if (std::abs(lateral_fp) > planner_data_->parameters.vehicle_width) {
continue;
}
const double current_distance_to_obj = calcSignedArcLength(path.points, 0, p_fp);
// ignore backward object
if (current_distance_to_obj < distance_to_ego) {
continue;
}
distance_to_obj = std::min(distance_to_obj, current_distance_to_obj);
}
}
return distance_to_obj;
}();
// Need to stop before blocking obstacle
if (distance_to_ego_lane_obj < distance_to_terminal) {
// consider rss distance when the LC need to avoid obstacles
const auto rss_dist = calcRssDistance(
0.0, lane_change_parameters_->minimum_lane_changing_velocity,
lane_change_parameters_->rss_params);
const double lane_change_buffer_for_blocking_object =
utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals);
const auto stopping_distance_for_obj =
distance_to_ego_lane_obj - lane_change_buffer_for_blocking_object -
lane_change_parameters_->backward_length_buffer_for_blocking_object - rss_dist -
getCommonParam().base_link2front;
// If the target lane in the lane change section is blocked by a stationary obstacle, there
// is no reason for stopping with a lane change margin. Instead, stop right behind the
// obstacle.
// ----------------------------------------------------------
// [obj]>
// ----------------------------------------------------------
// [ego]> | <--- lane change margin ---> [obj]>
// ----------------------------------------------------------
const bool has_blocking_target_lane_obj = std::any_of(
target_objects.target_lane.begin(), target_objects.target_lane.end(), [&](const auto & o) {
const auto v = std::abs(o.initial_twist.twist.linear.x);
if (v > lane_change_parameters_->stop_velocity_threshold) {
return false;
}
// target_objects includes objects out of target lanes, so filter them out
if (!boost::geometry::intersects(
tier4_autoware_utils::toPolygon2d(o.initial_pose.pose, o.shape).outer(),
lanelet::utils::combineLaneletsShape(status_.target_lanes)
.polygon2d()
.basicPolygon())) {
return false;
}
const double distance_to_target_lane_obj = getDistanceAlongLanelet(o.initial_pose.pose);
return stopping_distance_for_obj < distance_to_target_lane_obj &&
distance_to_target_lane_obj < distance_to_ego_lane_obj;
});
if (!has_blocking_target_lane_obj) {
stopping_distance = stopping_distance_for_obj;
}
}
if (stopping_distance > 0.0) {
const auto stop_point = utils::insertStopPoint(stopping_distance, path);
setStopPose(stop_point.point.pose);
}
}
PathWithLaneId NormalLaneChange::getReferencePath() const
{
return utils::getCenterLinePathFromRootLanelet(
status_.lane_change_path.info.target_lanes.front(), planner_data_);
}
std::optional<PathWithLaneId> NormalLaneChange::extendPath()
{
const auto path = status_.lane_change_path.path;
const auto lc_start_point = status_.lane_change_path.info.lane_changing_start.position;
const auto dist = calcSignedArcLength(path.points, lc_start_point, getEgoPosition());
if (dist < 0.0) {
return std::nullopt;
}
auto & target_lanes = status_.target_lanes;
const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes);
const auto dist_in_target = lanelet::utils::getArcCoordinates(target_lanes, getEgoPose());
const auto forward_path_length = getCommonParam().forward_path_length;
if ((target_lane_length - dist_in_target.length) > forward_path_length) {
return std::nullopt;
}
const auto is_goal_in_target = getRouteHandler()->isInGoalRouteSection(target_lanes.back());
if (is_goal_in_target) {
const auto goal_pose = getRouteHandler()->getGoalPose();
const auto dist_to_goal = lanelet::utils::getArcCoordinates(target_lanes, goal_pose).length;
const auto dist_to_end_of_path =
lanelet::utils::getArcCoordinates(target_lanes, path.points.back().point.pose).length;
return getRouteHandler()->getCenterLinePath(target_lanes, dist_to_end_of_path, dist_to_goal);
}
lanelet::ConstLanelet next_lane;
if (!getRouteHandler()->getNextLaneletWithinRoute(target_lanes.back(), &next_lane)) {
return std::nullopt;
}
target_lanes.push_back(next_lane);
const auto target_pose = std::invoke([&]() {
const auto is_goal_in_next_lane = getRouteHandler()->isInGoalRouteSection(next_lane);
if (is_goal_in_next_lane) {
return getRouteHandler()->getGoalPose();
}
Pose back_pose;
const auto back_point =
lanelet::utils::conversion::toGeomMsgPt(next_lane.centerline2d().back());
const double front_yaw = lanelet::utils::getLaneletAngle(next_lane, back_point);
back_pose.position = back_point;
tf2::Quaternion tf_quat;
tf_quat.setRPY(0, 0, front_yaw);
back_pose.orientation = tf2::toMsg(tf_quat);
return back_pose;
});
const auto dist_to_target_pose =
lanelet::utils::getArcCoordinates(target_lanes, target_pose).length;
const auto dist_to_end_of_path =
lanelet::utils::getArcCoordinates(target_lanes, path.points.back().point.pose).length;
return getRouteHandler()->getCenterLinePath(
target_lanes, dist_to_end_of_path, dist_to_target_pose);
}
void NormalLaneChange::resetParameters()
{
is_abort_path_approved_ = false;
is_abort_approval_requested_ = false;
current_lane_change_state_ = LaneChangeStates::Normal;
abort_path_ = nullptr;
status_ = {};
object_debug_.clear();
object_debug_after_approval_.clear();
debug_filtered_objects_.current_lane.clear();
debug_filtered_objects_.target_lane.clear();
debug_filtered_objects_.other_lane.clear();
debug_valid_path_.clear();
RCLCPP_DEBUG(logger_, "reset all flags and debug information.");
}
TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const
{
TurnSignalInfo turn_signal_info = calcTurnSignalInfo();
const auto [turn_signal_command, distance_to_vehicle_front] = utils::getPathTurnSignal(
status_.current_lanes, status_.lane_change_path.shifted_path,
status_.lane_change_path.info.shift_line, getEgoPose(), getEgoTwist().linear.x,
planner_data_->parameters);
turn_signal_info.turn_signal.command = turn_signal_command.command;
return turn_signal_info;
}
lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const
{
return utils::getCurrentLanesFromPath(prev_module_path_, planner_data_);
}
lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes(
const lanelet::ConstLanelets & current_lanes, Direction direction) const
{
if (current_lanes.empty()) {
return {};
}
// Get lane change lanes
const auto & route_handler = getRouteHandler();
const auto lane_change_lane = utils::lane_change::getLaneChangeTargetLane(
*getRouteHandler(), current_lanes, type_, direction);
if (!lane_change_lane) {
return {};
}
const auto front_pose = std::invoke([&lane_change_lane]() {
const auto & p = lane_change_lane->centerline().front();
const auto front_point = lanelet::utils::conversion::toGeomMsgPt(p);
const auto front_yaw = lanelet::utils::getLaneletAngle(*lane_change_lane, front_point);
geometry_msgs::msg::Pose front_pose;
front_pose.position = front_point;
tf2::Quaternion quat;
quat.setRPY(0, 0, front_yaw);
front_pose.orientation = tf2::toMsg(quat);
return front_pose;
});
const auto forward_length = std::invoke([&]() {
const auto signed_distance = utils::getSignedDistance(front_pose, getEgoPose(), current_lanes);
const auto forward_path_length = planner_data_->parameters.forward_path_length;
if (signed_distance <= 0.0) {
return forward_path_length;
}
return signed_distance + forward_path_length;
});
const auto backward_length = lane_change_parameters_->backward_lane_length;
return route_handler->getLaneletSequence(
lane_change_lane.value(), getEgoPose(), backward_length, forward_length);
}
bool NormalLaneChange::isNearEndOfCurrentLanes(
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
const double threshold) const
{
if (current_lanes.empty()) {
return false;
}
const auto & route_handler = getRouteHandler();
const auto & current_pose = getEgoPose();
const auto shift_intervals =
route_handler->getLateralIntervalsToPreferredLane(current_lanes.back());
const auto lane_change_buffer =
utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals);
auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes);
if (!target_lanes.empty() && route_handler->isInGoalRouteSection(target_lanes.back())) {
distance_to_end = std::min(
distance_to_end,
utils::getSignedDistance(current_pose, route_handler->getGoalPose(), current_lanes));
}
return (std::max(0.0, distance_to_end) - lane_change_buffer) < threshold;
}
bool NormalLaneChange::hasFinishedLaneChange() const
{
const auto & current_pose = getEgoPose();
const auto & lane_change_end = status_.lane_change_path.info.shift_line.end;
const double dist_to_lane_change_end = utils::getSignedDistance(
current_pose, lane_change_end, status_.lane_change_path.info.target_lanes);
double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer;
// If ego velocity is low, relax finish judge buffer
const double ego_velocity = getEgoVelocity();
if (std::abs(ego_velocity) < 1.0) {
finish_judge_buffer = 0.0;
}
const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0;
if (!reach_lane_change_end) {
return false;
}
const auto arc_length = lanelet::utils::getArcCoordinates(status_.target_lanes, current_pose);
const auto reach_target_lane =
std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold;
if (!reach_target_lane) {
return false;
}
return true;
}
bool NormalLaneChange::isAbleToReturnCurrentLane() const
{
if (status_.lane_change_path.path.points.size() < 2) {
return false;
}
if (!utils::isEgoWithinOriginalLane(
status_.current_lanes, getEgoPose(), planner_data_->parameters,
lane_change_parameters_->cancel.overhang_tolerance)) {
return false;
}
const auto nearest_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
status_.lane_change_path.path.points, getEgoPose(),
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
const double ego_velocity =
std::max(getEgoVelocity(), lane_change_parameters_->minimum_lane_changing_velocity);
const double estimated_travel_dist = ego_velocity * lane_change_parameters_->cancel.delta_time;
double dist = 0.0;
for (size_t idx = nearest_idx; idx < status_.lane_change_path.path.points.size() - 1; ++idx) {
dist += calcSignedArcLength(status_.lane_change_path.path.points, idx, idx + 1);
if (dist > estimated_travel_dist) {
const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose;
return utils::isEgoWithinOriginalLane(
status_.current_lanes, estimated_pose, planner_data_->parameters,
lane_change_parameters_->cancel.overhang_tolerance);
}
}
return true;
}
bool NormalLaneChange::isEgoOnPreparePhase() const
{
const auto & start_position = status_.lane_change_path.info.shift_line.start.position;
const auto & path_points = status_.lane_change_path.path.points;
return calcSignedArcLength(path_points, start_position, getEgoPosition()) < 0.0;
}
bool NormalLaneChange::isAbleToStopSafely() const
{
if (status_.lane_change_path.path.points.size() < 2) {
return false;
}
const auto nearest_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
status_.lane_change_path.path.points, getEgoPose(),
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
const auto current_velocity = getEgoVelocity();
const auto stop_dist =
-(current_velocity * current_velocity / (2.0 * planner_data_->parameters.min_acc));
double dist = 0.0;
for (size_t idx = nearest_idx; idx < status_.lane_change_path.path.points.size() - 1; ++idx) {
dist += calcSignedArcLength(status_.lane_change_path.path.points, idx, idx + 1);
if (dist > stop_dist) {
const auto & estimated_pose = status_.lane_change_path.path.points.at(idx + 1).point.pose;
return utils::isEgoWithinOriginalLane(
status_.current_lanes, estimated_pose, planner_data_->parameters);
}
}
return true;
}
bool NormalLaneChange::hasFinishedAbort() const
{
if (!abort_path_) {
return true;
}
const auto distance_to_finish = calcSignedArcLength(
abort_path_->path.points, getEgoPosition(), abort_path_->info.shift_line.end.position);
if (distance_to_finish < 0.0) {
return true;
}
return false;
}
bool NormalLaneChange::isAbortState() const
{
if (!lane_change_parameters_->cancel.enable_on_lane_changing_phase) {
return false;
}
if (current_lane_change_state_ != LaneChangeStates::Abort) {
return false;
}
if (!abort_path_) {
return false;
}
return true;
}
int NormalLaneChange::getNumToPreferredLane(const lanelet::ConstLanelet & lane) const
{
const auto get_opposite_direction =
(direction_ == Direction::RIGHT) ? Direction::LEFT : Direction::RIGHT;
return std::abs(getRouteHandler()->getNumLaneToPreferredLane(lane, get_opposite_direction));
}
std::pair<double, double> NormalLaneChange::calcCurrentMinMaxAcceleration() const
{
const auto & p = getCommonParam();
const auto vehicle_min_acc = std::max(p.min_acc, lane_change_parameters_->min_longitudinal_acc);
const auto vehicle_max_acc = std::min(p.max_acc, lane_change_parameters_->max_longitudinal_acc);
const auto ego_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prev_module_path_.points, getEgoPose(), p.ego_nearest_dist_threshold,
p.ego_nearest_yaw_threshold);
const auto max_path_velocity =
prev_module_path_.points.at(ego_seg_idx).point.longitudinal_velocity_mps;
// calculate minimum and maximum acceleration
const auto min_acc = utils::lane_change::calcMinimumAcceleration(
getEgoVelocity(), vehicle_min_acc, *lane_change_parameters_);
const auto max_acc = utils::lane_change::calcMaximumAcceleration(
getEgoVelocity(), max_path_velocity, vehicle_max_acc, *lane_change_parameters_);
return {min_acc, max_acc};
}
double NormalLaneChange::calcMaximumLaneChangeLength(
const lanelet::ConstLanelet & current_terminal_lanelet, const double max_acc) const
{
const auto shift_intervals =
getRouteHandler()->getLateralIntervalsToPreferredLane(current_terminal_lanelet);
return utils::lane_change::calcMaximumLaneChangeLength(
std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()),
*lane_change_parameters_, shift_intervals, max_acc);
}
std::vector<double> NormalLaneChange::sampleLongitudinalAccValues(
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const
{
if (prev_module_path_.points.empty()) {
return {};
}
const auto & route_handler = *getRouteHandler();
const auto current_pose = getEgoPose();
const auto longitudinal_acc_sampling_num = lane_change_parameters_->longitudinal_acc_sampling_num;
const auto [min_acc, max_acc] = calcCurrentMinMaxAcceleration();
// if max acc is not positive, then we do the normal sampling
if (max_acc <= 0.0) {
RCLCPP_DEBUG(
logger_, "Available max acc <= 0. Normal sampling for acc: [%f ~ %f]", min_acc, max_acc);
return utils::lane_change::getAccelerationValues(
min_acc, max_acc, longitudinal_acc_sampling_num);
}
// calculate maximum lane change length
const double max_lane_change_length = calcMaximumLaneChangeLength(current_lanes.back(), max_acc);
if (max_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) {
RCLCPP_DEBUG(
logger_, "No enough distance to the end of lane. Normal sampling for acc: [%f ~ %f]", min_acc,
max_acc);
return utils::lane_change::getAccelerationValues(
min_acc, max_acc, longitudinal_acc_sampling_num);
}
// If the ego is in stuck, sampling all possible accelerations to find avoiding path.
if (isVehicleStuck(current_lanes)) {
auto clock = rclcpp::Clock(RCL_ROS_TIME);
RCLCPP_INFO_THROTTLE(
logger_, clock, 1000, "Vehicle is in stuck. Sample all possible acc: [%f ~ %f]", min_acc,
max_acc);
return utils::lane_change::getAccelerationValues(
min_acc, max_acc, longitudinal_acc_sampling_num);
}
// if maximum lane change length is less than length to goal or the end of target lanes, only
// sample max acc
if (route_handler.isInGoalRouteSection(target_lanes.back())) {
const auto goal_pose = route_handler.getGoalPose();
if (max_lane_change_length < utils::getSignedDistance(current_pose, goal_pose, target_lanes)) {
RCLCPP_DEBUG(
logger_, "Distance to goal has enough distance. Sample only max_acc: %f", max_acc);
return {max_acc};
}
} else if (max_lane_change_length < utils::getDistanceToEndOfLane(current_pose, target_lanes)) {
RCLCPP_DEBUG(
logger_, "Distance to end of lane has enough distance. Sample only max_acc: %f", max_acc);
return {max_acc};
}
RCLCPP_DEBUG(logger_, "Normal sampling for acc: [%f ~ %f]", min_acc, max_acc);
return utils::lane_change::getAccelerationValues(min_acc, max_acc, longitudinal_acc_sampling_num);
}
std::vector<double> NormalLaneChange::calcPrepareDuration(
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const
{
const auto base_link2front = planner_data_->parameters.base_link2front;
const auto threshold =
lane_change_parameters_->min_length_for_turn_signal_activation + base_link2front;
std::vector<double> prepare_durations;
constexpr double step = 0.5;
for (double duration = lane_change_parameters_->lane_change_prepare_duration; duration >= 0.0;
duration -= step) {
prepare_durations.push_back(duration);
if (!isNearEndOfCurrentLanes(current_lanes, target_lanes, threshold)) {
break;
}
}
return prepare_durations;
}
PathWithLaneId NormalLaneChange::getPrepareSegment(
const lanelet::ConstLanelets & current_lanes, const double backward_path_length,
const double prepare_length) const
{
if (current_lanes.empty()) {
return PathWithLaneId();
}
auto prepare_segment = prev_module_path_;
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prepare_segment.points, getEgoPose(), 3.0, 1.0);
utils::clipPathLength(prepare_segment, current_seg_idx, prepare_length, backward_path_length);
return prepare_segment;
}
LaneChangeTargetObjects NormalLaneChange::getTargetObjects(
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const
{
const auto current_pose = getEgoPose();
const auto & route_handler = *getRouteHandler();
const auto & common_parameters = planner_data_->parameters;
auto objects = *planner_data_->dynamic_object;
utils::path_safety_checker::filterObjectsByClass(
objects, lane_change_parameters_->object_types_to_check);
// get backward lanes
const auto backward_length = lane_change_parameters_->backward_lane_length;
const auto target_backward_lanes = utils::lane_change::getBackwardLanelets(
route_handler, target_lanes, current_pose, backward_length);
// filter objects to get target object index
const auto target_obj_index =
filterObject(objects, current_lanes, target_lanes, target_backward_lanes);
LaneChangeTargetObjects target_objects;
target_objects.current_lane.reserve(target_obj_index.current_lane.size());
target_objects.target_lane.reserve(target_obj_index.target_lane.size());
target_objects.other_lane.reserve(target_obj_index.other_lane.size());
// objects in current lane
for (const auto & obj_idx : target_obj_index.current_lane) {
const auto extended_object = utils::lane_change::transform(
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
target_objects.current_lane.push_back(extended_object);
}
// objects in target lane
for (const auto & obj_idx : target_obj_index.target_lane) {
const auto extended_object = utils::lane_change::transform(
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
target_objects.target_lane.push_back(extended_object);
}
// objects in other lane
for (const auto & obj_idx : target_obj_index.other_lane) {
const auto extended_object = utils::lane_change::transform(
objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_);
target_objects.other_lane.push_back(extended_object);
}
return target_objects;
}
LaneChangeTargetObjectIndices NormalLaneChange::filterObject(
const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes,
const lanelet::ConstLanelets & target_backward_lanes) const
{
const auto current_pose = getEgoPose();
const auto & route_handler = *getRouteHandler();
const auto & common_parameters = planner_data_->parameters;
const auto shift_intervals =
route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction_);
const double minimum_lane_change_length =
utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals);
// Guard
if (objects.objects.empty()) {
return {};
}
// Get path
const auto path =
route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits<double>::max());
const auto target_path =
route_handler.getCenterLinePath(target_lanes, 0.0, std::numeric_limits<double>::max());
const auto current_polygon =
utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits<double>::max());
const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets(
target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset,
lane_change_parameters_->lane_expansion_right_offset);
const auto target_polygon = utils::lane_change::createPolygon(
expanded_target_lanes, 0.0, std::numeric_limits<double>::max());
const auto dist_ego_to_current_lanes_center =
lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose);
std::vector<std::optional<lanelet::BasicPolygon2d>> target_backward_polygons;
for (const auto & target_backward_lane : target_backward_lanes) {
// Check to see is target_backward_lane is in current_lanes
// Without this check, current lane object might be treated as target lane object
const auto is_current_lane = [&](const lanelet::ConstLanelet & current_lane) {
return current_lane.id() == target_backward_lane.id();
};
if (std::any_of(current_lanes.begin(), current_lanes.end(), is_current_lane)) {
continue;
}
lanelet::ConstLanelets lanelet{target_backward_lane};
auto lane_polygon =
utils::lane_change::createPolygon(lanelet, 0.0, std::numeric_limits<double>::max());
target_backward_polygons.push_back(lane_polygon);
}
LaneChangeTargetObjectIndices filtered_obj_indices;
for (size_t i = 0; i < objects.objects.size(); ++i) {
const auto & object = objects.objects.at(i);
const auto obj_velocity_norm = std::hypot(
object.kinematics.initial_twist_with_covariance.twist.linear.x,
object.kinematics.initial_twist_with_covariance.twist.linear.y);
const auto extended_object =
utils::lane_change::transform(object, common_parameters, *lane_change_parameters_);
const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object);
// calc distance from the current ego position
double max_dist_ego_to_obj = std::numeric_limits<double>::lowest();
double min_dist_ego_to_obj = std::numeric_limits<double>::max();
const auto obj_polygon_outer = obj_polygon.outer();
for (const auto & polygon_p : obj_polygon_outer) {
const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0);
const double dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p);
max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj);
min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj);
}
const auto is_lateral_far = [&]() {
const auto dist_object_to_current_lanes_center =
lanelet::utils::getLateralDistanceToClosestLanelet(
current_lanes, object.kinematics.initial_pose_with_covariance.pose);
const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center;
return std::abs(lateral) > (common_parameters.vehicle_width / 2);
};
// ignore object that are ahead of terminal lane change start
{
double distance_to_terminal_from_object = std::numeric_limits<double>::max();
for (const auto & polygon_p : obj_polygon_outer) {
const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0);
Pose polygon_pose;
polygon_pose.position = obj_p;
polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation;
const double dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes);
if (dist < distance_to_terminal_from_object) {
distance_to_terminal_from_object = dist;
}
}
if (minimum_lane_change_length > distance_to_terminal_from_object) {
continue;
}
}
// ignore static object that are behind the ego vehicle
if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) {
continue;
}
// check if the object intersects with target lanes