forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathmap_based_prediction_node.cpp
2354 lines (2058 loc) · 95.2 KB
/
map_based_prediction_node.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2021 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "map_based_prediction/map_based_prediction_node.hpp"
#include <interpolation/linear_interpolation.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <motion_utils/resample/resample.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/constants.hpp>
#include <tier4_autoware_utils/math/normalization.hpp>
#include <tier4_autoware_utils/math/unit_conversion.hpp>
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <boost/geometry.hpp>
#include <boost/geometry/geometries/polygon.hpp>
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_core/geometry/Point.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <tf2/utils.h>
#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif
#include <glog/logging.h>
#include <algorithm>
#include <chrono>
#include <cmath>
#include <functional>
#include <limits>
namespace map_based_prediction
{
namespace
{
/**
* @brief First order Low pass filtering
*
* @param prev_y previous filtered value
* @param prev_x previous input value
* @param x current input value
* @param cutoff_freq cutoff frequency in Hz not rad/s (1/s)
* @param sampling_time sampling time of discrete system (s)
*
* @return double current filtered value
*/
double FirstOrderLowpassFilter(
const double prev_y, const double prev_x, const double x, const double sampling_time = 0.1,
const double cutoff_freq = 0.1)
{
// Eq: yn = a yn-1 + b (xn-1 + xn)
const double wt = 2.0 * M_PI * cutoff_freq * sampling_time;
const double a = (2.0 - wt) / (2.0 + wt);
const double b = wt / (2.0 + wt);
return a * prev_y + b * (prev_x + x);
}
/**
* @brief calc lateral offset from pose to linestring
*
* @param boundary_line 2d line strings
* @param search_pose search point
* @return double
*/
double calcAbsLateralOffset(
const lanelet::ConstLineString2d & boundary_line, const geometry_msgs::msg::Pose & search_pose)
{
std::vector<geometry_msgs::msg::Point> boundary_path(boundary_line.size());
for (size_t i = 0; i < boundary_path.size(); ++i) {
const double x = boundary_line[i].x();
const double y = boundary_line[i].y();
boundary_path[i] = tier4_autoware_utils::createPoint(x, y, 0.0);
}
return std::fabs(motion_utils::calcLateralOffset(boundary_path, search_pose.position));
}
/**
* @brief init lateral kinematics struct
*
* @param lanelet closest lanelet
* @param pose search pose
* @return lateral kinematics data struct
*/
LateralKinematicsToLanelet initLateralKinematics(
const lanelet::ConstLanelet & lanelet, geometry_msgs::msg::Pose pose)
{
LateralKinematicsToLanelet lateral_kinematics;
const lanelet::ConstLineString2d left_bound = lanelet.leftBound2d();
const lanelet::ConstLineString2d right_bound = lanelet.rightBound2d();
const double left_dist = calcAbsLateralOffset(left_bound, pose);
const double right_dist = calcAbsLateralOffset(right_bound, pose);
// calc boundary distance
lateral_kinematics.dist_from_left_boundary = left_dist;
lateral_kinematics.dist_from_right_boundary = right_dist;
// velocities are not init in the first step
lateral_kinematics.left_lateral_velocity = 0;
lateral_kinematics.right_lateral_velocity = 0;
lateral_kinematics.filtered_left_lateral_velocity = 0;
lateral_kinematics.filtered_right_lateral_velocity = 0;
return lateral_kinematics;
}
/**
* @brief calc lateral velocity and filtered velocity of object in a lanelet
*
* @param prev_lateral_kinematics previous lateral lanelet kinematics
* @param current_lateral_kinematics current lateral lanelet kinematics
* @param dt sampling time [s]
*/
void calcLateralKinematics(
const LateralKinematicsToLanelet & prev_lateral_kinematics,
LateralKinematicsToLanelet & current_lateral_kinematics, const double dt, const double cutoff)
{
// calc velocity via backward difference
current_lateral_kinematics.left_lateral_velocity =
(current_lateral_kinematics.dist_from_left_boundary -
prev_lateral_kinematics.dist_from_left_boundary) /
dt;
current_lateral_kinematics.right_lateral_velocity =
(current_lateral_kinematics.dist_from_right_boundary -
prev_lateral_kinematics.dist_from_right_boundary) /
dt;
// low pass filtering left velocity: default cut_off is 0.6 Hz
current_lateral_kinematics.filtered_left_lateral_velocity = FirstOrderLowpassFilter(
prev_lateral_kinematics.filtered_left_lateral_velocity,
prev_lateral_kinematics.left_lateral_velocity, current_lateral_kinematics.left_lateral_velocity,
dt, cutoff);
current_lateral_kinematics.filtered_right_lateral_velocity = FirstOrderLowpassFilter(
prev_lateral_kinematics.filtered_right_lateral_velocity,
prev_lateral_kinematics.right_lateral_velocity,
current_lateral_kinematics.right_lateral_velocity, dt, cutoff);
}
/**
* @brief look for matching lanelet between current/previous object state and calculate velocity
*
* @param prev_obj previous ObjectData
* @param current_obj current ObjectData to be updated
* @param routing_graph_ptr_ routing graph pointer
*/
void updateLateralKinematicsVector(
const ObjectData & prev_obj, ObjectData & current_obj,
const lanelet::routing::RoutingGraphPtr routing_graph_ptr_, const double lowpass_cutoff)
{
const double dt = (current_obj.header.stamp.sec - prev_obj.header.stamp.sec) +
(current_obj.header.stamp.nanosec - prev_obj.header.stamp.nanosec) * 1e-9;
if (dt < 1e-6) {
return; // do not update
}
// look for matching lanelet between current and previous kinematics
for (auto & current_set : current_obj.lateral_kinematics_set) {
const auto & current_lane = current_set.first;
auto & current_lateral_kinematics = current_set.second;
// 1. has same lanelet
if (prev_obj.lateral_kinematics_set.count(current_lane) != 0) {
const auto & prev_lateral_kinematics = prev_obj.lateral_kinematics_set.at(current_lane);
calcLateralKinematics(
prev_lateral_kinematics, current_lateral_kinematics, dt, lowpass_cutoff);
break;
}
// 2. successive lanelet
for (auto & prev_set : prev_obj.lateral_kinematics_set) {
const auto & prev_lane = prev_set.first;
const auto & prev_lateral_kinematics = prev_set.second;
const bool successive_lanelet =
routing_graph_ptr_->routingRelation(prev_lane, current_lane) ==
lanelet::routing::RelationType::Successor;
if (successive_lanelet) { // lanelet can be connected
calcLateralKinematics(
prev_lateral_kinematics, current_lateral_kinematics, dt,
lowpass_cutoff); // calc velocity
break;
}
}
}
}
/**
* @brief calc absolute normalized yaw difference between lanelet and object
*
* @param object
* @param lanelet
* @return double
*/
double calcAbsYawDiffBetweenLaneletAndObject(
const TrackedObject & object, const lanelet::ConstLanelet & lanelet)
{
const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation);
const double lane_yaw =
lanelet::utils::getLaneletAngle(lanelet, object.kinematics.pose_with_covariance.pose.position);
const double delta_yaw = object_yaw - lane_yaw;
const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw);
const double abs_norm_delta = std::fabs(normalized_delta_yaw);
return abs_norm_delta;
}
/**
* @brief Get the Right LineSharing Lanelets object
*
* @param current_lanelet
* @param lanelet_map_ptr
* @return lanelet::ConstLanelets
*/
lanelet::ConstLanelets getRightLineSharingLanelets(
const lanelet::ConstLanelet & current_lanelet, const lanelet::LaneletMapPtr & lanelet_map_ptr)
{
lanelet::ConstLanelets
output_lanelets; // create an empty container of type lanelet::ConstLanelets
// step1: look for lane sharing current right bound
lanelet::Lanelets right_lane_candidates =
lanelet_map_ptr->laneletLayer.findUsages(current_lanelet.rightBound());
for (auto & candidate : right_lane_candidates) {
// exclude self lanelet
if (candidate == current_lanelet) continue;
// if candidate has linestring as left bound, assign it to output
if (candidate.leftBound() == current_lanelet.rightBound()) {
output_lanelets.push_back(candidate);
}
}
return output_lanelets; // return empty
}
/**
* @brief Get the Left LineSharing Lanelets object
*
* @param current_lanelet
* @param lanelet_map_ptr
* @return lanelet::ConstLanelets
*/
lanelet::ConstLanelets getLeftLineSharingLanelets(
const lanelet::ConstLanelet & current_lanelet, const lanelet::LaneletMapPtr & lanelet_map_ptr)
{
lanelet::ConstLanelets
output_lanelets; // create an empty container of type lanelet::ConstLanelets
// step1: look for lane sharing current left bound
lanelet::Lanelets left_lane_candidates =
lanelet_map_ptr->laneletLayer.findUsages(current_lanelet.leftBound());
for (auto & candidate : left_lane_candidates) {
// exclude self lanelet
if (candidate == current_lanelet) continue;
// if candidate has linestring as right bound, assign it to output
if (candidate.rightBound() == current_lanelet.leftBound()) {
output_lanelets.push_back(candidate);
}
}
return output_lanelets; // return empty
}
/**
* @brief Check if the lanelet is isolated in routing graph
* @param current_lanelet
* @param lanelet_map_ptr
*/
bool isIsolatedLanelet(
const lanelet::ConstLanelet & lanelet, lanelet::routing::RoutingGraphPtr & graph)
{
const auto & following_lanelets = graph->following(lanelet);
const auto & left_lanelets = graph->lefts(lanelet);
const auto & right_lanelets = graph->rights(lanelet);
return left_lanelets.empty() && right_lanelets.empty() && following_lanelets.empty();
}
/**
* @brief Get the Possible Paths For Isolated Lanelet object
* @param lanelet
* @return lanelet::routing::LaneletPaths
*/
lanelet::routing::LaneletPaths getPossiblePathsForIsolatedLanelet(
const lanelet::ConstLanelet & lanelet)
{
lanelet::ConstLanelets possible_lanelets;
possible_lanelets.push_back(lanelet);
lanelet::routing::LaneletPaths possible_paths;
// need to initialize path with constant lanelets
lanelet::routing::LaneletPath possible_path(possible_lanelets);
possible_paths.push_back(possible_path);
return possible_paths;
}
/**
* @brief validate isolated lanelet length has enough length for prediction
* @param lanelet
* @param object: object information for calc length threshold
* @param prediction_time: time horizon[s] for calc length threshold
* @return bool
*/
bool validateIsolatedLaneletLength(
const lanelet::ConstLanelet & lanelet, const TrackedObject & object, const double prediction_time)
{
// get closest center line point to object
const auto & center_line = lanelet.centerline2d();
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
const lanelet::BasicPoint2d obj_point(obj_pos.x, obj_pos.y);
// get end point of the center line
const auto & end_point = center_line.back();
// calc approx distance between closest point and end point
const double approx_distance = lanelet::geometry::distance2d(obj_point, end_point);
// calc min length for prediction
const double abs_speed = std::hypot(
object.kinematics.twist_with_covariance.twist.linear.x,
object.kinematics.twist_with_covariance.twist.linear.y);
const double min_length = abs_speed * prediction_time;
return approx_distance > min_length;
}
lanelet::ConstLanelets getLanelets(const map_based_prediction::LaneletsData & data)
{
lanelet::ConstLanelets lanelets;
for (const auto & lanelet_data : data) {
lanelets.push_back(lanelet_data.lanelet);
}
return lanelets;
}
CrosswalkEdgePoints getCrosswalkEdgePoints(const lanelet::ConstLanelet & crosswalk)
{
const Eigen::Vector2d r_p_front = crosswalk.rightBound().front().basicPoint2d();
const Eigen::Vector2d l_p_front = crosswalk.leftBound().front().basicPoint2d();
const Eigen::Vector2d front_center_point = (r_p_front + l_p_front) / 2.0;
const Eigen::Vector2d r_p_back = crosswalk.rightBound().back().basicPoint2d();
const Eigen::Vector2d l_p_back = crosswalk.leftBound().back().basicPoint2d();
const Eigen::Vector2d back_center_point = (r_p_back + l_p_back) / 2.0;
return CrosswalkEdgePoints{front_center_point, r_p_front, l_p_front,
back_center_point, r_p_back, l_p_back};
}
bool withinLanelet(
const TrackedObject & object, const lanelet::ConstLanelet & lanelet,
const bool use_yaw_information = false, const float yaw_threshold = 0.6)
{
using Point = boost::geometry::model::d2::point_xy<double>;
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
const Point p_object{obj_pos.x, obj_pos.y};
auto polygon = lanelet.polygon2d().basicPolygon();
boost::geometry::correct(polygon);
bool with_in_polygon = boost::geometry::within(p_object, polygon);
if (!use_yaw_information) return with_in_polygon;
// use yaw angle to compare
const double abs_yaw_diff = calcAbsYawDiffBetweenLaneletAndObject(object, lanelet);
if (abs_yaw_diff < yaw_threshold) return with_in_polygon;
return false;
}
bool withinRoadLanelet(
const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr,
const bool use_yaw_information = false)
{
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
lanelet::BasicPoint2d search_point(obj_pos.x, obj_pos.y);
// nearest lanelet
constexpr double search_radius = 10.0; // [m]
const auto surrounding_lanelets =
lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, search_radius);
for (const auto & lanelet : surrounding_lanelets) {
if (lanelet.second.hasAttribute(lanelet::AttributeName::Subtype)) {
lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype);
if (
attr.value() == lanelet::AttributeValueString::Crosswalk ||
attr.value() == lanelet::AttributeValueString::Walkway) {
continue;
}
}
if (withinLanelet(object, lanelet.second, use_yaw_information)) {
return true;
}
}
return false;
}
boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
const TrackedObject & object, const lanelet::ConstLanelet & target_crosswalk,
const CrosswalkEdgePoints & edge_points, const lanelet::LaneletMapPtr & lanelet_map_ptr,
const double time_horizon, const double min_object_vel)
{
using Point = boost::geometry::model::d2::point_xy<double>;
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear;
const auto yaw = tier4_autoware_utils::getRPY(object.kinematics.pose_with_covariance.pose).z;
lanelet::BasicPoint2d obj_pos_as_lanelet(obj_pos.x, obj_pos.y);
if (boost::geometry::within(obj_pos_as_lanelet, target_crosswalk.polygon2d().basicPolygon())) {
return {};
}
const auto & p1 = edge_points.front_center_point;
const auto & p2 = edge_points.back_center_point;
CrosswalkEdgePoints ret{p1, {}, {}, p2, {}, {}};
auto distance_pedestrian_to_p1 = std::hypot(p1.x() - obj_pos.x, p1.y() - obj_pos.y);
auto distance_pedestrian_to_p2 = std::hypot(p2.x() - obj_pos.x, p2.y() - obj_pos.y);
if (distance_pedestrian_to_p2 < distance_pedestrian_to_p1) {
ret.swap();
std::swap(distance_pedestrian_to_p1, distance_pedestrian_to_p2);
}
constexpr double stop_velocity_th = 0.14; // [m/s]
const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
const auto is_stop_object = estimated_velocity < stop_velocity_th;
const auto velocity = std::max(min_object_vel, estimated_velocity);
const auto surrounding_lanelets = lanelet::geometry::findNearest(
lanelet_map_ptr->laneletLayer, obj_pos_as_lanelet, time_horizon * velocity);
const auto isAcrossAnyRoad = [&surrounding_lanelets](const Point & p_src, const Point & p_dst) {
const auto withinAnyCrosswalk = [&surrounding_lanelets](const Point & p) {
for (const auto & lanelet : surrounding_lanelets) {
const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype);
if (
(attr.value() == lanelet::AttributeValueString::Crosswalk ||
attr.value() == lanelet::AttributeValueString::Walkway) &&
boost::geometry::within(p, lanelet.second.polygon2d().basicPolygon())) {
return true;
}
}
return false;
};
const auto isExist = [](const Point & p, const std::vector<Point> & points) {
for (const auto & existingPoint : points) {
if (boost::geometry::distance(p, existingPoint) < 1e-1) {
return true;
}
}
return false;
};
std::vector<Point> points_of_intersect;
const boost::geometry::model::linestring<Point> line{p_src, p_dst};
for (const auto & lanelet : surrounding_lanelets) {
const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype);
if (attr.value() != lanelet::AttributeValueString::Road) {
continue;
}
std::vector<Point> tmp_intersects;
boost::geometry::intersection(
line, lanelet.second.polygon2d().basicPolygon(), tmp_intersects);
for (const auto & p : tmp_intersects) {
if (isExist(p, points_of_intersect) || withinAnyCrosswalk(p)) {
continue;
}
points_of_intersect.push_back(p);
if (points_of_intersect.size() >= 2) {
return true;
}
}
}
return false;
};
const bool first_intersects_road = isAcrossAnyRoad(
{obj_pos.x, obj_pos.y}, {ret.front_center_point.x(), ret.front_center_point.y()});
const bool second_intersects_road =
isAcrossAnyRoad({obj_pos.x, obj_pos.y}, {ret.back_center_point.x(), ret.back_center_point.y()});
if (first_intersects_road && second_intersects_road) {
return {};
}
if (first_intersects_road && !second_intersects_road) {
ret.swap();
}
const Eigen::Vector2d pedestrian_to_crosswalk(
(ret.front_center_point.x() + ret.back_center_point.x()) / 2.0 - obj_pos.x,
(ret.front_center_point.y() + ret.back_center_point.y()) / 2.0 - obj_pos.y);
const Eigen::Vector2d pedestrian_heading_direction(
obj_vel.x * std::cos(yaw), obj_vel.x * std::sin(yaw));
const auto reachable =
std::min(distance_pedestrian_to_p1, distance_pedestrian_to_p2) < velocity * time_horizon;
const auto heading_for_crosswalk =
pedestrian_to_crosswalk.dot(pedestrian_heading_direction) > 0.0;
if ((reachable && heading_for_crosswalk) || (reachable && is_stop_object)) {
return ret;
}
return {};
}
bool hasPotentialToReach(
const TrackedObject & object, const Eigen::Vector2d & center_point,
const Eigen::Vector2d & right_point, const Eigen::Vector2d & left_point,
const double time_horizon, const double min_object_vel,
const double max_crosswalk_user_delta_yaw_threshold_for_lanelet)
{
const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear;
const auto yaw = tier4_autoware_utils::getRPY(object.kinematics.pose_with_covariance.pose).z;
constexpr double stop_velocity_th = 0.14; // [m/s]
const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
const auto is_stop_object = estimated_velocity < stop_velocity_th;
const auto velocity = std::max(min_object_vel, estimated_velocity);
const double pedestrian_to_crosswalk_center_direction =
std::atan2(center_point.y() - obj_pos.y, center_point.x() - obj_pos.x);
const auto
[pedestrian_to_crosswalk_right_rel_direction, pedestrian_to_crosswalk_left_rel_direction] =
[&]() {
const double pedestrian_to_crosswalk_right_direction =
std::atan2(right_point.y() - obj_pos.y, right_point.x() - obj_pos.x);
const double pedestrian_to_crosswalk_left_direction =
std::atan2(left_point.y() - obj_pos.y, left_point.x() - obj_pos.x);
return std::make_pair(
tier4_autoware_utils::normalizeRadian(
pedestrian_to_crosswalk_right_direction - pedestrian_to_crosswalk_center_direction),
tier4_autoware_utils::normalizeRadian(
pedestrian_to_crosswalk_left_direction - pedestrian_to_crosswalk_center_direction));
}();
const double pedestrian_heading_rel_direction = [&]() {
const double pedestrian_heading_direction =
std::atan2(obj_vel.x * std::sin(yaw), obj_vel.x * std::cos(yaw));
return tier4_autoware_utils::normalizeRadian(
pedestrian_heading_direction - pedestrian_to_crosswalk_center_direction);
}();
const double pedestrian_to_crosswalk_min_rel_direction = std::min(
pedestrian_to_crosswalk_right_rel_direction, pedestrian_to_crosswalk_left_rel_direction);
const double pedestrian_to_crosswalk_max_rel_direction = std::max(
pedestrian_to_crosswalk_right_rel_direction, pedestrian_to_crosswalk_left_rel_direction);
const double pedestrian_vel_angle_against_crosswalk = [&]() {
if (pedestrian_heading_rel_direction < pedestrian_to_crosswalk_min_rel_direction) {
return pedestrian_to_crosswalk_min_rel_direction - pedestrian_heading_rel_direction;
}
if (pedestrian_to_crosswalk_max_rel_direction < pedestrian_heading_rel_direction) {
return pedestrian_to_crosswalk_max_rel_direction - pedestrian_heading_rel_direction;
}
return 0.0;
}();
const auto heading_for_crosswalk = std::abs(pedestrian_vel_angle_against_crosswalk) <
max_crosswalk_user_delta_yaw_threshold_for_lanelet;
const auto reachable = std::hypot(center_point.x() - obj_pos.x, center_point.y() - obj_pos.y) <
velocity * time_horizon;
if (reachable && (heading_for_crosswalk || is_stop_object)) {
return true;
}
return false;
}
/**
* @brief change label for prediction
*
* @param label
* @return ObjectClassification::_label_type
*/
ObjectClassification::_label_type changeLabelForPrediction(
const ObjectClassification::_label_type & label, const TrackedObject & object,
const lanelet::LaneletMapPtr & lanelet_map_ptr_)
{
// for car like vehicle do not change labels
switch (label) {
case ObjectClassification::CAR:
case ObjectClassification::BUS:
case ObjectClassification::TRUCK:
case ObjectClassification::TRAILER:
case ObjectClassification::UNKNOWN:
return label;
case ObjectClassification::MOTORCYCLE:
case ObjectClassification::BICYCLE: { // if object is within road lanelet and satisfies yaw
// constraints
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
// if the object is within lanelet, do the same estimation with vehicle
if (within_road_lanelet) return ObjectClassification::MOTORCYCLE;
constexpr float high_speed_threshold =
tier4_autoware_utils::kmph2mps(25.0); // High speed bicycle 25 km/h
// calc abs speed from x and y velocity
const double abs_speed = std::hypot(
object.kinematics.twist_with_covariance.twist.linear.x,
object.kinematics.twist_with_covariance.twist.linear.y);
const bool high_speed_object = abs_speed > high_speed_threshold;
// high speed object outside road lanelet will move like unknown object
// return ObjectClassification::UNKNOWN; // temporary disabled
if (high_speed_object) return label; // Do nothing for now
return ObjectClassification::BICYCLE;
}
case ObjectClassification::PEDESTRIAN: {
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
const float max_velocity_for_human_mps =
tier4_autoware_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h
const double abs_speed = std::hypot(
object.kinematics.twist_with_covariance.twist.linear.x,
object.kinematics.twist_with_covariance.twist.linear.y);
const bool high_speed_object = abs_speed > max_velocity_for_human_mps;
// fast, human-like object: like segway
if (within_road_lanelet && high_speed_object) return label; // currently do nothing
// return ObjectClassification::MOTORCYCLE;
if (high_speed_object) return label; // currently do nothing
// fast human outside road lanelet will move like unknown object
// return ObjectClassification::UNKNOWN;
return label;
}
default:
return label;
}
}
StringStamped createStringStamped(const rclcpp::Time & now, const double data)
{
StringStamped msg;
msg.stamp = now;
msg.data = std::to_string(data);
return msg;
}
// NOTE: These two functions are copied from the route_handler package.
lanelet::Lanelets getRightOppositeLanelets(
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
const lanelet::ConstLanelet & lanelet)
{
const auto opposite_candidate_lanelets =
lanelet_map_ptr->laneletLayer.findUsages(lanelet.rightBound().invert());
lanelet::Lanelets opposite_lanelets;
for (const auto & candidate_lanelet : opposite_candidate_lanelets) {
if (candidate_lanelet.leftBound().id() == lanelet.rightBound().id()) {
continue;
}
opposite_lanelets.push_back(candidate_lanelet);
}
return opposite_lanelets;
}
lanelet::Lanelets getLeftOppositeLanelets(
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
const lanelet::ConstLanelet & lanelet)
{
const auto opposite_candidate_lanelets =
lanelet_map_ptr->laneletLayer.findUsages(lanelet.leftBound().invert());
lanelet::Lanelets opposite_lanelets;
for (const auto & candidate_lanelet : opposite_candidate_lanelets) {
if (candidate_lanelet.rightBound().id() == lanelet.leftBound().id()) {
continue;
}
opposite_lanelets.push_back(candidate_lanelet);
}
return opposite_lanelets;
}
void replaceObjectYawWithLaneletsYaw(
const LaneletsData & current_lanelets, TrackedObject & transformed_object)
{
// return if no lanelet is found
if (current_lanelets.empty()) return;
auto & pose_with_cov = transformed_object.kinematics.pose_with_covariance;
// for each lanelet, calc lanelet angle and calculate mean angle
double sum_x = 0.0;
double sum_y = 0.0;
for (const auto & current_lanelet : current_lanelets) {
const auto lanelet_angle =
lanelet::utils::getLaneletAngle(current_lanelet.lanelet, pose_with_cov.pose.position);
sum_x += std::cos(lanelet_angle);
sum_y += std::sin(lanelet_angle);
}
const double mean_yaw_angle = std::atan2(sum_y, sum_x);
double roll, pitch, yaw;
tf2::Quaternion original_quaternion;
tf2::fromMsg(pose_with_cov.pose.orientation, original_quaternion);
tf2::Matrix3x3(original_quaternion).getRPY(roll, pitch, yaw);
tf2::Quaternion filtered_quaternion;
filtered_quaternion.setRPY(roll, pitch, mean_yaw_angle);
pose_with_cov.pose.orientation = tf2::toMsg(filtered_quaternion);
}
} // namespace
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
{
google::InitGoogleLogging("map_based_prediction_node");
google::InstallFailureSignalHandler();
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
lateral_control_time_horizon_ =
declare_parameter<double>("lateral_control_time_horizon"); // [s] for lateral control point
prediction_sampling_time_interval_ = declare_parameter<double>("prediction_sampling_delta_time");
min_velocity_for_map_based_prediction_ =
declare_parameter<double>("min_velocity_for_map_based_prediction");
min_crosswalk_user_velocity_ = declare_parameter<double>("min_crosswalk_user_velocity");
max_crosswalk_user_delta_yaw_threshold_for_lanelet_ =
declare_parameter<double>("max_crosswalk_user_delta_yaw_threshold_for_lanelet");
dist_threshold_for_searching_lanelet_ =
declare_parameter<double>("dist_threshold_for_searching_lanelet");
delta_yaw_threshold_for_searching_lanelet_ =
declare_parameter<double>("delta_yaw_threshold_for_searching_lanelet");
sigma_lateral_offset_ = declare_parameter<double>("sigma_lateral_offset");
sigma_yaw_angle_deg_ = declare_parameter<double>("sigma_yaw_angle_deg");
object_buffer_time_length_ = declare_parameter<double>("object_buffer_time_length");
history_time_length_ = declare_parameter<double>("history_time_length");
check_lateral_acceleration_constraints_ =
declare_parameter<bool>("check_lateral_acceleration_constraints");
max_lateral_accel_ = declare_parameter<double>("max_lateral_accel");
min_acceleration_before_curve_ = declare_parameter<double>("min_acceleration_before_curve");
{ // lane change detection
lane_change_detection_method_ = declare_parameter<std::string>("lane_change_detection.method");
// lane change detection by time_to_change_lane
dist_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection"); // 1m
time_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection");
cutoff_freq_of_velocity_lpf_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_"
"detection");
// lane change detection by lat_diff_distance
dist_ratio_threshold_to_left_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.dist_ratio_threshold_to_left_bound");
dist_ratio_threshold_to_right_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.dist_ratio_threshold_to_right_bound");
diff_dist_threshold_to_left_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.diff_dist_threshold_to_left_bound");
diff_dist_threshold_to_right_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.diff_dist_threshold_to_right_bound");
num_continuous_state_transition_ =
declare_parameter<int>("lane_change_detection.num_continuous_state_transition");
consider_only_routable_neighbours_ =
declare_parameter<bool>("lane_change_detection.consider_only_routable_neighbours");
}
reference_path_resolution_ = declare_parameter<double>("reference_path_resolution");
/* prediction path will disabled when the estimated path length exceeds lanelet length. This
* parameter control the estimated path length = vx * th * (rate) */
prediction_time_horizon_rate_for_validate_lane_length_ =
declare_parameter<double>("prediction_time_horizon_rate_for_validate_shoulder_lane_length");
use_vehicle_acceleration_ = declare_parameter<bool>("use_vehicle_acceleration");
speed_limit_multiplier_ = declare_parameter<double>("speed_limit_multiplier");
acceleration_exponential_half_life_ =
declare_parameter<double>("acceleration_exponential_half_life");
use_crosswalk_signal_ = declare_parameter<bool>("crosswalk_with_signal.use_crosswalk_signal");
threshold_velocity_assumed_as_stopping_ =
declare_parameter<double>("crosswalk_with_signal.threshold_velocity_assumed_as_stopping");
distance_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
"crosswalk_with_signal.distance_set_for_no_intention_to_walk");
timeout_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
"crosswalk_with_signal.timeout_set_for_no_intention_to_walk");
path_generator_ = std::make_shared<PathGenerator>(
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
min_crosswalk_user_velocity_);
path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_);
path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_);
sub_objects_ = this->create_subscription<TrackedObjects>(
"~/input/objects", 1,
std::bind(&MapBasedPredictionNode::objectsCallback, this, std::placeholders::_1));
sub_map_ = this->create_subscription<HADMapBin>(
"/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&MapBasedPredictionNode::mapCallback, this, std::placeholders::_1));
sub_traffic_signals_ = this->create_subscription<TrafficSignalArray>(
"/traffic_signals", 1,
std::bind(&MapBasedPredictionNode::trafficSignalsCallback, this, std::placeholders::_1));
pub_objects_ = this->create_publisher<PredictedObjects>("~/output/objects", rclcpp::QoS{1});
pub_debug_markers_ =
this->create_publisher<visualization_msgs::msg::MarkerArray>("maneuver", rclcpp::QoS{1});
pub_calculation_time_ = create_publisher<StringStamped>("~/debug/calculation_time", 1);
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));
}
rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam(
const std::vector<rclcpp::Parameter> & parameters)
{
using tier4_autoware_utils::updateParam;
updateParam(parameters, "max_lateral_accel", max_lateral_accel_);
updateParam(parameters, "min_acceleration_before_curve", min_acceleration_before_curve_);
updateParam(
parameters, "check_lateral_acceleration_constraints", check_lateral_acceleration_constraints_);
updateParam(parameters, "use_vehicle_acceleration", use_vehicle_acceleration_);
updateParam(parameters, "speed_limit_multiplier", speed_limit_multiplier_);
updateParam(
parameters, "acceleration_exponential_half_life", acceleration_exponential_half_life_);
path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_);
path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_);
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
result.reason = "success";
return result;
}
PredictedObjectKinematics MapBasedPredictionNode::convertToPredictedKinematics(
const TrackedObjectKinematics & tracked_object)
{
PredictedObjectKinematics output;
output.initial_pose_with_covariance = tracked_object.pose_with_covariance;
output.initial_twist_with_covariance = tracked_object.twist_with_covariance;
output.initial_acceleration_with_covariance = tracked_object.acceleration_with_covariance;
return output;
}
PredictedObject MapBasedPredictionNode::convertToPredictedObject(
const TrackedObject & tracked_object)
{
PredictedObject predicted_object;
predicted_object.kinematics = convertToPredictedKinematics(tracked_object.kinematics);
predicted_object.classification = tracked_object.classification;
predicted_object.object_id = tracked_object.object_id;
predicted_object.shape = tracked_object.shape;
predicted_object.existence_probability = tracked_object.existence_probability;
return predicted_object;
}
void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg)
{
RCLCPP_INFO(get_logger(), "[Map Based Prediction]: Start loading lanelet");
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::fromBinMsg(
*msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_);
RCLCPP_INFO(get_logger(), "[Map Based Prediction]: Map is loaded");
const auto all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
const auto crosswalks = lanelet::utils::query::crosswalkLanelets(all_lanelets);
const auto walkways = lanelet::utils::query::walkwayLanelets(all_lanelets);
crosswalks_.insert(crosswalks_.end(), crosswalks.begin(), crosswalks.end());
crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end());
}
void MapBasedPredictionNode::trafficSignalsCallback(const TrafficSignalArray::ConstSharedPtr msg)
{
traffic_signal_id_map_.clear();
for (const auto & signal : msg->signals) {
traffic_signal_id_map_[signal.traffic_signal_id] = signal;
}
}
void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects)
{
stop_watch_.tic();
// Guard for map pointer and frame transformation
if (!lanelet_map_ptr_) {
return;
}
auto world2map_transform = transform_listener_.getTransform(
"map", // target
in_objects->header.frame_id, // src
in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1));
auto map2world_transform = transform_listener_.getTransform(
in_objects->header.frame_id, // target
"map", // src
in_objects->header.stamp, rclcpp::Duration::from_seconds(0.1));
auto debug_map2lidar_transform = transform_listener_.getTransform(
"base_link", // target
"map", // src
rclcpp::Time(), rclcpp::Duration::from_seconds(0.1));
if (!world2map_transform || !map2world_transform || !debug_map2lidar_transform) {
return;
}
// Remove old objects information in object history
const double objects_detected_time = rclcpp::Time(in_objects->header.stamp).seconds();
removeOldObjectsHistory(objects_detected_time, in_objects);
// result output
PredictedObjects output;
output.header = in_objects->header;
output.header.frame_id = "map";
// result debug
visualization_msgs::msg::MarkerArray debug_markers;
for (const auto & object : in_objects->objects) {
std::string object_id = tier4_autoware_utils::toHexString(object.object_id);
TrackedObject transformed_object = object;
// transform object frame if it's based on map frame
if (in_objects->header.frame_id != "map") {
geometry_msgs::msg::PoseStamped pose_in_map;
geometry_msgs::msg::PoseStamped pose_orig;
pose_orig.pose = object.kinematics.pose_with_covariance.pose;
tf2::doTransform(pose_orig, pose_in_map, *world2map_transform);
transformed_object.kinematics.pose_with_covariance.pose = pose_in_map.pose;
}
// get tracking label and update it for the prediction
const auto & label_ = transformed_object.classification.front().label;
const auto label = changeLabelForPrediction(label_, object, lanelet_map_ptr_);
switch (label) {
case ObjectClassification::PEDESTRIAN:
case ObjectClassification::BICYCLE: {
const auto predicted_object_crosswalk =
getPredictedObjectAsCrosswalkUser(transformed_object);
output.objects.push_back(predicted_object_crosswalk);
break;
}
case ObjectClassification::CAR:
case ObjectClassification::BUS:
case ObjectClassification::TRAILER:
case ObjectClassification::MOTORCYCLE:
case ObjectClassification::TRUCK: {
// Update object yaw and velocity
updateObjectData(transformed_object);
// Get Closest Lanelet
const auto current_lanelets = getCurrentLanelets(transformed_object);
// Update Objects History
updateObjectsHistory(output.header, transformed_object, current_lanelets);
// For off lane obstacles
if (current_lanelets.empty()) {
PredictedPath predicted_path =
path_generator_->generatePathForOffLaneVehicle(transformed_object);
predicted_path.confidence = 1.0;
if (predicted_path.path.empty()) break;
auto predicted_object_vehicle = convertToPredictedObject(transformed_object);
predicted_object_vehicle.kinematics.predicted_paths.push_back(predicted_path);
output.objects.push_back(predicted_object_vehicle);
break;
}
// For too-slow vehicle
const double abs_obj_speed = std::hypot(
transformed_object.kinematics.twist_with_covariance.twist.linear.x,
transformed_object.kinematics.twist_with_covariance.twist.linear.y);
if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) {
PredictedPath predicted_path =
path_generator_->generatePathForLowSpeedVehicle(transformed_object);
predicted_path.confidence = 1.0;
if (predicted_path.path.empty()) break;
auto predicted_slow_object = convertToPredictedObject(transformed_object);
predicted_slow_object.kinematics.predicted_paths.push_back(predicted_path);
output.objects.push_back(predicted_slow_object);
break;
}
// Get Predicted Reference Path for Each Maneuver and current lanelets
// return: <probability, paths>