@@ -229,7 +229,7 @@ VelocityPlanningResult ObstacleStopModule::plan(
229
229
// 4. filter obstacles of point cloud
230
230
auto stop_obstacles_for_point_cloud = filter_stop_obstacle_for_point_cloud (
231
231
planner_data->current_odometry , raw_trajectory_points, decimated_traj_points,
232
- planner_data->no_ground_pointcloud , planner_data->vehicle_info_ ,
232
+ planner_data->no_ground_pointcloud , planner_data->vehicle_info_ , dist_to_bumper,
233
233
planner_data->trajectory_polygon_collision_check ,
234
234
planner_data->find_index (raw_trajectory_points, planner_data->current_odometry .pose .pose ));
235
235
@@ -268,10 +268,9 @@ std::vector<geometry_msgs::msg::Point> ObstacleStopModule::convert_point_cloud_t
268
268
269
269
std::vector<geometry_msgs::msg::Point > stop_collision_points;
270
270
271
- // 1. transform pointcloud
272
271
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud_ptr =
273
272
std::make_shared<pcl::PointCloud<pcl::PointXYZ>>(pointcloud.pointcloud );
274
- // 2 . downsample & cluster pointcloud
273
+ // 1 . downsample & cluster pointcloud
275
274
PointCloud::Ptr filtered_points_ptr (new PointCloud);
276
275
pcl::VoxelGrid<pcl::PointXYZ> filter;
277
276
filter.setInputCloud (pointcloud_ptr);
@@ -292,7 +291,7 @@ std::vector<geometry_msgs::msg::Point> ObstacleStopModule::convert_point_cloud_t
292
291
ec.setInputCloud (filtered_points_ptr);
293
292
ec.extract (clusters);
294
293
295
- // 3 . convert clusters to obstacles
294
+ // 2 . convert clusters to obstacles
296
295
for (const auto & cluster_indices : clusters) {
297
296
double ego_to_stop_collision_distance = std::numeric_limits<double >::max ();
298
297
double lat_dist_from_obstacle_to_traj = std::numeric_limits<double >::max ();
@@ -335,14 +334,14 @@ std::vector<geometry_msgs::msg::Point> ObstacleStopModule::convert_point_cloud_t
335
334
336
335
std::optional<StopObstacle> ObstacleStopModule::create_stop_obstacle_for_point_cloud (
337
336
const std::vector<TrajectoryPoint> & traj_points, const rclcpp::Time & stamp,
338
- const geometry_msgs::msg::Point & stop_point) const
337
+ const geometry_msgs::msg::Point & stop_point, const double dist_to_bumper ) const
339
338
{
340
339
if (!use_pointcloud_) {
341
340
return std::nullopt;
342
341
}
343
342
344
343
const auto dist_to_collide_on_traj =
345
- autoware::motion_utils::calcSignedArcLength (traj_points, 0 , stop_point);
344
+ autoware::motion_utils::calcSignedArcLength (traj_points, 0 , stop_point) - dist_to_bumper ;
346
345
347
346
const unique_identifier_msgs::msg::UUID obj_uuid;
348
347
const auto & obj_uuid_str = autoware_utils::to_hex_string (obj_uuid);
@@ -444,6 +443,7 @@ std::vector<StopObstacle> ObstacleStopModule::filter_stop_obstacle_for_point_clo
444
443
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
445
444
const std::vector<TrajectoryPoint> & decimated_traj_points,
446
445
const PlannerData::Pointcloud & point_cloud, const VehicleInfo & vehicle_info,
446
+ const double dist_to_bumper,
447
447
const TrajectoryPolygonCollisionCheck & trajectory_polygon_collision_check, size_t ego_idx)
448
448
{
449
449
autoware_utils::ScopedTimeTrack st (__func__, *time_keeper_);
@@ -466,8 +466,8 @@ std::vector<StopObstacle> ObstacleStopModule::filter_stop_obstacle_for_point_clo
466
466
std::vector<StopObstacle> stop_obstacles;
467
467
for (const auto & stop_point : stop_points) {
468
468
// Filter obstacles for stop
469
- const auto stop_obstacle =
470
- create_stop_obstacle_for_point_cloud ( decimated_traj_points, stop_obstacle_stamp, stop_point);
469
+ const auto stop_obstacle = create_stop_obstacle_for_point_cloud (
470
+ decimated_traj_points, stop_obstacle_stamp, stop_point, dist_to_bumper );
471
471
if (stop_obstacle) {
472
472
stop_obstacles.push_back (*stop_obstacle);
473
473
continue ;
@@ -493,8 +493,10 @@ std::vector<StopObstacle> ObstacleStopModule::filter_stop_obstacle_for_point_clo
493
493
494
494
if (min_lat_dist_to_traj_poly < obstacle_filtering_param_.max_lat_margin_against_unknown ) {
495
495
auto stop_obstacle = *itr;
496
- stop_obstacle.dist_to_collide_on_decimated_traj = autoware::motion_utils::calcSignedArcLength (
497
- decimated_traj_points, 0 , stop_obstacle.collision_point );
496
+ stop_obstacle.dist_to_collide_on_decimated_traj =
497
+ autoware::motion_utils::calcSignedArcLength (
498
+ decimated_traj_points, 0 , stop_obstacle.collision_point ) -
499
+ dist_to_bumper;
498
500
past_stop_obstacles.push_back (stop_obstacle);
499
501
}
500
502
0 commit comments