@@ -484,12 +484,17 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam(
484
484
485
485
void ObstacleCruisePlannerNode::onTrajectory (const Trajectory::ConstSharedPtr msg)
486
486
{
487
- if (
488
- !ego_odom_sub_.updateLatestData () || !objects_sub_.updateLatestData () ||
489
- !acc_sub_.updateLatestData ()) {
487
+ const auto ego_odom_ptr = ego_odom_sub_.takeData ();
488
+ const auto objects_ptr = objects_sub_.takeData ();
489
+ const auto acc_ptr = acc_sub_.takeData ();
490
+ if (!ego_odom_ptr || !objects_ptr || !acc_ptr) {
490
491
return ;
491
492
}
492
493
494
+ const auto & ego_odom = *ego_odom_ptr;
495
+ const auto & objects = *objects_ptr;
496
+ const auto & acc = *acc_ptr;
497
+
493
498
const auto traj_points = motion_utils::convertToTrajectoryPointArray (*msg);
494
499
// check if subscribed variables are ready
495
500
if (traj_points.empty ()) {
@@ -506,14 +511,14 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
506
511
// (1) with a proper label
507
512
// (2) in front of ego
508
513
// (3) not too far from trajectory
509
- const auto target_obstacles = convertToObstacles (traj_points);
514
+ const auto target_obstacles = convertToObstacles (ego_odom, objects, traj_points);
510
515
511
516
// 2. Determine ego's behavior against each obstacle from stop, cruise and slow down.
512
517
const auto & [stop_obstacles, cruise_obstacles, slow_down_obstacles] =
513
- determineEgoBehaviorAgainstObstacles (traj_points, target_obstacles);
518
+ determineEgoBehaviorAgainstObstacles (ego_odom, objects, traj_points, target_obstacles);
514
519
515
520
// 3. Create data for planning
516
- const auto planner_data = createPlannerData (traj_points);
521
+ const auto planner_data = createPlannerData (ego_odom, acc, traj_points);
517
522
518
523
// 4. Stop planning
519
524
const auto stop_traj_points = planner_ptr_->generateStopTrajectory (planner_data, stop_obstacles);
@@ -629,15 +634,16 @@ std::vector<Polygon2d> ObstacleCruisePlannerNode::createOneStepPolygons(
629
634
}
630
635
631
636
std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles (
637
+ const Odometry & odometry, const PredictedObjects & objects,
632
638
const std::vector<TrajectoryPoint> & traj_points) const
633
639
{
634
640
stop_watch_.tic (__func__);
635
641
636
- const auto obj_stamp = rclcpp::Time (objects_sub_. getData () .header .stamp );
642
+ const auto obj_stamp = rclcpp::Time (objects .header .stamp );
637
643
const auto & p = behavior_determination_param_;
638
644
639
645
std::vector<Obstacle> target_obstacles;
640
- for (const auto & predicted_object : objects_sub_. getData () .objects ) {
646
+ for (const auto & predicted_object : objects .objects ) {
641
647
const auto & object_id =
642
648
tier4_autoware_utils::toHexString (predicted_object.object_id ).substr (0 , 4 );
643
649
const auto & current_obstacle_pose =
@@ -655,8 +661,7 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
655
661
}
656
662
657
663
// 2. Check if the obstacle is in front of the ego.
658
- const size_t ego_idx =
659
- ego_nearest_param_.findIndex (traj_points, ego_odom_sub_.getData ().pose .pose );
664
+ const size_t ego_idx = ego_nearest_param_.findIndex (traj_points, odometry.pose .pose );
660
665
const auto ego_to_obstacle_distance =
661
666
calcDistanceToFrontVehicle (traj_points, ego_idx, current_obstacle_pose.pose .position );
662
667
if (!ego_to_obstacle_distance) {
@@ -745,14 +750,15 @@ bool ObstacleCruisePlannerNode::isFrontCollideObstacle(
745
750
746
751
std::tuple<std::vector<StopObstacle>, std::vector<CruiseObstacle>, std::vector<SlowDownObstacle>>
747
752
ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles (
753
+ const Odometry & odometry, const PredictedObjects & objects,
748
754
const std::vector<TrajectoryPoint> & traj_points, const std::vector<Obstacle> & obstacles)
749
755
{
750
756
stop_watch_.tic (__func__);
751
757
752
758
// calculated decimated trajectory points and trajectory polygon
753
- const auto decimated_traj_points = decimateTrajectoryPoints (traj_points);
759
+ const auto decimated_traj_points = decimateTrajectoryPoints (odometry, traj_points);
754
760
const auto decimated_traj_polys =
755
- createOneStepPolygons (decimated_traj_points, vehicle_info_, ego_odom_sub_. getData () .pose .pose );
761
+ createOneStepPolygons (decimated_traj_points, vehicle_info_, odometry .pose .pose );
756
762
debug_data_ptr_->detection_polygons = decimated_traj_polys;
757
763
758
764
// determine ego's behavior from stop, cruise and slow down
@@ -777,14 +783,14 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
777
783
cruise_obstacles.push_back (*cruise_obstacle);
778
784
continue ;
779
785
}
780
- const auto stop_obstacle =
781
- createStopObstacle ( decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
786
+ const auto stop_obstacle = createStopObstacle (
787
+ odometry, decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist);
782
788
if (stop_obstacle) {
783
789
stop_obstacles.push_back (*stop_obstacle);
784
790
continue ;
785
791
}
786
792
const auto slow_down_obstacle =
787
- createSlowDownObstacle (decimated_traj_points, obstacle, precise_lat_dist);
793
+ createSlowDownObstacle (odometry, decimated_traj_points, obstacle, precise_lat_dist);
788
794
if (slow_down_obstacle) {
789
795
slow_down_obstacles.push_back (*slow_down_obstacle);
790
796
continue ;
@@ -810,7 +816,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
810
816
slow_down_condition_counter_.removeCounterUnlessUpdated ();
811
817
812
818
// Check target obstacles' consistency
813
- checkConsistency (objects_sub_. getData (). header .stamp , objects_sub_. getData () , stop_obstacles);
819
+ checkConsistency (objects. header .stamp , objects , stop_obstacles);
814
820
815
821
// update previous obstacles
816
822
prev_stop_obstacles_ = stop_obstacles;
@@ -826,13 +832,12 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles(
826
832
}
827
833
828
834
std::vector<TrajectoryPoint> ObstacleCruisePlannerNode::decimateTrajectoryPoints (
829
- const std::vector<TrajectoryPoint> & traj_points) const
835
+ const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points) const
830
836
{
831
837
const auto & p = behavior_determination_param_;
832
838
833
839
// trim trajectory
834
- const size_t ego_seg_idx =
835
- ego_nearest_param_.findSegmentIndex (traj_points, ego_odom_sub_.getData ().pose .pose );
840
+ const size_t ego_seg_idx = ego_nearest_param_.findSegmentIndex (traj_points, odometry.pose .pose );
836
841
const size_t traj_start_point_idx = ego_seg_idx;
837
842
const auto trimmed_traj_points =
838
843
std::vector<TrajectoryPoint>(traj_points.begin () + traj_start_point_idx, traj_points.end ());
@@ -1151,8 +1156,9 @@ ObstacleCruisePlannerNode::createCollisionPointsForOutsideCruiseObstacle(
1151
1156
}
1152
1157
1153
1158
std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle (
1154
- const std::vector<TrajectoryPoint> & traj_points, const std::vector<Polygon2d> & traj_polys,
1155
- const Obstacle & obstacle, const double precise_lat_dist) const
1159
+ const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
1160
+ const std::vector<Polygon2d> & traj_polys, const Obstacle & obstacle,
1161
+ const double precise_lat_dist) const
1156
1162
{
1157
1163
const auto & p = behavior_determination_param_;
1158
1164
const auto & object_id = obstacle.uuid .substr (0 , 4 );
@@ -1203,7 +1209,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1203
1209
}
1204
1210
1205
1211
const double collision_time_margin =
1206
- calcCollisionTimeMargin (collision_points, traj_points, is_driving_forward_);
1212
+ calcCollisionTimeMargin (odometry, collision_points, traj_points, is_driving_forward_);
1207
1213
if (p.collision_time_margin < collision_time_margin) {
1208
1214
RCLCPP_INFO_EXPRESSION (
1209
1215
get_logger (), enable_debug_info_,
@@ -1216,7 +1222,7 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1216
1222
1217
1223
// calculate collision points with trajectory with lateral stop margin
1218
1224
const auto traj_polys_with_lat_margin = createOneStepPolygons (
1219
- traj_points, vehicle_info_, ego_odom_sub_. getData () .pose .pose , p.max_lat_margin_for_stop );
1225
+ traj_points, vehicle_info_, odometry .pose .pose , p.max_lat_margin_for_stop );
1220
1226
1221
1227
const auto collision_point = polygon_utils::getCollisionPoint (
1222
1228
traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_);
@@ -1231,8 +1237,8 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
1231
1237
}
1232
1238
1233
1239
std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacle (
1234
- const std::vector<TrajectoryPoint> & traj_points, const Obstacle & obstacle ,
1235
- const double precise_lat_dist)
1240
+ const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
1241
+ const Obstacle & obstacle, const double precise_lat_dist)
1236
1242
{
1237
1243
const auto & object_id = obstacle.uuid .substr (0 , 4 );
1238
1244
const auto & p = behavior_determination_param_;
@@ -1286,7 +1292,7 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
1286
1292
// calculate collision points with trajectory with lateral stop margin
1287
1293
// NOTE: For additional margin, hysteresis is not divided by two.
1288
1294
const auto traj_polys_with_lat_margin = createOneStepPolygons (
1289
- traj_points, vehicle_info_, ego_odom_sub_. getData () .pose .pose ,
1295
+ traj_points, vehicle_info_, odometry .pose .pose ,
1290
1296
p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down );
1291
1297
1292
1298
std::vector<Polygon2d> front_collision_polygons;
@@ -1446,11 +1452,11 @@ bool ObstacleCruisePlannerNode::isObstacleCrossing(
1446
1452
}
1447
1453
1448
1454
double ObstacleCruisePlannerNode::calcCollisionTimeMargin (
1449
- const std::vector<PointWithStamp> & collision_points,
1455
+ const Odometry & odometry, const std::vector<PointWithStamp> & collision_points,
1450
1456
const std::vector<TrajectoryPoint> & traj_points, const bool is_driving_forward) const
1451
1457
{
1452
- const auto & ego_pose = ego_odom_sub_. getData () .pose .pose ;
1453
- const double ego_vel = ego_odom_sub_. getData () .twist .twist .linear .x ;
1458
+ const auto & ego_pose = odometry .pose .pose ;
1459
+ const double ego_vel = odometry .twist .twist .linear .x ;
1454
1460
1455
1461
const double time_to_reach_collision_point = [&]() {
1456
1462
const double abs_ego_offset = is_driving_forward
@@ -1477,14 +1483,15 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin(
1477
1483
}
1478
1484
1479
1485
PlannerData ObstacleCruisePlannerNode::createPlannerData (
1486
+ const Odometry & odometry, const AccelWithCovarianceStamped & acc,
1480
1487
const std::vector<TrajectoryPoint> & traj_points) const
1481
1488
{
1482
1489
PlannerData planner_data;
1483
1490
planner_data.current_time = now ();
1484
1491
planner_data.traj_points = traj_points;
1485
- planner_data.ego_pose = ego_odom_sub_. getData () .pose .pose ;
1486
- planner_data.ego_vel = ego_odom_sub_. getData () .twist .twist .linear .x ;
1487
- planner_data.ego_acc = acc_sub_. getData () .accel .accel .linear .x ;
1492
+ planner_data.ego_pose = odometry .pose .pose ;
1493
+ planner_data.ego_vel = odometry .twist .twist .linear .x ;
1494
+ planner_data.ego_acc = acc .accel .accel .linear .x ;
1488
1495
planner_data.is_driving_forward = is_driving_forward_;
1489
1496
return planner_data;
1490
1497
}
0 commit comments