forked from autowarefoundation/autoware.universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathscene_crosswalk.cpp
1209 lines (1013 loc) · 44.2 KB
/
scene_crosswalk.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 2020 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 "scene_crosswalk.hpp"
#include <autoware_auto_tf2/tf2_autoware_auto_msgs.hpp>
#include <behavior_velocity_planner_common/utilization/path_utilization.hpp>
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <motion_utils/distance/distance.hpp>
#include <motion_utils/resample/resample.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
#include <lanelet2_core/geometry/LineString.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <lanelet2_routing/RoutingGraphContainer.h>
#include <algorithm>
#include <cmath>
#include <limits>
#include <set>
#include <tuple>
#include <vector>
namespace behavior_velocity_planner
{
namespace bg = boost::geometry;
using motion_utils::calcArcLength;
using motion_utils::calcDecelDistWithJerkAndAccConstraints;
using motion_utils::calcLateralOffset;
using motion_utils::calcLongitudinalOffsetPoint;
using motion_utils::calcLongitudinalOffsetPose;
using motion_utils::calcSignedArcLength;
using motion_utils::calcSignedArcLengthPartialSum;
using motion_utils::findNearestSegmentIndex;
using motion_utils::insertTargetPoint;
using motion_utils::resamplePath;
using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::getPose;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
using tier4_autoware_utils::pose2transform;
using tier4_autoware_utils::toHexString;
namespace
{
geometry_msgs::msg::Point32 createPoint32(const double x, const double y, const double z)
{
geometry_msgs::msg::Point32 p;
p.x = x;
p.y = y;
p.z = z;
return p;
}
std::vector<geometry_msgs::msg::Point> toGeometryPointVector(
const Polygon2d & polygon, const double z)
{
std::vector<geometry_msgs::msg::Point> points;
for (const auto & p : polygon.outer()) {
points.push_back(createPoint(p.x(), p.y(), z));
}
return points;
}
void offsetPolygon2d(
const geometry_msgs::msg::Pose & origin_point, const geometry_msgs::msg::Polygon & polygon,
Polygon2d & offset_polygon)
{
for (const auto & polygon_point : polygon.points) {
const auto offset_pos =
tier4_autoware_utils::calcOffsetPose(origin_point, polygon_point.x, polygon_point.y, 0.0)
.position;
offset_polygon.outer().push_back(Point2d(offset_pos.x, offset_pos.y));
}
}
template <class T>
Polygon2d createMultiStepPolygon(
const T & obj_path_points, const geometry_msgs::msg::Polygon & polygon, const size_t start_idx,
const size_t end_idx)
{
Polygon2d multi_step_polygon{};
for (size_t i = start_idx; i <= end_idx; ++i) {
offsetPolygon2d(
tier4_autoware_utils::getPose(obj_path_points.at(i)), polygon, multi_step_polygon);
}
Polygon2d hull_multi_step_polygon{};
bg::convex_hull(multi_step_polygon, hull_multi_step_polygon);
bg::correct(hull_multi_step_polygon);
return hull_multi_step_polygon;
}
void sortCrosswalksByDistance(
const PathWithLaneId & ego_path, const geometry_msgs::msg::Point & ego_pos,
lanelet::ConstLanelets & crosswalks)
{
const auto compare = [&](const lanelet::ConstLanelet & l1, const lanelet::ConstLanelet & l2) {
const auto l1_intersects =
getPolygonIntersects(ego_path, l1.polygon2d().basicPolygon(), ego_pos, 2);
const auto l2_intersects =
getPolygonIntersects(ego_path, l2.polygon2d().basicPolygon(), ego_pos, 2);
if (l1_intersects.empty() || l2_intersects.empty()) {
return true;
}
const auto dist_l1 = calcSignedArcLength(ego_path.points, size_t(0), l1_intersects.front());
const auto dist_l2 = calcSignedArcLength(ego_path.points, size_t(0), l2_intersects.front());
return dist_l1 < dist_l2;
};
std::sort(crosswalks.begin(), crosswalks.end(), compare);
}
std::vector<Polygon2d> calcOverlappingPoints(const Polygon2d & polygon1, const Polygon2d & polygon2)
{
// NOTE: If one polygon is fully inside the other polygon, the result is empty.
std::vector<Polygon2d> intersection_polygons{};
bg::intersection(polygon1, polygon2, intersection_polygons);
return intersection_polygons;
}
StopFactor createStopFactor(
const geometry_msgs::msg::Pose & stop_pose,
const std::vector<geometry_msgs::msg::Point> stop_factor_points = {})
{
StopFactor stop_factor;
stop_factor.stop_factor_points = stop_factor_points;
stop_factor.stop_pose = stop_pose;
return stop_factor;
}
tier4_debug_msgs::msg::StringStamped createStringStampedMessage(
const rclcpp::Time & now, const int64_t module_id_,
const std::vector<std::tuple<std::string, CollisionPoint, CollisionState>> & collision_points)
{
tier4_debug_msgs::msg::StringStamped msg;
msg.stamp = now;
for (const auto & collision_point : collision_points) {
std::stringstream ss;
ss << module_id_ << "," << std::get<0>(collision_point).substr(0, 4) << ","
<< std::get<1>(collision_point).time_to_collision << ","
<< std::get<1>(collision_point).time_to_vehicle << ","
<< static_cast<int>(std::get<2>(collision_point)) << ",";
msg.data += ss.str();
}
return msg;
}
} // namespace
CrosswalkModule::CrosswalkModule(
rclcpp::Node & node, const int64_t lane_id, const int64_t module_id,
const std::optional<int64_t> & reg_elem_id, const lanelet::LaneletMapPtr & lanelet_map_ptr,
const PlannerParam & planner_param, const rclcpp::Logger & logger,
const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock),
module_id_(module_id),
planner_param_(planner_param),
use_regulatory_element_(reg_elem_id)
{
velocity_factor_.init(PlanningBehavior::CROSSWALK);
passed_safety_slow_point_ = false;
if (use_regulatory_element_) {
const auto reg_elem_ptr = std::dynamic_pointer_cast<const lanelet::autoware::Crosswalk>(
lanelet_map_ptr->regulatoryElementLayer.get(*reg_elem_id));
stop_lines_ = reg_elem_ptr->stopLines();
crosswalk_ = reg_elem_ptr->crosswalkLanelet();
} else {
const auto stop_line = getStopLineFromMap(module_id_, lanelet_map_ptr, "crosswalk_id");
if (stop_line) {
stop_lines_.push_back(*stop_line);
}
crosswalk_ = lanelet_map_ptr->laneletLayer.get(module_id);
}
road_ = lanelet_map_ptr->laneletLayer.get(lane_id);
collision_info_pub_ =
node.create_publisher<tier4_debug_msgs::msg::StringStamped>("~/debug/collision_info", 1);
}
bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
{
if (path->points.size() < 2) {
RCLCPP_DEBUG(logger_, "Do not interpolate because path size is less than 2.");
return {};
}
stop_watch_.tic("total_processing_time");
RCLCPP_INFO_EXPRESSION(
logger_, planner_param_.show_processing_time,
"=========== module_id: %ld ===========", module_id_);
*stop_reason = planning_utils::initializeStopReason(StopReason::CROSSWALK);
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto objects_ptr = planner_data_->predicted_objects;
// Initialize debug data
debug_data_ = DebugData(planner_data_);
for (const auto & p : crosswalk_.polygon2d().basicPolygon()) {
debug_data_.crosswalk_polygon.push_back(createPoint(p.x(), p.y(), ego_pos.z));
}
recordTime(1);
// Calculate intersection between path and crosswalks
const auto path_intersects =
getPolygonIntersects(*path, crosswalk_.polygon2d().basicPolygon(), ego_pos, 2);
// Apply safety slow down speed if defined in Lanelet2 map
if (crosswalk_.hasAttribute("safety_slow_down_speed")) {
applySafetySlowDownSpeed(*path, path_intersects);
}
recordTime(2);
// Calculate stop point with margin
const auto p_stop_line = getStopPointWithMargin(*path, path_intersects);
std::optional<geometry_msgs::msg::Pose> default_stop_pose = std::nullopt;
if (p_stop_line.has_value()) {
default_stop_pose =
calcLongitudinalOffsetPose(path->points, p_stop_line->first, p_stop_line->second);
}
// Resample path sparsely for less computation cost
constexpr double resample_interval = 4.0;
const auto sparse_resample_path =
resamplePath(*path, resample_interval, false, true, true, false);
// Decide to stop for crosswalk users
const auto stop_factor_for_crosswalk_users = checkStopForCrosswalkUsers(
*path, sparse_resample_path, p_stop_line, path_intersects, default_stop_pose);
// Decide to stop for stuck vehicle
const auto stop_factor_for_stuck_vehicles = checkStopForStuckVehicles(
sparse_resample_path, objects_ptr->objects, path_intersects, default_stop_pose);
// Get nearest stop factor
const auto nearest_stop_factor =
getNearestStopFactor(*path, stop_factor_for_crosswalk_users, stop_factor_for_stuck_vehicles);
recordTime(3);
// Set safe or unsafe
setSafe(!nearest_stop_factor);
// Set distance
// NOTE: If no stop point is inserted, distance to the virtual stop line has to be calculated.
setDistanceToStop(*path, default_stop_pose, nearest_stop_factor);
// plan Go/Stop
if (isActivated()) {
planGo(*path, nearest_stop_factor);
} else {
planStop(*path, nearest_stop_factor, default_stop_pose, stop_reason);
}
recordTime(4);
const auto collision_info_msg =
createStringStampedMessage(clock_->now(), module_id_, debug_data_.collision_points);
collision_info_pub_->publish(collision_info_msg);
return true;
}
// NOTE: The stop point will be the returned point with the margin.
std::optional<std::pair<geometry_msgs::msg::Point, double>> CrosswalkModule::getStopPointWithMargin(
const PathWithLaneId & ego_path,
const std::vector<geometry_msgs::msg::Point> & path_intersects) const
{
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
// If stop lines are found in the LL2 map.
for (const auto & stop_line : stop_lines_) {
const auto p_stop_lines = getLinestringIntersects(
ego_path, lanelet::utils::to2D(stop_line).basicLineString(), ego_pos, 2);
if (!p_stop_lines.empty()) {
return std::make_pair(p_stop_lines.front(), -base_link2front);
}
}
// If stop lines are not found in the LL2 map.
if (!path_intersects.empty()) {
return std::make_pair(
path_intersects.front(), -planner_param_.stop_distance_from_crosswalk - base_link2front);
}
return {};
}
std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
const PathWithLaneId & ego_path, const PathWithLaneId & sparse_resample_path,
const std::optional<std::pair<geometry_msgs::msg::Point, double>> & p_stop_line,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const std::optional<geometry_msgs::msg::Pose> & default_stop_pose)
{
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const double ego_vel = planner_data_->current_velocity->twist.linear.x;
const double ego_acc = planner_data_->current_acceleration->accel.accel.linear.x;
const std::optional<double> ego_crosswalk_passage_direction =
findEgoPassageDirectionAlongPath(sparse_resample_path);
const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
const auto dist_ego_to_stop =
calcSignedArcLength(ego_path.points, ego_pos, p_stop_line->first) + p_stop_line->second;
// Calculate attention range for crosswalk
const auto crosswalk_attention_range = getAttentionRange(sparse_resample_path, path_intersects);
// Get attention area, which is ego's footprints on the crosswalk
const auto attention_area = getAttentionArea(sparse_resample_path, crosswalk_attention_range);
// Update object state
updateObjectState(
dist_ego_to_stop, sparse_resample_path, crosswalk_attention_range, attention_area);
// Check if ego moves forward enough to ignore yield.
const auto & p = planner_param_;
if (!path_intersects.empty()) {
const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
const double dist_ego2crosswalk =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front());
const auto braking_distance_opt = motion_utils::calcDecelDistWithJerkAndAccConstraints(
ego_vel, 0.0, ego_acc, p.min_acc_for_no_stop_decision, p.max_jerk_for_no_stop_decision,
p.min_jerk_for_no_stop_decision);
const double braking_distance = braking_distance_opt ? *braking_distance_opt : 0.0;
if (
dist_ego2crosswalk - base_link2front - braking_distance <
p.max_offset_to_crosswalk_for_yield) {
return {};
}
}
// Check pedestrian for stop
// NOTE: first stop point and its minimum distance from ego to stop
auto isVehicleType = [](const uint8_t label) {
return label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE;
};
std::optional<std::pair<geometry_msgs::msg::Point, double>> nearest_stop_info;
std::vector<geometry_msgs::msg::Point> stop_factor_points;
for (const auto & object : object_info_manager_.getObject()) {
const auto & collision_point_opt = object.collision_point;
if (collision_point_opt) {
const auto & collision_point = collision_point_opt.value();
const auto & collision_state = object.collision_state;
if (collision_state != CollisionState::YIELD) {
continue;
}
if (
isVehicleType(object.classification) && ego_crosswalk_passage_direction &&
collision_point.crosswalk_passage_direction) {
const double direction_diff = tier4_autoware_utils::normalizeRadian(
collision_point.crosswalk_passage_direction.value() -
ego_crosswalk_passage_direction.value());
if (std::fabs(direction_diff) < planner_param_.vehicle_object_cross_angle_threshold) {
continue;
}
}
stop_factor_points.push_back(object.position);
const auto dist_ego2cp =
calcSignedArcLength(sparse_resample_path.points, ego_pos, collision_point.collision_point) -
planner_param_.stop_distance_from_object;
if (!nearest_stop_info || dist_ego2cp - base_link2front < nearest_stop_info->second) {
nearest_stop_info =
std::make_pair(collision_point.collision_point, dist_ego2cp - base_link2front);
}
}
}
// Check if stop is required
if (!nearest_stop_info) {
return {};
}
// Check if the ego should stop at the stop line or the other points.
const bool stop_at_stop_line =
dist_ego_to_stop < nearest_stop_info->second &&
nearest_stop_info->second < dist_ego_to_stop + planner_param_.far_object_threshold;
if (stop_at_stop_line) {
// Stop at the stop line
if (default_stop_pose) {
return createStopFactor(*default_stop_pose, stop_factor_points);
}
} else {
const auto stop_pose = calcLongitudinalOffsetPose(
ego_path.points, nearest_stop_info->first,
-base_link2front - planner_param_.stop_distance_from_object);
if (stop_pose) {
return createStopFactor(*stop_pose, stop_factor_points);
}
}
return {};
}
std::pair<double, double> CrosswalkModule::getAttentionRange(
const PathWithLaneId & ego_path, const std::vector<geometry_msgs::msg::Point> & path_intersects)
{
stop_watch_.tic(__func__);
if (path_intersects.size() < 2) {
return std::make_pair(0.0, 0.0);
}
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto near_attention_range =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()) -
planner_param_.crosswalk_attention_range;
const auto far_attention_range =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back()) +
planner_param_.crosswalk_attention_range;
const auto [clamped_near_attention_range, clamped_far_attention_range] =
clampAttentionRangeByNeighborCrosswalks(ego_path, near_attention_range, far_attention_range);
RCLCPP_INFO_EXPRESSION(
logger_, planner_param_.show_processing_time, "%s : %f ms", __func__,
stop_watch_.toc(__func__, true));
return std::make_pair(
std::max(0.0, clamped_near_attention_range), std::max(0.0, clamped_far_attention_range));
}
void CrosswalkModule::insertDecelPointWithDebugInfo(
const geometry_msgs::msg::Point & stop_point, const float target_velocity,
PathWithLaneId & output) const
{
const auto stop_pose = planning_utils::insertDecelPoint(stop_point, output, target_velocity);
if (!stop_pose) {
return;
}
debug_data_.first_stop_pose = getPose(*stop_pose);
if (std::abs(target_velocity) < 1e-3) {
debug_data_.stop_poses.push_back(*stop_pose);
} else {
debug_data_.slow_poses.push_back(*stop_pose);
}
}
float CrosswalkModule::calcTargetVelocity(
const geometry_msgs::msg::Point & stop_point, const PathWithLaneId & ego_path) const
{
const auto max_jerk = planner_param_.max_slow_down_jerk;
const auto max_accel = planner_param_.max_slow_down_accel;
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto ego_vel = planner_data_->current_velocity->twist.linear.x;
if (ego_vel < planner_param_.no_relax_velocity) {
return 0.0;
}
const auto ego_acc = planner_data_->current_acceleration->accel.accel.linear.x;
const auto dist_deceleration = calcSignedArcLength(ego_path.points, ego_pos, stop_point);
const auto feasible_velocity = planning_utils::calcDecelerationVelocityFromDistanceToTarget(
max_jerk, max_accel, ego_acc, ego_vel, dist_deceleration);
constexpr double margin_velocity = 0.5; // 1.8 km/h
return margin_velocity < feasible_velocity ? feasible_velocity : 0.0;
}
std::pair<double, double> CrosswalkModule::clampAttentionRangeByNeighborCrosswalks(
const PathWithLaneId & ego_path, const double near_attention_range,
const double far_attention_range)
{
stop_watch_.tic(__func__);
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto p_near = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, near_attention_range);
const auto p_far = calcLongitudinalOffsetPoint(ego_path.points, ego_pos, far_attention_range);
if (!p_near || !p_far) {
return std::make_pair(near_attention_range, far_attention_range);
}
const auto near_idx = findNearestSegmentIndex(ego_path.points, p_near.value());
const auto far_idx = findNearestSegmentIndex(ego_path.points, p_far.value()) + 1;
std::set<int64_t> lane_ids;
for (size_t i = near_idx; i < far_idx; ++i) {
for (const auto & id : ego_path.points.at(i).lane_ids) {
lane_ids.insert(id);
}
}
lanelet::ConstLanelets crosswalks{};
constexpr int PEDESTRIAN_GRAPH_ID = 1;
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
const auto overall_graphs_ptr = planner_data_->route_handler_->getOverallGraphPtr();
for (const auto & id : lane_ids) {
const auto ll = lanelet_map_ptr->laneletLayer.get(id);
const auto conflicting_crosswalks =
overall_graphs_ptr->conflictingInGraph(ll, PEDESTRIAN_GRAPH_ID);
for (const auto & crosswalk : conflicting_crosswalks) {
const auto itr = std::find_if(
crosswalks.begin(), crosswalks.end(),
[&](const lanelet::ConstLanelet & ll) { return ll.id() == crosswalk.id(); });
if (itr == crosswalks.end()) {
crosswalks.push_back(crosswalk);
}
}
}
sortCrosswalksByDistance(ego_path, ego_pos, crosswalks);
std::optional<lanelet::ConstLanelet> prev_crosswalk{std::nullopt};
std::optional<lanelet::ConstLanelet> next_crosswalk{std::nullopt};
if (!crosswalks.empty()) {
for (size_t i = 0; i < crosswalks.size() - 1; ++i) {
const auto ll_front = crosswalks.at(i);
const auto ll_back = crosswalks.at(i + 1);
if (ll_front.id() == module_id_ && ll_back.id() != module_id_) {
next_crosswalk = ll_back;
}
if (ll_front.id() != module_id_ && ll_back.id() == module_id_) {
prev_crosswalk = ll_front;
}
}
}
const double clamped_near_attention_range = [&]() {
if (!prev_crosswalk) {
return near_attention_range;
}
auto reverse_ego_path = ego_path;
std::reverse(reverse_ego_path.points.begin(), reverse_ego_path.points.end());
const auto prev_crosswalk_intersects = getPolygonIntersects(
reverse_ego_path, prev_crosswalk->polygon2d().basicPolygon(), ego_pos, 2);
if (prev_crosswalk_intersects.empty()) {
return near_attention_range;
}
const auto dist_to_prev_crosswalk =
calcSignedArcLength(ego_path.points, ego_pos, prev_crosswalk_intersects.front());
return std::max(near_attention_range, dist_to_prev_crosswalk);
}();
const double clamped_far_attention_range = [&]() {
if (!next_crosswalk) {
return far_attention_range;
}
const auto next_crosswalk_intersects =
getPolygonIntersects(ego_path, next_crosswalk->polygon2d().basicPolygon(), ego_pos, 2);
if (next_crosswalk_intersects.empty()) {
return far_attention_range;
}
const auto dist_to_next_crosswalk =
calcSignedArcLength(ego_path.points, ego_pos, next_crosswalk_intersects.front());
return std::min(far_attention_range, dist_to_next_crosswalk);
}();
const auto update_p_near =
calcLongitudinalOffsetPoint(ego_path.points, ego_pos, near_attention_range);
const auto update_p_far =
calcLongitudinalOffsetPoint(ego_path.points, ego_pos, far_attention_range);
if (update_p_near && update_p_far) {
debug_data_.range_near_point = update_p_near.value();
debug_data_.range_far_point = update_p_far.value();
}
RCLCPP_INFO_EXPRESSION(
logger_, planner_param_.show_processing_time, "%s : %f ms", __func__,
stop_watch_.toc(__func__, true));
return std::make_pair(clamped_near_attention_range, clamped_far_attention_range);
}
std::optional<double> CrosswalkModule::findEgoPassageDirectionAlongPath(
const PathWithLaneId & path) const
{
auto findIntersectPoint = [&](const lanelet::ConstLineString3d line)
-> std::optional<std::pair<size_t, geometry_msgs::msg::Point>> {
const auto line_start =
tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z());
const auto line_end =
tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z());
for (unsigned i = 0; i < path.points.size() - 1; ++i) {
const auto & start = path.points.at(i).point.pose.position;
const auto & end = path.points.at(i + 1).point.pose.position;
if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end);
intersect.has_value()) {
return std::make_optional(std::make_pair(i, intersect.value()));
}
}
return std::nullopt;
};
const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound());
const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound());
if (!intersect_pt1 || !intersect_pt2) {
return std::nullopt;
}
const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first;
const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second;
const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second;
return std::atan2(back.y - front.y, back.x - front.x);
}
std::optional<double> CrosswalkModule::findObjectPassageDirectionAlongVehicleLane(
const autoware_auto_perception_msgs::msg::PredictedPath & path) const
{
using tier4_autoware_utils::Segment2d;
auto findIntersectPoint = [&](const lanelet::ConstLineString3d line)
-> std::optional<std::pair<size_t, geometry_msgs::msg::Point>> {
const auto line_start =
tier4_autoware_utils::createPoint(line.front().x(), line.front().y(), line.front().z());
const auto line_end =
tier4_autoware_utils::createPoint(line.back().x(), line.back().y(), line.back().z());
for (unsigned i = 0; i < path.path.size() - 1; ++i) {
const auto & start = path.path.at(i).position;
const auto & end = path.path.at(i + 1).position;
if (const auto intersect = tier4_autoware_utils::intersect(line_start, line_end, start, end);
intersect.has_value()) {
return std::make_optional(std::make_pair(i, intersect.value()));
}
}
return std::nullopt;
};
const auto intersect_pt1 = findIntersectPoint(crosswalk_.leftBound());
const auto intersect_pt2 = findIntersectPoint(crosswalk_.rightBound());
if (!intersect_pt1 || !intersect_pt2) {
return std::nullopt;
}
const auto idx1 = intersect_pt1.value().first, idx2 = intersect_pt2.value().first;
const auto & front = idx1 > idx2 ? intersect_pt2.value().second : intersect_pt1.value().second;
const auto & back = idx1 > idx2 ? intersect_pt1.value().second : intersect_pt2.value().second;
return std::atan2(back.y - front.y, back.x - front.x);
}
std::optional<CollisionPoint> CrosswalkModule::getCollisionPoint(
const PathWithLaneId & ego_path, const PredictedObject & object,
const std::pair<double, double> & crosswalk_attention_range, const Polygon2d & attention_area)
{
stop_watch_.tic(__func__);
std::vector<CollisionPoint> ret{};
const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear;
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto & ego_vel = planner_data_->current_velocity->twist.linear;
const auto obj_polygon =
createObjectPolygon(object.shape.dimensions.x, object.shape.dimensions.y);
double minimum_stop_dist = std::numeric_limits<double>::max();
std::optional<CollisionPoint> nearest_collision_point{std::nullopt};
for (const auto & obj_path : object.kinematics.predicted_paths) {
size_t start_idx{0};
bool is_start_idx_initialized{false};
for (size_t i = 0; i < obj_path.path.size(); ++i) {
// For effective computation, the point and polygon intersection is calculated first.
const auto obj_one_step_polygon = createMultiStepPolygon(obj_path.path, obj_polygon, i, i);
const auto one_step_intersection_polygons =
calcOverlappingPoints(obj_one_step_polygon, attention_area);
if (!one_step_intersection_polygons.empty()) {
if (!is_start_idx_initialized) {
start_idx = i;
is_start_idx_initialized = true;
}
if (i != obj_path.path.size() - 1) {
// NOTE: Even if the object path does not fully cross the ego path, the path should be
// considered.
continue;
}
}
if (!is_start_idx_initialized) {
continue;
}
// Calculate multi-step object polygon, and reset start_idx
const size_t start_idx_with_margin = std::max(static_cast<int>(start_idx) - 1, 0);
const size_t end_idx_with_margin = std::min(i + 1, obj_path.path.size() - 1);
const auto object_crosswalk_passage_direction =
findObjectPassageDirectionAlongVehicleLane(obj_path);
const auto obj_multi_step_polygon = createMultiStepPolygon(
obj_path.path, obj_polygon, start_idx_with_margin, end_idx_with_margin);
is_start_idx_initialized = false;
// Calculate intersection points between object and attention area
const auto multi_step_intersection_polygons =
calcOverlappingPoints(obj_multi_step_polygon, attention_area);
if (multi_step_intersection_polygons.empty()) {
continue;
}
// Calculate nearest collision point among collisions with a predicted path
Point2d boost_intersection_center_point;
bg::centroid(multi_step_intersection_polygons.front(), boost_intersection_center_point);
const auto intersection_center_point = createPoint(
boost_intersection_center_point.x(), boost_intersection_center_point.y(), ego_pos.z);
const auto dist_ego2cp =
calcSignedArcLength(ego_path.points, ego_pos, intersection_center_point);
constexpr double eps = 1e-3;
const auto dist_obj2cp =
calcArcLength(obj_path.path) < eps
? 0.0
: calcSignedArcLength(obj_path.path, size_t(0), intersection_center_point);
if (
dist_ego2cp < crosswalk_attention_range.first ||
crosswalk_attention_range.second < dist_ego2cp) {
continue;
}
// Calculate nearest collision point among predicted paths
if (dist_ego2cp < minimum_stop_dist) {
minimum_stop_dist = dist_ego2cp;
nearest_collision_point = createCollisionPoint(
intersection_center_point, dist_ego2cp, dist_obj2cp, ego_vel, obj_vel,
object_crosswalk_passage_direction);
debug_data_.obj_polygons.push_back(
toGeometryPointVector(obj_multi_step_polygon, ego_pos.z));
}
break;
}
}
RCLCPP_INFO_EXPRESSION(
logger_, planner_param_.show_processing_time, "%s : %f ms", __func__,
stop_watch_.toc(__func__, true));
return nearest_collision_point;
}
CollisionPoint CrosswalkModule::createCollisionPoint(
const geometry_msgs::msg::Point & nearest_collision_point, const double dist_ego2cp,
const double dist_obj2cp, const geometry_msgs::msg::Vector3 & ego_vel,
const geometry_msgs::msg::Vector3 & obj_vel,
const std::optional<double> object_crosswalk_passage_direction) const
{
constexpr double min_ego_velocity = 1.38; // [m/s]
const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m;
const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity);
CollisionPoint collision_point{};
collision_point.collision_point = nearest_collision_point;
collision_point.crosswalk_passage_direction = object_crosswalk_passage_direction;
collision_point.time_to_collision =
std::max(0.0, dist_ego2cp - planner_param_.stop_distance_from_object - base_link2front) /
std::max(ego_vel.x, min_ego_velocity);
collision_point.time_to_vehicle = std::max(0.0, dist_obj2cp) / velocity;
return collision_point;
}
void CrosswalkModule::applySafetySlowDownSpeed(
PathWithLaneId & output, const std::vector<geometry_msgs::msg::Point> & path_intersects)
{
if (path_intersects.empty()) {
return;
}
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto ego_path = output;
// Safety slow down speed in [m/s]
const auto & safety_slow_down_speed =
static_cast<float>(crosswalk_.attribute("safety_slow_down_speed").asDouble().get());
if (!passed_safety_slow_point_) {
// Safety slow down distance [m]
const double safety_slow_down_distance =
crosswalk_.attributeOr("safety_slow_down_distance", 2.0);
// the range until to the point where ego will have a const safety slow down speed
const double safety_slow_margin =
planner_data_->vehicle_info_.max_longitudinal_offset_m + safety_slow_down_distance;
const double safety_slow_point_range =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.front()) - safety_slow_margin;
const auto & p_safety_slow =
calcLongitudinalOffsetPoint(ego_path.points, ego_pos, safety_slow_point_range);
insertDecelPointWithDebugInfo(p_safety_slow.value(), safety_slow_down_speed, output);
if (safety_slow_point_range < 0.0) {
passed_safety_slow_point_ = true;
}
} else {
// the range until to the point where ego will start accelerate
const double safety_slow_end_point_range =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back());
if (0.0 < safety_slow_end_point_range) {
// insert constant ego speed until the end of the crosswalk
for (auto & p : output.points) {
const float original_velocity = p.point.longitudinal_velocity_mps;
p.point.longitudinal_velocity_mps = std::min(original_velocity, safety_slow_down_speed);
}
}
}
}
Polygon2d CrosswalkModule::getAttentionArea(
const PathWithLaneId & sparse_resample_path,
const std::pair<double, double> & crosswalk_attention_range) const
{
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto ego_polygon = createVehiclePolygon(planner_data_->vehicle_info_);
const auto backward_path_length =
calcSignedArcLength(sparse_resample_path.points, size_t(0), ego_pos);
const auto length_sum = calcSignedArcLengthPartialSum(
sparse_resample_path.points, size_t(0), sparse_resample_path.points.size());
Polygon2d attention_area;
for (size_t j = 0; j < sparse_resample_path.points.size() - 1; ++j) {
const auto front_length = length_sum.at(j) - backward_path_length;
const auto back_length = length_sum.at(j + 1) - backward_path_length;
if (back_length < crosswalk_attention_range.first) {
continue;
}
if (crosswalk_attention_range.second < front_length) {
break;
}
const auto ego_one_step_polygon =
createMultiStepPolygon(sparse_resample_path.points, ego_polygon, j, j + 1);
debug_data_.ego_polygons.push_back(toGeometryPointVector(ego_one_step_polygon, ego_pos.z));
std::vector<Polygon2d> unions;
bg::union_(attention_area, ego_one_step_polygon, unions);
if (!unions.empty()) {
attention_area = unions.front();
bg::correct(attention_area);
}
}
return attention_area;
}
std::optional<StopFactor> CrosswalkModule::checkStopForStuckVehicles(
const PathWithLaneId & ego_path, const std::vector<PredictedObject> & objects,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const std::optional<geometry_msgs::msg::Pose> & stop_pose) const
{
const auto & p = planner_param_;
if (path_intersects.size() < 2 || !stop_pose) {
return {};
}
// skip stuck vehicle checking for crosswalk which is in intersection.
if (!p.enable_stuck_check_in_intersection) {
std::string turn_direction = road_.attributeOr("turn_direction", "else");
if (turn_direction == "right" || turn_direction == "left" || turn_direction == "straight") {
if (!road_.regulatoryElementsAs<const lanelet::TrafficLight>().empty()) {
return {};
}
}
}
for (const auto & object : objects) {
if (!isVehicle(object)) {
continue;
}
const auto & obj_vel = object.kinematics.initial_twist_with_covariance.twist.linear;
if (p.stuck_vehicle_velocity < std::hypot(obj_vel.x, obj_vel.y)) {
continue;
}
const auto & obj_pos = object.kinematics.initial_pose_with_covariance.pose.position;
const auto lateral_offset = calcLateralOffset(ego_path.points, obj_pos);
if (p.max_stuck_vehicle_lateral_offset < std::abs(lateral_offset)) {
continue;
}
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto ego_vel = planner_data_->current_velocity->twist.linear.x;
const auto ego_acc = planner_data_->current_acceleration->accel.accel.linear.x;
const double near_attention_range =
calcSignedArcLength(ego_path.points, ego_pos, path_intersects.back());
const double far_attention_range = near_attention_range + p.stuck_vehicle_attention_range;
const auto dist_ego2obj = calcSignedArcLength(ego_path.points, ego_pos, obj_pos);
if (near_attention_range < dist_ego2obj && dist_ego2obj < far_attention_range) {
// Plan STOP considering min_acc, max_jerk and min_jerk.
const auto min_feasible_dist_ego2stop = calcDecelDistWithJerkAndAccConstraints(
ego_vel, 0.0, ego_acc, p.min_acc_for_stuck_vehicle, p.max_jerk_for_stuck_vehicle,
p.min_jerk_for_stuck_vehicle);
if (!min_feasible_dist_ego2stop) {
continue;
}
const double dist_ego2stop =
calcSignedArcLength(ego_path.points, ego_pos, stop_pose->position);
const double feasible_dist_ego2stop = std::max(*min_feasible_dist_ego2stop, dist_ego2stop);
const double dist_to_ego =
calcSignedArcLength(ego_path.points, ego_path.points.front().point.pose.position, ego_pos);
const auto feasible_stop_pose =
calcLongitudinalOffsetPose(ego_path.points, 0, dist_to_ego + feasible_dist_ego2stop);
if (!feasible_stop_pose) {
continue;
}
return createStopFactor(*feasible_stop_pose, {obj_pos});
}
}
return {};
}
std::optional<StopFactor> CrosswalkModule::getNearestStopFactor(
const PathWithLaneId & ego_path,
const std::optional<StopFactor> & stop_factor_for_crosswalk_users,
const std::optional<StopFactor> & stop_factor_for_stuck_vehicles)
{
const auto get_distance_to_stop = [&](const auto stop_factor) -> std::optional<double> {
const auto & ego_pos = planner_data_->current_odometry->pose.position;
if (!stop_factor) return std::nullopt;
return calcSignedArcLength(ego_path.points, ego_pos, stop_factor->stop_pose.position);
};
const auto dist_to_stop_for_crosswalk_users =
get_distance_to_stop(stop_factor_for_crosswalk_users);
const auto dist_to_stop_for_stuck_vehicles = get_distance_to_stop(stop_factor_for_stuck_vehicles);
if (dist_to_stop_for_crosswalk_users) {
if (dist_to_stop_for_stuck_vehicles) {
if (*dist_to_stop_for_stuck_vehicles < *dist_to_stop_for_crosswalk_users) {
return stop_factor_for_stuck_vehicles;
}
}
return stop_factor_for_crosswalk_users;
}
if (dist_to_stop_for_stuck_vehicles) {
return stop_factor_for_stuck_vehicles;
}
return {};
}
void CrosswalkModule::updateObjectState(
const double dist_ego_to_stop, const PathWithLaneId & sparse_resample_path,
const std::pair<double, double> & crosswalk_attention_range, const Polygon2d & attention_area)
{
const auto & objects_ptr = planner_data_->predicted_objects;
const auto traffic_lights_reg_elems =
crosswalk_.regulatoryElementsAs<const lanelet::TrafficLight>();
const bool has_traffic_light = !traffic_lights_reg_elems.empty();
// Check if ego is yielding
const bool is_ego_yielding = [&]() {
const auto has_reached_stop_point = dist_ego_to_stop < planner_param_.stop_position_threshold;
return planner_data_->isVehicleStopped(planner_param_.timeout_ego_stop_for_yield) &&
has_reached_stop_point;
}();
const auto ignore_crosswalk = isRedSignalForPedestrians();
debug_data_.ignore_crosswalk = ignore_crosswalk;
// Update object state
object_info_manager_.init();