forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathnode.cpp
1663 lines (1454 loc) · 69.9 KB
/
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 2022 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 "obstacle_cruise_planner/node.hpp"
#include "motion_utils/resample/resample.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "obstacle_cruise_planner/polygon_utils.hpp"
#include "obstacle_cruise_planner/utils.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include <boost/format.hpp>
#include <algorithm>
#include <chrono>
namespace
{
VelocityLimitClearCommand createVelocityLimitClearCommandMessage(
const rclcpp::Time & current_time, const std::string & module_name)
{
VelocityLimitClearCommand msg;
msg.stamp = current_time;
msg.sender = "obstacle_cruise_planner." + module_name;
msg.command = true;
return msg;
}
template <typename T>
std::optional<T> getObstacleFromUuid(
const std::vector<T> & obstacles, const std::string & target_uuid)
{
const auto itr = std::find_if(obstacles.begin(), obstacles.end(), [&](const auto & obstacle) {
return obstacle.uuid == target_uuid;
});
if (itr == obstacles.end()) {
return std::nullopt;
}
return *itr;
}
std::optional<double> calcDistanceToFrontVehicle(
const std::vector<TrajectoryPoint> & traj_points, const size_t ego_idx,
const geometry_msgs::msg::Point & obstacle_pos)
{
const size_t obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle_pos);
const auto ego_to_obstacle_distance =
motion_utils::calcSignedArcLength(traj_points, ego_idx, obstacle_idx);
if (ego_to_obstacle_distance < 0.0) return std::nullopt;
return ego_to_obstacle_distance;
}
PredictedPath resampleHighestConfidencePredictedPath(
const std::vector<PredictedPath> & predicted_paths, const double time_interval,
const double time_horizon)
{
// get highest confidence path
const auto reliable_path = std::max_element(
predicted_paths.begin(), predicted_paths.end(),
[](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; });
// resample
return object_recognition_utils::resamplePredictedPath(
*reliable_path, time_interval, time_horizon);
}
double calcDiffAngleAgainstTrajectory(
const std::vector<TrajectoryPoint> & traj_points, const geometry_msgs::msg::Pose & target_pose)
{
const size_t nearest_idx = motion_utils::findNearestIndex(traj_points, target_pose.position);
const double traj_yaw = tf2::getYaw(traj_points.at(nearest_idx).pose.orientation);
const double target_yaw = tf2::getYaw(target_pose.orientation);
const double diff_yaw = tier4_autoware_utils::normalizeRadian(target_yaw - traj_yaw);
return diff_yaw;
}
std::pair<double, double> projectObstacleVelocityToTrajectory(
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle)
{
const size_t object_idx = motion_utils::findNearestIndex(traj_points, obstacle.pose.position);
const double traj_yaw = tf2::getYaw(traj_points.at(object_idx).pose.orientation);
const double obstacle_yaw = tf2::getYaw(obstacle.pose.orientation);
const Eigen::Rotation2Dd R_ego_to_obstacle(obstacle_yaw - traj_yaw);
const Eigen::Vector2d obstacle_velocity(obstacle.twist.linear.x, obstacle.twist.linear.y);
const Eigen::Vector2d projected_velocity = R_ego_to_obstacle * obstacle_velocity;
return std::make_pair(projected_velocity[0], projected_velocity[1]);
}
double calcObstacleMaxLength(const Shape & shape)
{
if (shape.type == Shape::BOUNDING_BOX) {
return std::hypot(shape.dimensions.x / 2.0, shape.dimensions.y / 2.0);
} else if (shape.type == Shape::CYLINDER) {
return shape.dimensions.x / 2.0;
} else if (shape.type == Shape::POLYGON) {
double max_length_to_point = 0.0;
for (const auto rel_point : shape.footprint.points) {
const double length_to_point = std::hypot(rel_point.x, rel_point.y);
if (max_length_to_point < length_to_point) {
max_length_to_point = length_to_point;
}
}
return max_length_to_point;
}
throw std::logic_error("The shape type is not supported in obstacle_cruise_planner.");
}
TrajectoryPoint getExtendTrajectoryPoint(
const double extend_distance, const TrajectoryPoint & goal_point, const bool is_driving_forward)
{
TrajectoryPoint extend_trajectory_point;
extend_trajectory_point.pose = tier4_autoware_utils::calcOffsetPose(
goal_point.pose, extend_distance * (is_driving_forward ? 1.0 : -1.0), 0.0, 0.0);
extend_trajectory_point.longitudinal_velocity_mps = goal_point.longitudinal_velocity_mps;
extend_trajectory_point.lateral_velocity_mps = goal_point.lateral_velocity_mps;
extend_trajectory_point.acceleration_mps2 = goal_point.acceleration_mps2;
return extend_trajectory_point;
}
std::vector<TrajectoryPoint> extendTrajectoryPoints(
const std::vector<TrajectoryPoint> & input_points, const double extend_distance,
const double step_length)
{
auto output_points = input_points;
const auto is_driving_forward_opt = motion_utils::isDrivingForwardWithTwist(input_points);
const bool is_driving_forward = is_driving_forward_opt ? *is_driving_forward_opt : true;
if (extend_distance < std::numeric_limits<double>::epsilon()) {
return output_points;
}
const auto goal_point = input_points.back();
double extend_sum = 0.0;
while (extend_sum <= (extend_distance - step_length)) {
const auto extend_trajectory_point =
getExtendTrajectoryPoint(extend_sum, goal_point, is_driving_forward);
output_points.push_back(extend_trajectory_point);
extend_sum += step_length;
}
const auto extend_trajectory_point =
getExtendTrajectoryPoint(extend_distance, goal_point, is_driving_forward);
output_points.push_back(extend_trajectory_point);
return output_points;
}
std::vector<int> getTargetObjectType(rclcpp::Node & node, const std::string & param_prefix)
{
std::unordered_map<std::string, int> types_map{
{"unknown", ObjectClassification::UNKNOWN}, {"car", ObjectClassification::CAR},
{"truck", ObjectClassification::TRUCK}, {"bus", ObjectClassification::BUS},
{"trailer", ObjectClassification::TRAILER}, {"motorcycle", ObjectClassification::MOTORCYCLE},
{"bicycle", ObjectClassification::BICYCLE}, {"pedestrian", ObjectClassification::PEDESTRIAN}};
std::vector<int> types;
for (const auto & type : types_map) {
if (node.declare_parameter<bool>(param_prefix + type.first)) {
types.push_back(type.second);
}
}
return types;
}
std::vector<TrajectoryPoint> resampleTrajectoryPoints(
const std::vector<TrajectoryPoint> & traj_points, const double interval)
{
const auto traj = motion_utils::convertToTrajectory(traj_points);
const auto resampled_traj = motion_utils::resampleTrajectory(traj, interval);
return motion_utils::convertToTrajectoryPointArray(resampled_traj);
}
geometry_msgs::msg::Point toGeomPoint(const tier4_autoware_utils::Point2d & point)
{
geometry_msgs::msg::Point geom_point;
geom_point.x = point.x();
geom_point.y = point.y();
return geom_point;
}
bool isLowerConsideringHysteresis(
const double current_val, const bool was_low, const double high_val, const double low_val)
{
if (was_low) {
if (high_val < current_val) {
return false;
}
return true;
}
if (current_val < low_val) {
return true;
}
return false;
}
} // namespace
namespace motion_planning
{
ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationParam(
rclcpp::Node & node)
{ // behavior determination
decimate_trajectory_step_length =
node.declare_parameter<double>("behavior_determination.decimate_trajectory_step_length");
obstacle_velocity_threshold_from_cruise_to_stop = node.declare_parameter<double>(
"behavior_determination.obstacle_velocity_threshold_from_cruise_to_stop");
obstacle_velocity_threshold_from_stop_to_cruise = node.declare_parameter<double>(
"behavior_determination.obstacle_velocity_threshold_from_stop_to_cruise");
crossing_obstacle_velocity_threshold = node.declare_parameter<double>(
"behavior_determination.crossing_obstacle.obstacle_velocity_threshold");
crossing_obstacle_traj_angle_threshold = node.declare_parameter<double>(
"behavior_determination.crossing_obstacle.obstacle_traj_angle_threshold");
collision_time_margin = node.declare_parameter<double>(
"behavior_determination.stop.crossing_obstacle.collision_time_margin");
outside_obstacle_min_velocity_threshold = node.declare_parameter<double>(
"behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold");
ego_obstacle_overlap_time_threshold = node.declare_parameter<double>(
"behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold");
max_prediction_time_for_collision_check = node.declare_parameter<double>(
"behavior_determination.cruise.outside_obstacle.max_prediction_time_for_collision_check");
stop_obstacle_hold_time_threshold =
node.declare_parameter<double>("behavior_determination.stop_obstacle_hold_time_threshold");
prediction_resampling_time_interval =
node.declare_parameter<double>("behavior_determination.prediction_resampling_time_interval");
prediction_resampling_time_horizon =
node.declare_parameter<double>("behavior_determination.prediction_resampling_time_horizon");
max_lat_margin_for_stop =
node.declare_parameter<double>("behavior_determination.stop.max_lat_margin");
max_lat_margin_for_cruise =
node.declare_parameter<double>("behavior_determination.cruise.max_lat_margin");
enable_yield = node.declare_parameter<bool>("behavior_determination.cruise.yield.enable_yield");
yield_lat_distance_threshold =
node.declare_parameter<double>("behavior_determination.cruise.yield.lat_distance_threshold");
max_lat_dist_between_obstacles = node.declare_parameter<double>(
"behavior_determination.cruise.yield.max_lat_dist_between_obstacles");
stopped_obstacle_velocity_threshold = node.declare_parameter<double>(
"behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold");
max_obstacles_collision_time = node.declare_parameter<double>(
"behavior_determination.cruise.yield.max_obstacles_collision_time");
max_lat_margin_for_slow_down =
node.declare_parameter<double>("behavior_determination.slow_down.max_lat_margin");
lat_hysteresis_margin_for_slow_down =
node.declare_parameter<double>("behavior_determination.slow_down.lat_hysteresis_margin");
successive_num_to_entry_slow_down_condition = node.declare_parameter<int>(
"behavior_determination.slow_down.successive_num_to_entry_slow_down_condition");
successive_num_to_exit_slow_down_condition = node.declare_parameter<int>(
"behavior_determination.slow_down.successive_num_to_exit_slow_down_condition");
enable_to_consider_current_pose = node.declare_parameter<bool>(
"behavior_determination.consider_current_pose.enable_to_consider_current_pose");
time_to_convergence = node.declare_parameter<double>(
"behavior_determination.consider_current_pose.time_to_convergence");
}
void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
const std::vector<rclcpp::Parameter> & parameters)
{
// behavior determination
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.decimate_trajectory_step_length",
decimate_trajectory_step_length);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.crossing_obstacle.obstacle_velocity_threshold",
crossing_obstacle_velocity_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.crossing_obstacle.obstacle_traj_angle_threshold",
crossing_obstacle_traj_angle_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop.crossing_obstacle.collision_time_margin",
collision_time_margin);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold",
outside_obstacle_min_velocity_threshold);
tier4_autoware_utils::updateParam<double>(
parameters,
"behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold",
ego_obstacle_overlap_time_threshold);
tier4_autoware_utils::updateParam<double>(
parameters,
"behavior_determination.cruise.outside_obstacle.max_prediction_time_for_collision_check",
max_prediction_time_for_collision_check);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop_obstacle_hold_time_threshold",
stop_obstacle_hold_time_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.prediction_resampling_time_interval",
prediction_resampling_time_interval);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.prediction_resampling_time_horizon",
prediction_resampling_time_horizon);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.stop.max_lat_margin", max_lat_margin_for_stop);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise);
tier4_autoware_utils::updateParam<bool>(
parameters, "behavior_determination.cruise.yield.enable_yield", enable_yield);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.lat_distance_threshold",
yield_lat_distance_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.max_lat_dist_between_obstacles",
max_lat_dist_between_obstacles);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold",
stopped_obstacle_velocity_threshold);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.cruise.yield.max_obstacles_collision_time",
max_obstacles_collision_time);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.slow_down.max_lat_margin", max_lat_margin_for_slow_down);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.slow_down.lat_hysteresis_margin",
lat_hysteresis_margin_for_slow_down);
tier4_autoware_utils::updateParam<int>(
parameters, "behavior_determination.slow_down.successive_num_to_entry_slow_down_condition",
successive_num_to_entry_slow_down_condition);
tier4_autoware_utils::updateParam<int>(
parameters, "behavior_determination.slow_down.successive_num_to_exit_slow_down_condition",
successive_num_to_exit_slow_down_condition);
tier4_autoware_utils::updateParam<bool>(
parameters, "behavior_determination.consider_current_pose.enable_to_consider_current_pose",
enable_to_consider_current_pose);
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.consider_current_pose.time_to_convergence",
time_to_convergence);
}
ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options)
: Node("obstacle_cruise_planner", node_options),
vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()),
debug_data_ptr_(std::make_shared<DebugData>())
{
using std::placeholders::_1;
// subscriber
traj_sub_ = create_subscription<Trajectory>(
"~/input/trajectory", rclcpp::QoS{1},
std::bind(&ObstacleCruisePlannerNode::onTrajectory, this, _1));
// publisher
trajectory_pub_ = create_publisher<Trajectory>("~/output/trajectory", 1);
vel_limit_pub_ =
create_publisher<VelocityLimit>("~/output/velocity_limit", rclcpp::QoS{1}.transient_local());
clear_vel_limit_pub_ = create_publisher<VelocityLimitClearCommand>(
"~/output/clear_velocity_limit", rclcpp::QoS{1}.transient_local());
// debug publisher
debug_calculation_time_pub_ = create_publisher<Float32Stamped>("~/debug/processing_time_ms", 1);
debug_cruise_wall_marker_pub_ = create_publisher<MarkerArray>("~/debug/cruise/virtual_wall", 1);
debug_stop_wall_marker_pub_ = create_publisher<MarkerArray>("~/virtual_wall", 1);
debug_slow_down_wall_marker_pub_ =
create_publisher<MarkerArray>("~/debug/slow_down/virtual_wall", 1);
debug_marker_pub_ = create_publisher<MarkerArray>("~/debug/marker", 1);
debug_stop_planning_info_pub_ =
create_publisher<Float32MultiArrayStamped>("~/debug/stop_planning_info", 1);
debug_cruise_planning_info_pub_ =
create_publisher<Float32MultiArrayStamped>("~/debug/cruise_planning_info", 1);
debug_slow_down_planning_info_pub_ =
create_publisher<Float32MultiArrayStamped>("~/debug/slow_down_planning_info", 1);
const auto longitudinal_info = LongitudinalInfo(*this);
ego_nearest_param_ = EgoNearestParam(*this);
enable_debug_info_ = declare_parameter<bool>("common.enable_debug_info");
enable_calculation_time_info_ = declare_parameter<bool>("common.enable_calculation_time_info");
enable_slow_down_planning_ = declare_parameter<bool>("common.enable_slow_down_planning");
behavior_determination_param_ = BehaviorDeterminationParam(*this);
{ // planning algorithm
const std::string planning_algorithm_param =
declare_parameter<std::string>("common.planning_algorithm");
planning_algorithm_ = getPlanningAlgorithmType(planning_algorithm_param);
if (planning_algorithm_ == PlanningAlgorithm::OPTIMIZATION_BASE) {
planner_ptr_ = std::make_unique<OptimizationBasedPlanner>(
*this, longitudinal_info, vehicle_info_, ego_nearest_param_, debug_data_ptr_);
} else if (planning_algorithm_ == PlanningAlgorithm::PID_BASE) {
planner_ptr_ = std::make_unique<PIDBasedPlanner>(
*this, longitudinal_info, vehicle_info_, ego_nearest_param_, debug_data_ptr_);
} else {
std::logic_error("Designated algorithm is not supported.");
}
min_behavior_stop_margin_ = declare_parameter<double>("common.min_behavior_stop_margin");
additional_safe_distance_margin_on_curve_ =
declare_parameter<double>("common.stop_on_curve.additional_safe_distance_margin");
enable_approaching_on_curve_ =
declare_parameter<bool>("common.stop_on_curve.enable_approaching");
min_safe_distance_margin_on_curve_ =
declare_parameter<double>("common.stop_on_curve.min_safe_distance_margin");
suppress_sudden_obstacle_stop_ =
declare_parameter<bool>("common.suppress_sudden_obstacle_stop");
planner_ptr_->setParam(
enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_,
enable_approaching_on_curve_, additional_safe_distance_margin_on_curve_,
min_safe_distance_margin_on_curve_, suppress_sudden_obstacle_stop_);
}
{ // stop/cruise/slow down obstacle type
stop_obstacle_types_ = getTargetObjectType(*this, "common.stop_obstacle_type.");
inside_cruise_obstacle_types_ =
getTargetObjectType(*this, "common.cruise_obstacle_type.inside.");
outside_cruise_obstacle_types_ =
getTargetObjectType(*this, "common.cruise_obstacle_type.outside.");
slow_down_obstacle_types_ = getTargetObjectType(*this, "common.slow_down_obstacle_type.");
}
// set parameter callback
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&ObstacleCruisePlannerNode::onParam, this, std::placeholders::_1));
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);
published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
}
ObstacleCruisePlannerNode::PlanningAlgorithm ObstacleCruisePlannerNode::getPlanningAlgorithmType(
const std::string & param) const
{
if (param == "pid_base") {
return PlanningAlgorithm::PID_BASE;
} else if (param == "optimization_base") {
return PlanningAlgorithm::OPTIMIZATION_BASE;
}
return PlanningAlgorithm::INVALID;
}
rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam(
const std::vector<rclcpp::Parameter> & parameters)
{
planner_ptr_->onParam(parameters);
tier4_autoware_utils::updateParam<bool>(
parameters, "common.enable_debug_info", enable_debug_info_);
tier4_autoware_utils::updateParam<bool>(
parameters, "common.enable_calculation_time_info", enable_calculation_time_info_);
tier4_autoware_utils::updateParam<bool>(
parameters, "common.stop_on_curve.enable_approaching", enable_approaching_on_curve_);
tier4_autoware_utils::updateParam<double>(
parameters, "common.stop_on_curve.additional_safe_distance_margin",
additional_safe_distance_margin_on_curve_);
tier4_autoware_utils::updateParam<double>(
parameters, "common.stop_on_curve.min_safe_distance_margin",
min_safe_distance_margin_on_curve_);
planner_ptr_->setParam(
enable_debug_info_, enable_calculation_time_info_, min_behavior_stop_margin_,
enable_approaching_on_curve_, additional_safe_distance_margin_on_curve_,
min_safe_distance_margin_on_curve_, suppress_sudden_obstacle_stop_);
tier4_autoware_utils::updateParam<bool>(
parameters, "common.enable_slow_down_planning", enable_slow_down_planning_);
behavior_determination_param_.onParam(parameters);
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
result.reason = "success";
return result;
}
void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg)
{
const auto ego_odom_ptr = ego_odom_sub_.takeData();
const auto objects_ptr = objects_sub_.takeData();
const auto acc_ptr = acc_sub_.takeData();
if (!ego_odom_ptr || !objects_ptr || !acc_ptr) {
return;
}
const auto & ego_odom = *ego_odom_ptr;
const auto & objects = *objects_ptr;
const auto & acc = *acc_ptr;
const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg);
// check if subscribed variables are ready
if (traj_points.empty()) {
return;
}
stop_watch_.tic(__func__);
*debug_data_ptr_ = DebugData();
const auto is_driving_forward = motion_utils::isDrivingForwardWithTwist(traj_points);
is_driving_forward_ = is_driving_forward ? is_driving_forward.value() : is_driving_forward_;
// 1. Convert predicted objects to obstacles which are
// (1) with a proper label
// (2) in front of ego
// (3) not too far from trajectory
const auto target_obstacles = convertToObstacles(ego_odom, objects, traj_points);
// 2. Determine ego's behavior against each obstacle from stop, cruise and slow down.
const auto & [stop_obstacles, cruise_obstacles, slow_down_obstacles] =
determineEgoBehaviorAgainstObstacles(ego_odom, objects, traj_points, target_obstacles);
// 3. Create data for planning
const auto planner_data = createPlannerData(ego_odom, acc, traj_points);
// 4. Stop planning
const auto stop_traj_points = planner_ptr_->generateStopTrajectory(planner_data, stop_obstacles);
// 5. Cruise planning
std::optional<VelocityLimit> cruise_vel_limit;
const auto cruise_traj_points = planner_ptr_->generateCruiseTrajectory(
planner_data, stop_traj_points, cruise_obstacles, cruise_vel_limit);
publishVelocityLimit(cruise_vel_limit, "cruise");
// 6. Slow down planning
std::optional<VelocityLimit> slow_down_vel_limit;
const auto slow_down_traj_points = planner_ptr_->generateSlowDownTrajectory(
planner_data, cruise_traj_points, slow_down_obstacles, slow_down_vel_limit);
publishVelocityLimit(slow_down_vel_limit, "slow_down");
// 7. Publish trajectory
const auto output_traj = motion_utils::convertToTrajectory(slow_down_traj_points, msg->header);
trajectory_pub_->publish(output_traj);
// 8. Publish debug data
published_time_publisher_->publish_if_subscribed(trajectory_pub_, output_traj.header.stamp);
publishDebugMarker();
publishDebugInfo();
// 9. Publish and print calculation time
const double calculation_time = stop_watch_.toc(__func__);
publishCalculationTime(calculation_time);
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_calculation_time_info_, "%s := %f [ms]", __func__, calculation_time);
}
std::vector<Polygon2d> ObstacleCruisePlannerNode::createOneStepPolygons(
const std::vector<TrajectoryPoint> & traj_points,
const vehicle_info_util::VehicleInfo & vehicle_info,
const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin) const
{
const auto & p = behavior_determination_param_;
const double front_length = vehicle_info.max_longitudinal_offset_m;
const double rear_length = vehicle_info.rear_overhang_m;
const double vehicle_width = vehicle_info.vehicle_width_m;
const size_t nearest_idx =
motion_utils::findNearestSegmentIndex(traj_points, current_ego_pose.position);
const auto nearest_pose = traj_points.at(nearest_idx).pose;
const auto current_ego_pose_error =
tier4_autoware_utils::inverseTransformPose(current_ego_pose, nearest_pose);
const double current_ego_lat_error = current_ego_pose_error.position.y;
const double current_ego_yaw_error = tf2::getYaw(current_ego_pose_error.orientation);
double time_elapsed{0.0};
std::vector<Polygon2d> output_polygons;
Polygon2d tmp_polys{};
for (size_t i = 0; i < traj_points.size(); ++i) {
std::vector<geometry_msgs::msg::Pose> current_poses = {traj_points.at(i).pose};
// estimate the future ego pose with assuming that the pose error against the reference path
// will decrease to zero by the time_to_convergence
if (p.enable_to_consider_current_pose && time_elapsed < p.time_to_convergence) {
const double rem_ratio = (p.time_to_convergence - time_elapsed) / p.time_to_convergence;
geometry_msgs::msg::Pose indexed_pose_err;
indexed_pose_err.set__orientation(
tier4_autoware_utils::createQuaternionFromYaw(current_ego_yaw_error * rem_ratio));
indexed_pose_err.set__position(
tier4_autoware_utils::createPoint(0.0, current_ego_lat_error * rem_ratio, 0.0));
current_poses.push_back(
tier4_autoware_utils::transformPose(indexed_pose_err, traj_points.at(i).pose));
if (traj_points.at(i).longitudinal_velocity_mps != 0.0) {
time_elapsed +=
p.decimate_trajectory_step_length / std::abs(traj_points.at(i).longitudinal_velocity_mps);
} else {
time_elapsed = std::numeric_limits<double>::max();
}
}
Polygon2d idx_poly{};
for (const auto & pose : current_poses) {
if (i == 0 && traj_points.at(i).longitudinal_velocity_mps > 1e-3) {
boost::geometry::append(
idx_poly,
tier4_autoware_utils::toFootprint(pose, front_length, rear_length, vehicle_width)
.outer());
boost::geometry::append(
idx_poly,
tier4_autoware_utils::fromMsg(tier4_autoware_utils::calcOffsetPose(
pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0)
.position)
.to_2d());
boost::geometry::append(
idx_poly, tier4_autoware_utils::fromMsg(
tier4_autoware_utils::calcOffsetPose(
pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0)
.position)
.to_2d());
} else {
boost::geometry::append(
idx_poly, tier4_autoware_utils::toFootprint(
pose, front_length, rear_length, vehicle_width + lat_margin * 2.0)
.outer());
}
}
boost::geometry::append(tmp_polys, idx_poly.outer());
Polygon2d hull_polygon;
boost::geometry::convex_hull(tmp_polys, hull_polygon);
boost::geometry::correct(hull_polygon);
output_polygons.push_back(hull_polygon);
tmp_polys = std::move(idx_poly);
}
return output_polygons;
}
std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
const Odometry & odometry, const PredictedObjects & objects,
const std::vector<TrajectoryPoint> & traj_points) const
{
stop_watch_.tic(__func__);
const auto obj_stamp = rclcpp::Time(objects.header.stamp);
const auto & p = behavior_determination_param_;
std::vector<Obstacle> target_obstacles;
for (const auto & predicted_object : objects.objects) {
const auto & object_id =
tier4_autoware_utils::toHexString(predicted_object.object_id).substr(0, 4);
const auto & current_obstacle_pose =
obstacle_cruise_utils::getCurrentObjectPose(predicted_object, obj_stamp, now(), true);
// 1. Check if the obstacle's label is target
const uint8_t label = predicted_object.classification.front().label;
const bool is_target_obstacle =
isStopObstacle(label) || isCruiseObstacle(label) || isSlowDownObstacle(label);
if (!is_target_obstacle) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_, "Ignore obstacle (%s) since its label is not target.",
object_id.c_str());
continue;
}
// 2. Check if the obstacle is in front of the ego.
const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, odometry.pose.pose);
const auto ego_to_obstacle_distance =
calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position);
if (!ego_to_obstacle_distance) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_, "Ignore obstacle (%s) since it is not front obstacle.",
object_id.c_str());
continue;
}
// 3. Check if rough lateral distance is smaller than the threshold
const double lat_dist_from_obstacle_to_traj =
motion_utils::calcLateralOffset(traj_points, current_obstacle_pose.pose.position);
const double min_lat_dist_to_traj_poly = [&]() {
const double obstacle_max_length = calcObstacleMaxLength(predicted_object.shape);
return std::abs(lat_dist_from_obstacle_to_traj) - vehicle_info_.vehicle_width_m -
obstacle_max_length;
}();
const double max_lat_margin = std::max(
std::max(p.max_lat_margin_for_stop, p.max_lat_margin_for_cruise),
p.max_lat_margin_for_slow_down);
if (max_lat_margin < min_lat_dist_to_traj_poly) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"Ignore obstacle (%s) since it is too far from the trajectory.", object_id.c_str());
continue;
}
const auto target_obstacle = Obstacle(
obj_stamp, predicted_object, current_obstacle_pose.pose, ego_to_obstacle_distance.value(),
lat_dist_from_obstacle_to_traj);
target_obstacles.push_back(target_obstacle);
}
const double calculation_time = stop_watch_.toc(__func__);
RCLCPP_INFO_EXPRESSION(
rclcpp::get_logger("ObstacleCruisePlanner"), enable_debug_info_, " %s := %f [ms]", __func__,
calculation_time);
return target_obstacles;
}
bool ObstacleCruisePlannerNode::isStopObstacle(const uint8_t label) const
{
const auto & types = stop_obstacle_types_;
return std::find(types.begin(), types.end(), label) != types.end();
}
bool ObstacleCruisePlannerNode::isInsideCruiseObstacle(const uint8_t label) const
{
const auto & types = inside_cruise_obstacle_types_;
return std::find(types.begin(), types.end(), label) != types.end();
}
bool ObstacleCruisePlannerNode::isOutsideCruiseObstacle(const uint8_t label) const
{
const auto & types = outside_cruise_obstacle_types_;
return std::find(types.begin(), types.end(), label) != types.end();
}
bool ObstacleCruisePlannerNode::isCruiseObstacle(const uint8_t label) const
{
return isInsideCruiseObstacle(label) || isOutsideCruiseObstacle(label);
}
bool ObstacleCruisePlannerNode::isSlowDownObstacle(const uint8_t label) const
{
const auto & types = slow_down_obstacle_types_;
return std::find(types.begin(), types.end(), label) != types.end();
}
bool ObstacleCruisePlannerNode::isFrontCollideObstacle(
const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle,
const size_t first_collision_idx) const
{
const auto obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle.pose.position);
const double obstacle_to_col_points_distance =
motion_utils::calcSignedArcLength(traj_points, obstacle_idx, first_collision_idx);
const double obstacle_max_length = calcObstacleMaxLength(obstacle.shape);
// If the obstacle is far in front of the collision point, the obstacle is behind the ego.
return obstacle_to_col_points_distance > -obstacle_max_length;
}
std::tuple<std::vector<StopObstacle>, std::vector<CruiseObstacle>, std::vector<SlowDownObstacle>>
ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
const Odometry & odometry, const PredictedObjects & objects,
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Obstacle> & obstacles)
{
stop_watch_.tic(__func__);
// calculated decimated trajectory points and trajectory polygon
const auto decimated_traj_points = decimateTrajectoryPoints(odometry, traj_points);
const auto decimated_traj_polys =
createOneStepPolygons(decimated_traj_points, vehicle_info_, odometry.pose.pose);
debug_data_ptr_->detection_polygons = decimated_traj_polys;
// determine ego's behavior from stop, cruise and slow down
std::vector<StopObstacle> stop_obstacles;
std::vector<CruiseObstacle> cruise_obstacles;
std::vector<SlowDownObstacle> slow_down_obstacles;
slow_down_condition_counter_.resetCurrentUuids();
for (const auto & obstacle : obstacles) {
const auto obstacle_poly = obstacle.toPolygon();
// Calculate distance between trajectory and obstacle first
double precise_lat_dist = std::numeric_limits<double>::max();
for (const auto & traj_poly : decimated_traj_polys) {
const double current_precise_lat_dist = bg::distance(traj_poly, obstacle_poly);
precise_lat_dist = std::min(precise_lat_dist, current_precise_lat_dist);
}
// Filter obstacles for cruise, stop and slow down
const auto cruise_obstacle =
createCruiseObstacle(decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
if (cruise_obstacle) {
cruise_obstacles.push_back(*cruise_obstacle);
continue;
}
const auto stop_obstacle = createStopObstacle(
odometry, decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
if (stop_obstacle) {
stop_obstacles.push_back(*stop_obstacle);
continue;
}
const auto slow_down_obstacle =
createSlowDownObstacle(odometry, decimated_traj_points, obstacle, precise_lat_dist);
if (slow_down_obstacle) {
slow_down_obstacles.push_back(*slow_down_obstacle);
continue;
}
}
const auto & p = behavior_determination_param_;
if (p.enable_yield) {
const auto yield_obstacles = findYieldCruiseObstacles(obstacles, decimated_traj_points);
if (yield_obstacles) {
for (const auto & y : yield_obstacles.value()) {
// Check if there is no member with the same UUID in cruise_obstacles
auto it = std::find_if(
cruise_obstacles.begin(), cruise_obstacles.end(),
[&y](const auto & c) { return y.uuid == c.uuid; });
// If no matching UUID found, insert yield obstacle into cruise_obstacles
if (it == cruise_obstacles.end()) {
cruise_obstacles.push_back(y);
}
}
}
}
slow_down_condition_counter_.removeCounterUnlessUpdated();
// Check target obstacles' consistency
checkConsistency(objects.header.stamp, objects, stop_obstacles);
// update previous obstacles
prev_stop_obstacles_ = stop_obstacles;
prev_cruise_obstacles_ = cruise_obstacles;
prev_slow_down_obstacles_ = slow_down_obstacles;
const double calculation_time = stop_watch_.toc(__func__);
RCLCPP_INFO_EXPRESSION(
rclcpp::get_logger("ObstacleCruisePlanner"), enable_calculation_time_info_, " %s := %f [ms]",
__func__, calculation_time);
return {stop_obstacles, cruise_obstacles, slow_down_obstacles};
}
std::vector<TrajectoryPoint> ObstacleCruisePlannerNode::decimateTrajectoryPoints(
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points) const
{
const auto & p = behavior_determination_param_;
// trim trajectory
const size_t ego_seg_idx = ego_nearest_param_.findSegmentIndex(traj_points, odometry.pose.pose);
const size_t traj_start_point_idx = ego_seg_idx;
const auto trimmed_traj_points =
std::vector<TrajectoryPoint>(traj_points.begin() + traj_start_point_idx, traj_points.end());
// decimate trajectory
const auto decimated_traj_points =
resampleTrajectoryPoints(trimmed_traj_points, p.decimate_trajectory_step_length);
// extend trajectory
const auto extended_traj_points = extendTrajectoryPoints(
decimated_traj_points, planner_ptr_->getSafeDistanceMargin(),
p.decimate_trajectory_step_length);
if (extended_traj_points.size() < 2) {
return traj_points;
}
return extended_traj_points;
}
std::optional<CruiseObstacle> ObstacleCruisePlannerNode::createCruiseObstacle(
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
const Obstacle & obstacle, const double precise_lat_dist)
{
const auto & object_id = obstacle.uuid.substr(0, 4);
const auto & p = behavior_determination_param_;
// NOTE: When driving backward, Stop will be planned instead of cruise.
// When the obstacle is crossing the ego's trajectory, cruise can be ignored.
if (!isCruiseObstacle(obstacle.classification.label) || !is_driving_forward_) {
return std::nullopt;
}
if (p.max_lat_margin_for_cruise < precise_lat_dist) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore obstacle (%s) since it's far from trajectory.", object_id.c_str());
return std::nullopt;
}
if (isObstacleCrossing(traj_points, obstacle)) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore obstacle (%s) since it's crossing the ego's trajectory..",
object_id.c_str());
return std::nullopt;
}
const auto collision_points = [&]() -> std::optional<std::vector<PointWithStamp>> {
constexpr double epsilon = 1e-6;
if (precise_lat_dist < epsilon) {
// obstacle is inside the trajectory
return createCollisionPointsForInsideCruiseObstacle(traj_points, traj_polys, obstacle);
}
// obstacle is outside the trajectory
return createCollisionPointsForOutsideCruiseObstacle(traj_points, traj_polys, obstacle);
}();
if (!collision_points) {
return std::nullopt;
}
const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle);
return CruiseObstacle{obstacle.uuid, obstacle.stamp, obstacle.pose,
tangent_vel, normal_vel, *collision_points};
}
std::optional<CruiseObstacle> ObstacleCruisePlannerNode::createYieldCruiseObstacle(
const Obstacle & obstacle, const std::vector<TrajectoryPoint> & traj_points)
{
if (traj_points.empty()) return std::nullopt;
// check label
const auto & object_id = obstacle.uuid.substr(0, 4);
const auto & p = behavior_determination_param_;
if (!isOutsideCruiseObstacle(obstacle.classification.label)) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since its type is not designated.", object_id.c_str());
return std::nullopt;
}
if (
std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y) <
p.outside_obstacle_min_velocity_threshold) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since the obstacle velocity is low.", object_id.c_str());
return std::nullopt;
}
if (isObstacleCrossing(traj_points, obstacle)) {
RCLCPP_INFO_EXPRESSION(
get_logger(), enable_debug_info_,
"[Cruise] Ignore yield obstacle (%s) since it's crossing the ego's trajectory..",
object_id.c_str());
return std::nullopt;
}
const auto collision_points = [&]() -> std::optional<std::vector<PointWithStamp>> {
const auto obstacle_idx = motion_utils::findNearestIndex(traj_points, obstacle.pose);
if (!obstacle_idx) return std::nullopt;
const auto collision_traj_point = traj_points.at(obstacle_idx.value());
const auto object_time = now() + traj_points.at(obstacle_idx.value()).time_from_start;
PointWithStamp collision_traj_point_with_stamp;
collision_traj_point_with_stamp.stamp = object_time;
collision_traj_point_with_stamp.point.x = collision_traj_point.pose.position.x;
collision_traj_point_with_stamp.point.y = collision_traj_point.pose.position.y;
collision_traj_point_with_stamp.point.z = collision_traj_point.pose.position.z;
std::vector<PointWithStamp> collision_points_vector{collision_traj_point_with_stamp};
return collision_points_vector;
}();
if (!collision_points) return std::nullopt;
const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle);
// check if obstacle is driving on the opposite direction
if (tangent_vel < 0.0) return std::nullopt;
return CruiseObstacle{obstacle.uuid, obstacle.stamp, obstacle.pose,
tangent_vel, normal_vel, collision_points.value()};
}
std::optional<std::vector<CruiseObstacle>> ObstacleCruisePlannerNode::findYieldCruiseObstacles(
const std::vector<Obstacle> & obstacles, const std::vector<TrajectoryPoint> & traj_points)
{
if (obstacles.empty() || traj_points.empty()) return std::nullopt;
const auto & p = behavior_determination_param_;
std::vector<Obstacle> stopped_obstacles;
std::vector<Obstacle> moving_obstacles;
std::for_each(
obstacles.begin(), obstacles.end(),
[&stopped_obstacles, &moving_obstacles, &p](const auto & o) {
const bool is_moving =
std::hypot(o.twist.linear.x, o.twist.linear.y) > p.stopped_obstacle_velocity_threshold;
if (is_moving) {
const bool is_within_lat_dist_threshold =
o.lat_dist_from_obstacle_to_traj < p.yield_lat_distance_threshold;
if (is_within_lat_dist_threshold) moving_obstacles.push_back(o);
return;
}
// lat threshold is larger for stopped obstacles
const bool is_within_lat_dist_threshold =
o.lat_dist_from_obstacle_to_traj <
p.yield_lat_distance_threshold + p.max_lat_dist_between_obstacles;
if (is_within_lat_dist_threshold) stopped_obstacles.push_back(o);
return;
});
if (stopped_obstacles.empty() || moving_obstacles.empty()) return std::nullopt;
std::sort(
stopped_obstacles.begin(), stopped_obstacles.end(), [](const auto & o1, const auto & o2) {
return o1.ego_to_obstacle_distance < o2.ego_to_obstacle_distance;
});
std::sort(moving_obstacles.begin(), moving_obstacles.end(), [](const auto & o1, const auto & o2) {
return o1.ego_to_obstacle_distance < o2.ego_to_obstacle_distance;
});
std::vector<CruiseObstacle> yield_obstacles;
for (const auto & moving_obstacle : moving_obstacles) {
for (const auto & stopped_obstacle : stopped_obstacles) {
const bool is_moving_obs_behind_of_stopped_obs =