@@ -597,7 +597,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
597
597
concatenate (cruise_obstacles, cruise_object_obstacles);
598
598
concatenate (slow_down_obstacles, slow_down_object_obstacles);
599
599
}
600
- if (pointcloud_ptr && !pointcloud_ptr-> data . empty () ) {
600
+ if (pointcloud_ptr) {
601
601
const auto target_obstacles =
602
602
convertToObstacles (ego_odom, *pointcloud_ptr, traj_points, msg->header );
603
603
@@ -822,7 +822,7 @@ std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles(
822
822
transform_stamped = std::nullopt;
823
823
}
824
824
825
- if (transform_stamped) {
825
+ if (!pointcloud. data . empty () && transform_stamped) {
826
826
// 1. transform pointcloud
827
827
PointCloud::Ptr pointcloud_ptr (new PointCloud);
828
828
pcl::fromROSMsg (pointcloud, *pointcloud_ptr);
@@ -1033,9 +1033,9 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstPredictedObjectObstacles(
1033
1033
checkConsistency (objects.header .stamp , objects, stop_obstacles);
1034
1034
1035
1035
// update previous obstacles
1036
- prev_stop_obstacles_ = stop_obstacles;
1037
- prev_cruise_obstacles_ = cruise_obstacles;
1038
- prev_slow_down_obstacles_ = slow_down_obstacles;
1036
+ prev_stop_object_obstacles_ = stop_obstacles;
1037
+ prev_cruise_object_obstacles_ = cruise_obstacles;
1038
+ prev_slow_down_object_obstacles_ = slow_down_obstacles;
1039
1039
1040
1040
const double calculation_time = stop_watch_.toc (__func__);
1041
1041
RCLCPP_INFO_EXPRESSION (
@@ -1052,6 +1052,8 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstPointCloudObstacles(
1052
1052
{
1053
1053
stop_watch_.tic (__func__);
1054
1054
1055
+ const auto & p = behavior_determination_param_;
1056
+
1055
1057
// calculated decimated trajectory points and trajectory polygon
1056
1058
const auto decimated_traj_points = decimateTrajectoryPoints (odometry, traj_points);
1057
1059
const auto decimated_traj_polys =
@@ -1078,6 +1080,32 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstPointCloudObstacles(
1078
1080
}
1079
1081
}
1080
1082
1083
+ std::vector<StopObstacle> past_stop_obstacles;
1084
+ for (auto itr = stop_pc_obstacle_history_.begin (); itr != stop_pc_obstacle_history_.end ();) {
1085
+ const double elapsed_time = (rclcpp::Time (odometry.header .stamp ) - itr->stamp ).seconds ();
1086
+ if (elapsed_time >= p.stop_obstacle_hold_time_threshold ) {
1087
+ itr = stop_pc_obstacle_history_.erase (itr);
1088
+ continue ;
1089
+ }
1090
+
1091
+ const auto lat_dist_from_obstacle_to_traj =
1092
+ autoware::motion_utils::calcLateralOffset (traj_points, itr->collision_point );
1093
+ const auto min_lat_dist_to_traj_poly =
1094
+ std::abs (lat_dist_from_obstacle_to_traj) - vehicle_info_.vehicle_width_m ;
1095
+
1096
+ if (min_lat_dist_to_traj_poly < p.max_lat_margin_for_stop_against_unknown ) {
1097
+ auto stop_obstacle = *itr;
1098
+ stop_obstacle.dist_to_collide_on_decimated_traj = autoware::motion_utils::calcSignedArcLength (
1099
+ decimated_traj_points, 0 , stop_obstacle.collision_point );
1100
+ past_stop_obstacles.push_back (stop_obstacle);
1101
+ }
1102
+
1103
+ ++itr;
1104
+ }
1105
+
1106
+ concatenate (stop_pc_obstacle_history_, stop_obstacles);
1107
+ concatenate (stop_obstacles, past_stop_obstacles);
1108
+
1081
1109
const double calculation_time = stop_watch_.toc (__func__);
1082
1110
RCLCPP_INFO_EXPRESSION (
1083
1111
rclcpp::get_logger (" ObstacleCruisePlanner" ), enable_calculation_time_info_, " %s := %f [ms]" ,
@@ -1308,7 +1336,7 @@ ObstacleCruisePlannerNode::createCollisionPointsForInsideCruiseObstacle(
1308
1336
// const bool is_prev_obstacle_stop = getObstacleFromUuid(prev_stop_obstacles_,
1309
1337
// obstacle.uuid).has_value();
1310
1338
const bool is_prev_obstacle_cruise =
1311
- getObstacleFromUuid (prev_cruise_obstacles_ , obstacle.uuid ).has_value ();
1339
+ getObstacleFromUuid (prev_cruise_object_obstacles_ , obstacle.uuid ).has_value ();
1312
1340
1313
1341
if (is_prev_obstacle_cruise) {
1314
1342
if (obstacle_tangent_vel < p.obstacle_velocity_threshold_from_cruise_to_stop ) {
@@ -1555,7 +1583,7 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
1555
1583
slow_down_condition_counter_.addCurrentUuid (obstacle.uuid );
1556
1584
1557
1585
const bool is_prev_obstacle_slow_down =
1558
- getObstacleFromUuid (prev_slow_down_obstacles_ , obstacle.uuid ).has_value ();
1586
+ getObstacleFromUuid (prev_slow_down_object_obstacles_ , obstacle.uuid ).has_value ();
1559
1587
1560
1588
if (!enable_slow_down_planning_ || !isSlowDownObstacle (obstacle.classification .label )) {
1561
1589
return std::nullopt;
@@ -1694,7 +1722,7 @@ void ObstacleCruisePlannerNode::checkConsistency(
1694
1722
const rclcpp::Time & current_time, const PredictedObjects & predicted_objects,
1695
1723
std::vector<StopObstacle> & stop_obstacles)
1696
1724
{
1697
- for (const auto & prev_closest_stop_obstacle : prev_closest_stop_obstacles_ ) {
1725
+ for (const auto & prev_closest_stop_obstacle : prev_closest_stop_object_obstacles_ ) {
1698
1726
const auto predicted_object_itr = std::find_if (
1699
1727
predicted_objects.objects .begin (), predicted_objects.objects .end (),
1700
1728
[&prev_closest_stop_obstacle](const PredictedObject & po) {
@@ -1724,7 +1752,8 @@ void ObstacleCruisePlannerNode::checkConsistency(
1724
1752
}
1725
1753
}
1726
1754
1727
- prev_closest_stop_obstacles_ = obstacle_cruise_utils::getClosestStopObstacles (stop_obstacles);
1755
+ prev_closest_stop_object_obstacles_ =
1756
+ obstacle_cruise_utils::getClosestStopObstacles (stop_obstacles);
1728
1757
}
1729
1758
1730
1759
bool ObstacleCruisePlannerNode::isObstacleCrossing (
0 commit comments