-
Notifications
You must be signed in to change notification settings - Fork 691
/
Copy pathscene.cpp
1730 lines (1422 loc) · 62 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_avoidance_module/scene.hpp"
#include "behavior_path_avoidance_module/debug.hpp"
#include "behavior_path_avoidance_module/utils.hpp"
#include "behavior_path_planner_common/interface/scene_module_visitor.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 <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>
#include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp"
#include <tier4_planning_msgs/msg/detail/avoidance_debug_factor__struct.hpp>
#include <algorithm>
#include <limits>
#include <memory>
#include <set>
#include <string>
#include <vector>
// set as macro so that calling function name will be printed.
// debug print is heavy. turn on only when debugging.
#define DEBUG_PRINT(...) \
RCLCPP_DEBUG_EXPRESSION(getLogger(), parameters_->print_debug_info, __VA_ARGS__)
#define printShiftLines(p, msg) DEBUG_PRINT("[%s] %s", msg, toStrInfo(p).c_str())
namespace behavior_path_planner
{
using motion_utils::calcLongitudinalOffsetPose;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestIndex;
using tier4_autoware_utils::appendMarkerArray;
using tier4_autoware_utils::calcDistance2d;
using tier4_autoware_utils::calcLateralDeviation;
using tier4_autoware_utils::getPoint;
using tier4_autoware_utils::getPose;
using tier4_autoware_utils::toHexString;
using tier4_planning_msgs::msg::AvoidanceDebugFactor;
namespace
{
bool isDrivingSameLane(
const lanelet::ConstLanelets & previous_lanes, const lanelet::ConstLanelets & current_lanes)
{
std::multiset<lanelet::Id> prev_ids{};
std::multiset<lanelet::Id> curr_ids{};
std::multiset<lanelet::Id> same_ids{};
std::for_each(
previous_lanes.begin(), previous_lanes.end(), [&](const auto & l) { prev_ids.insert(l.id()); });
std::for_each(
current_lanes.begin(), current_lanes.end(), [&](const auto & l) { curr_ids.insert(l.id()); });
std::set_intersection(
prev_ids.begin(), prev_ids.end(), curr_ids.begin(), curr_ids.end(),
std::inserter(same_ids, same_ids.end()));
return !same_ids.empty();
}
bool isBestEffort(const std::string & policy)
{
return policy == "best_effort";
}
lanelet::BasicLineString3d toLineString3d(const std::vector<Point> & bound)
{
lanelet::BasicLineString3d ret{};
std::for_each(
bound.begin(), bound.end(), [&](const auto & p) { ret.emplace_back(p.x, p.y, p.z); });
return ret;
}
} // namespace
AvoidanceModule::AvoidanceModule(
const std::string & name, rclcpp::Node & node, std::shared_ptr<AvoidanceParameters> parameters,
const std::unordered_map<std::string, std::shared_ptr<RTCInterface>> & rtc_interface_ptr_map,
std::unordered_map<std::string, std::shared_ptr<ObjectsOfInterestMarkerInterface>> &
objects_of_interest_marker_interface_ptr_map)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
helper_{std::make_shared<AvoidanceHelper>(parameters)},
parameters_{parameters},
generator_{parameters}
{
}
bool AvoidanceModule::isExecutionRequested() const
{
DEBUG_PRINT("AVOIDANCE isExecutionRequested");
// Check ego is in preferred lane
updateInfoMarker(avoid_data_);
updateDebugMarker(avoid_data_, path_shifter_, debug_data_);
// there is object that should be avoid. return true.
if (!!avoid_data_.stop_target_object) {
return true;
}
if (avoid_data_.new_shift_line.empty()) {
return false;
}
return std::any_of(
avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), [](const auto & o) {
return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
});
}
bool AvoidanceModule::isExecutionReady() const
{
DEBUG_PRINT("AVOIDANCE isExecutionReady");
return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid && avoid_data_.ready;
}
bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & data) const
{
const bool has_avoidance_target =
std::any_of(data.target_objects.begin(), data.target_objects.end(), [](const auto & o) {
return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
});
if (has_avoidance_target) {
return false;
}
// If the ego is on the shift line, keep RUNNING.
{
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);
const auto within = [](const auto & line, const size_t idx) {
return line.start_idx < idx && idx < line.end_idx;
};
for (const auto & shift_line : path_shifter_.getShiftLines()) {
if (within(shift_line, idx)) {
return false;
}
}
}
const bool has_shift_point = !path_shifter_.getShiftLines().empty();
const bool has_base_offset =
std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold;
// Nothing to do. -> EXIT.
if (!has_shift_point && !has_base_offset) {
return true;
}
// Be able to canceling avoidance path. -> EXIT.
if (!helper_->isShifted() && parameters_->enable_cancel_maneuver) {
return true;
}
return false;
}
bool AvoidanceModule::canTransitSuccessState()
{
const auto & data = avoid_data_;
// Change input lane. -> EXIT.
if (!isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
RCLCPP_WARN(getLogger(), "Previous module lane is updated. Exit.");
return true;
}
helper_->setPreviousDrivingLanes(data.current_lanelets);
// Reach input path end point. -> EXIT.
{
const auto idx = planner_data_->findEgoIndex(data.reference_path.points);
if (idx == data.reference_path.points.size() - 1) {
arrived_path_end_ = true;
}
constexpr double THRESHOLD = 1.0;
const auto is_further_than_threshold =
calcDistance2d(getEgoPose(), getPose(data.reference_path.points.back())) > THRESHOLD;
if (is_further_than_threshold && arrived_path_end_) {
RCLCPP_WARN(getLogger(), "Reach path end point. Exit.");
return true;
}
}
return data.success;
}
void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugData & debug)
{
// reference pose
data.reference_pose =
utils::getUnshiftedEgoPose(getEgoPose(), helper_->getPreviousSplineShiftPath());
// lanelet info
data.current_lanelets = utils::avoidance::getCurrentLanesFromPath(
getPreviousModuleOutput().reference_path, planner_data_);
data.extend_lanelets =
utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_);
// expand drivable lanes
const auto is_within_current_lane =
utils::avoidance::isWithinLanes(data.current_lanelets, planner_data_);
const auto red_signal_lane_itr = std::find_if(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
const auto next_lanes = planner_data_->route_handler->getNextLanelets(lanelet);
return utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data_);
});
const auto not_use_adjacent_lane =
is_within_current_lane && red_signal_lane_itr != data.current_lanelets.end();
std::for_each(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
if (!not_use_adjacent_lane) {
data.drivable_lanes.push_back(
utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_));
} else if (red_signal_lane_itr->id() != lanelet.id()) {
data.drivable_lanes.push_back(
utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_));
} else {
data.drivable_lanes.push_back(utils::avoidance::generateNotExpandedDrivableLanes(lanelet));
}
});
// calc drivable bound
auto tmp_path = getPreviousModuleOutput().path;
const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes);
const auto use_left_side_hatched_road_marking_area = [&]() {
if (!not_use_adjacent_lane) {
return true;
}
return !planner_data_->route_handler->getRoutingGraphPtr()->left(*red_signal_lane_itr);
}();
const auto use_right_side_hatched_road_marking_area = [&]() {
if (!not_use_adjacent_lane) {
return true;
}
return !planner_data_->route_handler->getRoutingGraphPtr()->right(*red_signal_lane_itr);
}();
data.left_bound = utils::calcBound(
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
use_left_side_hatched_road_marking_area, parameters_->use_intersection_areas,
parameters_->use_freespace_areas, true);
data.right_bound = utils::calcBound(
getPreviousModuleOutput().path, planner_data_, shorten_lanes,
use_right_side_hatched_road_marking_area, parameters_->use_intersection_areas,
parameters_->use_freespace_areas, false);
// reference path
if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
data.reference_path_rough = extendBackwardLength(getPreviousModuleOutput().path);
} else {
data.reference_path_rough = getPreviousModuleOutput().path;
RCLCPP_WARN(getLogger(), "Previous module lane is updated. Don't use latest reference path.");
}
// resampled reference path
data.reference_path = utils::resamplePathWithSpline(
data.reference_path_rough, parameters_->resample_interval_for_planning);
// closest index
data.ego_closest_path_index = planner_data_->findEgoIndex(data.reference_path.points);
// arclength from ego pose (used in many functions)
data.arclength_from_ego = utils::calcPathArcLengthArray(
data.reference_path, 0, data.reference_path.points.size(),
calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0));
data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine(
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);
data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine(
data.current_lanelets, data.reference_path_rough, planner_data_, parameters_);
// target objects for avoidance
fillAvoidanceTargetObjects(data, debug);
// lost object compensation
utils::avoidance::updateRegisteredObject(registered_objects_, data.target_objects, parameters_);
utils::avoidance::compensateDetectionLost(
registered_objects_, data.target_objects, data.other_objects);
// sort object order by longitudinal distance
std::sort(data.target_objects.begin(), data.target_objects.end(), [](auto a, auto b) {
return a.longitudinal < b.longitudinal;
});
// set base path
path_shifter_.setPath(data.reference_path);
}
void AvoidanceModule::fillAvoidanceTargetObjects(
AvoidancePlanningData & data, DebugData & debug) const
{
using utils::avoidance::fillAvoidanceNecessity;
using utils::avoidance::fillObjectStoppableJudge;
using utils::avoidance::filterTargetObjects;
using utils::avoidance::getTargetLanelets;
using utils::avoidance::separateObjectsByPath;
using utils::avoidance::updateRoadShoulderDistance;
using utils::traffic_light::calcDistanceToRedTrafficLight;
// Separate dynamic objects based on whether they are inside or outside of the expanded lanelets.
constexpr double MARGIN = 10.0;
const auto forward_detection_range = [&]() {
const auto to_traffic_light = calcDistanceToRedTrafficLight(
data.current_lanelets, helper_->getPreviousReferencePath(), planner_data_);
if (!to_traffic_light.has_value()) {
return helper_->getForwardDetectionRange();
}
return std::min(helper_->getForwardDetectionRange(), to_traffic_light.value());
}();
const auto [object_within_target_lane, object_outside_target_lane] = separateObjectsByPath(
helper_->getPreviousReferencePath(), helper_->getPreviousSplineShiftPath().path, planner_data_,
data, parameters_, forward_detection_range + MARGIN, debug);
for (const auto & object : object_outside_target_lane.objects) {
ObjectData other_object = createObjectData(data, object);
other_object.reason = "OutOfTargetArea";
data.other_objects.push_back(other_object);
}
ObjectDataArray objects;
for (const auto & object : object_within_target_lane.objects) {
objects.push_back(createObjectData(data, object));
}
// Filter out the objects to determine the ones to be avoided.
filterTargetObjects(objects, data, forward_detection_range, planner_data_, parameters_);
updateRoadShoulderDistance(data, planner_data_, parameters_);
// Calculate the distance needed to safely decelerate the ego vehicle to a stop line.
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
const auto feasible_stop_distance = helper_->getFeasibleDecelDistance(0.0, false);
std::for_each(data.target_objects.begin(), data.target_objects.end(), [&, this](auto & o) {
fillAvoidanceNecessity(o, registered_objects_, vehicle_width, parameters_);
o.to_stop_line = calcDistanceToStopLine(o);
fillObjectStoppableJudge(o, registered_objects_, feasible_stop_distance, parameters_);
});
// debug
{
std::vector<AvoidanceDebugMsg> debug_info_array;
const auto append = [&](const auto & o) {
AvoidanceDebugMsg debug_info;
debug_info.object_id = toHexString(o.object.object_id);
debug_info.longitudinal_distance = o.longitudinal;
debug_info.lateral_distance_from_centerline = o.to_centerline;
debug_info.allow_avoidance = o.reason == "";
debug_info.failed_reason = o.reason;
debug_info_array.push_back(debug_info);
};
std::for_each(objects.begin(), objects.end(), [&](const auto & o) { append(o); });
updateAvoidanceDebugData(debug_info_array);
}
}
ObjectData AvoidanceModule::createObjectData(
const AvoidancePlanningData & data, const PredictedObject & object) const
{
using boost::geometry::return_centroid;
const auto & path_points = data.reference_path.points;
const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose;
const auto object_closest_index = findNearestIndex(path_points, object_pose.position);
const auto object_closest_pose = path_points.at(object_closest_index).point.pose;
const auto object_type = utils::getHighestProbLabel(object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
ObjectData object_data{};
object_data.object = object;
const auto lower = parameters_->lower_distance_for_polygon_expansion;
const auto upper = parameters_->upper_distance_for_polygon_expansion;
const auto clamp =
std::clamp(calcDistance2d(getEgoPose(), object_pose) - lower, 0.0, upper) / upper;
object_data.distance_factor = object_parameter.max_expand_ratio * clamp + 1.0;
// Calc envelop polygon.
utils::avoidance::fillObjectEnvelopePolygon(
object_data, registered_objects_, object_closest_pose, parameters_);
// calc object centroid.
object_data.centroid = return_centroid<Point2d>(object_data.envelope_poly);
// Calc moving time.
utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, parameters_);
// Fill init pose.
utils::avoidance::fillInitialPose(object_data, detected_objects_);
// Calc lateral deviation from path to target object.
object_data.direction = calcLateralDeviation(object_closest_pose, object_pose.position) > 0.0
? Direction::LEFT
: Direction::RIGHT;
return object_data;
}
bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const
{
// transit yield maneuver only when the avoidance maneuver is not initiated.
if (helper_->isShifted()) {
RCLCPP_DEBUG(getLogger(), "avoidance maneuver already initiated.");
return false;
}
// prevent sudden steering.
const auto registered_lines = path_shifter_.getShiftLines();
if (!registered_lines.empty()) {
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);
const auto to_shift_start_point = calcSignedArcLength(
path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx);
if (to_shift_start_point < helper_->getMinimumPrepareDistance()) {
RCLCPP_DEBUG(
getLogger(),
"Distance to shift start point is less than minimum prepare distance. The distance is not "
"enough.");
return false;
}
}
if (!data.stop_target_object) {
RCLCPP_DEBUG(getLogger(), "can pass by the object safely without avoidance maneuver.");
return true;
}
constexpr double TH_STOP_SPEED = 0.01;
constexpr double TH_STOP_POSITION = 0.5;
const auto stopped_for_the_object =
getEgoSpeed() < TH_STOP_SPEED && std::abs(data.to_stop_line) < TH_STOP_POSITION;
const auto id = data.stop_target_object.value().object.object_id;
const auto same_id_obj = std::find_if(
ego_stopped_objects_.begin(), ego_stopped_objects_.end(),
[&id](const auto & o) { return o.object.object_id == id; });
// if the ego already started avoiding for the object, never transit yield maneuver again.
if (same_id_obj != ego_stopped_objects_.end()) {
return stopped_for_the_object;
}
// registered objects whom the ego stopped for at the moment of stopping.
if (stopped_for_the_object) {
ego_stopped_objects_.push_back(data.stop_target_object.value());
}
return true;
}
void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & debug) const
{
auto path_shifter = path_shifter_;
/**
* STEP1: Create candidate shift lines.
* Merge rough shift lines, and extract new shift lines.
*/
data.new_shift_line = generator_.generate(data, debug);
/**
* Step2: Validate new shift lines.
* Output new shift lines only when the avoidance path which is generated from them doesn't have
* huge offset from ego.
*/
data.valid = isValidShiftLine(data.new_shift_line, path_shifter);
const auto found_new_sl = data.new_shift_line.size() > 0;
const auto registered = path_shifter.getShiftLines().size() > 0;
data.found_avoidance_path = found_new_sl || registered;
/**
* STEP3: Set new shift lines.
* If there are new shift points, these shift points are registered in path_shifter in order to
* generate candidate avoidance path.
*/
if (!data.new_shift_line.empty()) {
addNewShiftLines(path_shifter, data.new_shift_line);
}
/**
* STEP4: Generate avoidance path.
*/
ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path);
const auto success_spline_path_generation =
path_shifter.generate(&spline_shift_path, true, SHIFT_TYPE::SPLINE);
data.candidate_path = success_spline_path_generation
? spline_shift_path
: utils::avoidance::toShiftedPath(data.reference_path);
/**
* STEP5: Check avoidance path safety.
* For each target objects and the objects in adjacent lanes,
* check that there is a certain amount of margin in the lateral and longitudinal direction.
*/
data.comfortable = helper_->isComfortable(data.new_shift_line);
data.safe = isSafePath(data.candidate_path, debug);
data.ready = helper_->isReady(data.new_shift_line, path_shifter_.getLastShiftLength()) &&
helper_->isReady(data.target_objects);
}
void AvoidanceModule::fillEgoStatus(
AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const
{
data.success = isSatisfiedSuccessCondition(data);
/**
* Find the nearest object that should be avoid. When the ego follows reference path,
* if the both of following two conditions are satisfied, the module surely avoid the object.
* Condition1: there is risk to collide with object without avoidance.
* Condition2: there is enough space to avoid.
* In TOO_LARGE_JERK condition, it is possible to avoid object by deceleration even if the flag
* is_avoidable is FALSE. So, the module inserts stop point for such a object.
*/
for (const auto & o : data.target_objects) {
const auto enough_space = o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK;
if (o.avoid_required && enough_space) {
data.avoid_required = true;
data.stop_target_object = o;
data.to_stop_line = o.to_stop_line;
break;
}
}
const auto can_yield_maneuver = canYieldManeuver(data);
/**
* If the output path is locked by outside of this module, don't update output path.
*/
if (isOutputPathLocked()) {
data.safe_shift_line.clear();
data.candidate_path = helper_->getPreviousSplineShiftPath();
RCLCPP_DEBUG_THROTTLE(
getLogger(), *clock_, 500, "this module is locked now. keep current path.");
return;
}
/**
* If the avoidance path is safe, use unapproved_new_sl for avoidance path generation.
*/
if (data.safe) {
data.yield_required = false;
data.safe_shift_line = data.new_shift_line;
return;
}
/**
* If the yield maneuver is disabled, use unapproved_new_sl for avoidance path generation even if
* the shift line is unsafe.
*/
if (!parameters_->enable_yield_maneuver) {
data.yield_required = false;
data.safe_shift_line = data.new_shift_line;
return;
}
/**
* TODO(Satoshi OTA) Think yield maneuver in the middle of avoidance.
* Even if it is determined that a yield is necessary, the yield maneuver is not executed
* if the avoidance has already been initiated.
*/
if (!can_yield_maneuver) {
data.safe = true; // overwrite safety judge.
data.yield_required = false;
data.safe_shift_line = data.new_shift_line;
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 500, "unsafe. but could not transit yield status.");
return;
}
/**
* Transit yield maneuver. Clear shift lines and output yield path.
*/
{
data.yield_required = true;
data.safe_shift_line = data.new_shift_line;
}
/**
* Even if data.avoid_required is false, the module cancels registered shift point when the
* approved avoidance path is not safe.
*/
const auto approved_path_exist = !path_shifter_.getShiftLines().empty();
if (approved_path_exist) {
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. canceling approved path...");
return;
}
/**
* If the avoidance path is not safe in situation where the ego should avoid object, the ego
* stops in front of the front object with the necessary distance to avoid the object.
*/
{
RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "unsafe. transit yield maneuver...");
}
}
void AvoidanceModule::fillDebugData(
const AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const
{
if (!data.stop_target_object) {
return;
}
if (helper_->isShifted()) {
return;
}
if (data.new_shift_line.empty()) {
return;
}
const auto o_front = data.stop_target_object.value();
const auto object_type = utils::getHighestProbLabel(o_front.object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto constant_distance = helper_->getFrontConstantDistance(o_front);
const auto & vehicle_width = planner_data_->parameters.vehicle_width;
const auto max_avoid_margin = object_parameter.lateral_hard_margin * o_front.distance_factor +
object_parameter.lateral_soft_margin + 0.5 * vehicle_width;
const auto avoidance_distance = helper_->getSharpAvoidanceDistance(
helper_->getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin));
const auto prepare_distance = helper_->getNominalPrepareDistance();
const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance;
dead_pose_ = calcLongitudinalOffsetPose(
data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance);
if (!dead_pose_) {
dead_pose_ = getPose(data.reference_path.points.front());
}
}
AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & data) const
{
if (data.yield_required) {
return AvoidanceState::YIELD;
}
if (!data.avoid_required) {
return AvoidanceState::NOT_AVOID;
}
if (!data.found_avoidance_path) {
return AvoidanceState::AVOID_PATH_NOT_READY;
}
if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) {
return AvoidanceState::AVOID_PATH_READY;
}
return AvoidanceState::AVOID_EXECUTE;
}
void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, ShiftedPath & path)
{
if (parameters_->disable_path_update) {
return;
}
insertPrepareVelocity(path);
switch (data.state) {
case AvoidanceState::NOT_AVOID: {
break;
}
case AvoidanceState::YIELD: {
insertYieldVelocity(path);
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
break;
}
case AvoidanceState::AVOID_PATH_NOT_READY: {
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
break;
}
case AvoidanceState::AVOID_PATH_READY: {
insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path);
break;
}
case AvoidanceState::AVOID_EXECUTE: {
insertStopPoint(isBestEffort(parameters_->policy_deceleration), path);
break;
}
default:
throw std::domain_error("invalid behavior");
}
insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path);
setStopReason(StopReason::AVOIDANCE, path.path);
}
bool AvoidanceModule::isSafePath(
ShiftedPath & shifted_path, [[maybe_unused]] DebugData & debug) const
{
const auto & p = planner_data_->parameters;
if (!parameters_->enable_safety_check) {
return true; // if safety check is disabled, it always return safe.
}
const auto ego_idx = planner_data_->findEgoIndex(shifted_path.path.points);
const auto has_left_shift = [&]() {
for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) {
const auto length = shifted_path.shift_length.at(i);
if (parameters_->lateral_avoid_check_threshold < length) {
return true;
}
}
return false;
}();
const auto has_right_shift = [&]() {
for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) {
const auto length = shifted_path.shift_length.at(i);
if (parameters_->lateral_avoid_check_threshold < -1.0 * length) {
return true;
}
}
return false;
}();
if (!has_left_shift && !has_right_shift) {
return true;
}
const auto hysteresis_factor = safe_ ? 1.0 : parameters_->hysteresis_factor_expand_rate;
const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects(
avoid_data_, planner_data_, parameters_, has_left_shift, has_right_shift, debug);
if (safety_check_target_objects.empty()) {
return true;
}
const bool limit_to_max_velocity = false;
const auto ego_predicted_path_params =
std::make_shared<utils::path_safety_checker::EgoPredictedPathParams>(
parameters_->ego_predicted_path_params);
const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(shifted_path.path.points);
const auto ego_predicted_path_for_front_object = utils::path_safety_checker::createPredictedPath(
ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx,
true, limit_to_max_velocity);
const auto ego_predicted_path_for_rear_object = utils::path_safety_checker::createPredictedPath(
ego_predicted_path_params, shifted_path.path.points, getEgoPose(), getEgoSpeed(), ego_seg_idx,
false, limit_to_max_velocity);
for (const auto & object : safety_check_target_objects) {
auto current_debug_data = utils::path_safety_checker::createObjectDebug(object);
const auto obj_polygon =
tier4_autoware_utils::toPolygon2d(object.initial_pose.pose, object.shape);
const auto is_object_front =
utils::path_safety_checker::isTargetObjectFront(getEgoPose(), obj_polygon, p.vehicle_info);
const auto & object_twist = object.initial_twist.twist;
const auto v_norm = std::hypot(object_twist.linear.x, object_twist.linear.y);
const auto object_type = utils::getHighestProbLabel(object.classification);
const auto object_parameter = parameters_->object_parameters.at(object_type);
const auto is_object_moving = v_norm > object_parameter.moving_speed_threshold;
const auto is_object_oncoming =
is_object_moving &&
utils::path_safety_checker::isTargetObjectOncoming(getEgoPose(), object.initial_pose.pose);
const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj(
object, parameters_->check_all_predicted_path);
const auto & ego_predicted_path = is_object_front && !is_object_oncoming
? ego_predicted_path_for_front_object
: ego_predicted_path_for_rear_object;
for (const auto & obj_path : obj_predicted_paths) {
if (!utils::path_safety_checker::checkCollision(
shifted_path.path, ego_predicted_path, object, obj_path, p, parameters_->rss_params,
hysteresis_factor, current_debug_data.second)) {
utils::path_safety_checker::updateCollisionCheckDebugMap(
debug.collision_check, current_debug_data, false);
safe_count_ = 0;
return false;
}
}
utils::path_safety_checker::updateCollisionCheckDebugMap(
debug.collision_check, current_debug_data, true);
}
safe_count_++;
return safe_ || safe_count_ > parameters_->hysteresis_factor_safe_count;
}
PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & original_path) const
{
const auto previous_path = helper_->getPreviousReferencePath();
const auto longest_dist_to_shift_point = [&]() {
double max_dist = 0.0;
auto lines = path_shifter_.getShiftLines();
if (lines.empty()) {
return max_dist;
}
std::sort(lines.begin(), lines.end(), [](const auto & a, const auto & b) {
return a.start_idx < b.start_idx;
});
return std::max(
max_dist,
calcSignedArcLength(previous_path.points, lines.front().start.position, getEgoPosition()));
}();
const auto extra_margin = 10.0; // Since distance does not consider arclength, but just line.
const auto backward_length = std::max(
planner_data_->parameters.backward_path_length, longest_dist_to_shift_point + extra_margin);
const size_t orig_ego_idx = planner_data_->findEgoIndex(original_path.points);
const auto prev_ego_idx = motion_utils::findNearestSegmentIndex(
previous_path.points, getPose(original_path.points.at(orig_ego_idx)),
std::numeric_limits<double>::max(), planner_data_->parameters.ego_nearest_yaw_threshold);
if (!prev_ego_idx) {
return original_path;
}
size_t clip_idx = 0;
for (size_t i = 0; i < prev_ego_idx; ++i) {
if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) {
break;
}
clip_idx = i;
}
PathWithLaneId extended_path{};
{
extended_path.points.insert(
extended_path.points.end(), previous_path.points.begin() + clip_idx,
previous_path.points.begin() + *prev_ego_idx);
}
// overwrite backward path velocity by latest one.
std::for_each(extended_path.points.begin(), extended_path.points.end(), [&](auto & p) {
p.point.longitudinal_velocity_mps =
original_path.points.at(orig_ego_idx).point.longitudinal_velocity_mps;
});
{
extended_path.points.insert(
extended_path.points.end(), original_path.points.begin() + orig_ego_idx,
original_path.points.end());
}
return extended_path;
}
BehaviorModuleOutput AvoidanceModule::plan()
{
const auto & data = avoid_data_;
resetPathCandidate();
resetPathReference();
updatePathShifter(data.safe_shift_line);
if (data.success) {
removeRegisteredShiftLines();
}
if (data.yield_required) {
removeRegisteredShiftLines();
}
// generate path with shift points that have been inserted.
ShiftedPath linear_shift_path = utils::avoidance::toShiftedPath(data.reference_path);
ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path);
const auto success_spline_path_generation =
path_shifter_.generate(&spline_shift_path, true, SHIFT_TYPE::SPLINE);
const auto success_linear_path_generation =
path_shifter_.generate(&linear_shift_path, true, SHIFT_TYPE::LINEAR);
// set previous data
if (success_spline_path_generation && success_linear_path_generation) {
helper_->setPreviousLinearShiftPath(linear_shift_path);
helper_->setPreviousSplineShiftPath(spline_shift_path);
helper_->setPreviousReferencePath(path_shifter_.getReferencePath());
} else {
spline_shift_path = helper_->getPreviousSplineShiftPath();
}
// post processing
{
postProcess(); // remove old shift points
}
BehaviorModuleOutput output;
const auto is_ignore_signal = [this](const UUID & uuid) {
if (!ignore_signal_.has_value()) {
return false;
}
return ignore_signal_.value() == uuid;
};
const auto update_ignore_signal = [this](const UUID & uuid, const bool is_ignore) {
ignore_signal_ = is_ignore ? std::make_optional(uuid) : std::nullopt;
};
// turn signal info
if (path_shifter_.getShiftLines().empty()) {
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
} else if (is_ignore_signal(path_shifter_.getShiftLines().front().id)) {
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
} else {
const auto original_signal = getPreviousModuleOutput().turn_signal_info;
constexpr bool is_driving_forward = true;
constexpr bool egos_lane_is_shifted = true;
const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo(
linear_shift_path, path_shifter_.getShiftLines().front(), avoid_data_.current_lanelets,
helper_->getEgoShift(), is_driving_forward, egos_lane_is_shifted);
const auto current_seg_idx = planner_data_->findEgoSegmentIndex(spline_shift_path.path.points);
output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal(
spline_shift_path.path, getEgoPose(), current_seg_idx, original_signal, new_signal,
planner_data_->parameters.ego_nearest_dist_threshold,
planner_data_->parameters.ego_nearest_yaw_threshold);
update_ignore_signal(path_shifter_.getShiftLines().front().id, is_ignore);
}
// sparse resampling for computational cost
{
spline_shift_path.path = utils::resamplePathWithSpline(
spline_shift_path.path, parameters_->resample_interval_for_output);
}
avoid_data_.state = updateEgoState(data);
// update output data
{
updateEgoBehavior(data, spline_shift_path);
updateInfoMarker(avoid_data_);
updateDebugMarker(avoid_data_, path_shifter_, debug_data_);
}
if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
output.path = spline_shift_path.path;
} else {
output.path = getPreviousModuleOutput().path;
RCLCPP_WARN(getLogger(), "Previous module lane is updated. Do nothing.");
}
output.reference_path = getPreviousModuleOutput().reference_path;
path_reference_ = std::make_shared<PathWithLaneId>(getPreviousModuleOutput().reference_path);
const size_t ego_idx = planner_data_->findEgoIndex(output.path.points);
utils::clipPathLength(output.path, ego_idx, planner_data_->parameters);
// Drivable area generation.
{
DrivableAreaInfo current_drivable_area_info;
// generate drivable lanes
std::for_each(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
current_drivable_area_info.drivable_lanes.push_back(
utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_));
});
// expand hatched road markings
current_drivable_area_info.enable_expanding_hatched_road_markings =
parameters_->use_hatched_road_markings;