Skip to content

Commit 5a3e917

Browse files
Merge pull request #1901 from tier4/hotfix/beta/v0.42_obstacle_stop
fix(obstacle_stop): accounting for vehicle bumper length when handling point-cloud stop points (autowarefoundation#10250)
2 parents 4b0d1b9 + c79ab36 commit 5a3e917

File tree

2 files changed

+14
-11
lines changed

2 files changed

+14
-11
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_stop_module/src/obstacle_stop_module.cpp

+12-10
Original file line numberDiff line numberDiff line change
@@ -229,7 +229,7 @@ VelocityPlanningResult ObstacleStopModule::plan(
229229
// 4. filter obstacles of point cloud
230230
auto stop_obstacles_for_point_cloud = filter_stop_obstacle_for_point_cloud(
231231
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,
233233
planner_data->trajectory_polygon_collision_check,
234234
planner_data->find_index(raw_trajectory_points, planner_data->current_odometry.pose.pose));
235235

@@ -268,10 +268,9 @@ std::vector<geometry_msgs::msg::Point> ObstacleStopModule::convert_point_cloud_t
268268

269269
std::vector<geometry_msgs::msg::Point> stop_collision_points;
270270

271-
// 1. transform pointcloud
272271
pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud_ptr =
273272
std::make_shared<pcl::PointCloud<pcl::PointXYZ>>(pointcloud.pointcloud);
274-
// 2. downsample & cluster pointcloud
273+
// 1. downsample & cluster pointcloud
275274
PointCloud::Ptr filtered_points_ptr(new PointCloud);
276275
pcl::VoxelGrid<pcl::PointXYZ> filter;
277276
filter.setInputCloud(pointcloud_ptr);
@@ -292,7 +291,7 @@ std::vector<geometry_msgs::msg::Point> ObstacleStopModule::convert_point_cloud_t
292291
ec.setInputCloud(filtered_points_ptr);
293292
ec.extract(clusters);
294293

295-
// 3. convert clusters to obstacles
294+
// 2. convert clusters to obstacles
296295
for (const auto & cluster_indices : clusters) {
297296
double ego_to_stop_collision_distance = std::numeric_limits<double>::max();
298297
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
335334

336335
std::optional<StopObstacle> ObstacleStopModule::create_stop_obstacle_for_point_cloud(
337336
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
339338
{
340339
if (!use_pointcloud_) {
341340
return std::nullopt;
342341
}
343342

344343
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;
346345

347346
const unique_identifier_msgs::msg::UUID obj_uuid;
348347
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
444443
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
445444
const std::vector<TrajectoryPoint> & decimated_traj_points,
446445
const PlannerData::Pointcloud & point_cloud, const VehicleInfo & vehicle_info,
446+
const double dist_to_bumper,
447447
const TrajectoryPolygonCollisionCheck & trajectory_polygon_collision_check, size_t ego_idx)
448448
{
449449
autoware_utils::ScopedTimeTrack st(__func__, *time_keeper_);
@@ -466,8 +466,8 @@ std::vector<StopObstacle> ObstacleStopModule::filter_stop_obstacle_for_point_clo
466466
std::vector<StopObstacle> stop_obstacles;
467467
for (const auto & stop_point : stop_points) {
468468
// 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);
471471
if (stop_obstacle) {
472472
stop_obstacles.push_back(*stop_obstacle);
473473
continue;
@@ -493,8 +493,10 @@ std::vector<StopObstacle> ObstacleStopModule::filter_stop_obstacle_for_point_clo
493493

494494
if (min_lat_dist_to_traj_poly < obstacle_filtering_param_.max_lat_margin_against_unknown) {
495495
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;
498500
past_stop_obstacles.push_back(stop_obstacle);
499501
}
500502

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_stop_module/src/obstacle_stop_module.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,7 @@ class ObstacleStopModule : public PluginModuleInterface
132132
const Odometry & odometry, const std::vector<TrajectoryPoint> & traj_points,
133133
const std::vector<TrajectoryPoint> & decimated_traj_points,
134134
const PlannerData::Pointcloud & point_cloud, const VehicleInfo & vehicle_info,
135+
const double dist_to_bumper,
135136
const TrajectoryPolygonCollisionCheck & trajectory_polygon_collision_check, size_t ego_idx);
136137

137138
std::optional<geometry_msgs::msg::Point> plan_stop(
@@ -188,7 +189,7 @@ class ObstacleStopModule : public PluginModuleInterface
188189

189190
std::optional<StopObstacle> create_stop_obstacle_for_point_cloud(
190191
const std::vector<TrajectoryPoint> & traj_points, const rclcpp::Time & stamp,
191-
const geometry_msgs::msg::Point & stop_point) const;
192+
const geometry_msgs::msg::Point & stop_point, const double dist_to_bumper) const;
192193

193194
std::optional<std::pair<geometry_msgs::msg::Point, double>>
194195
create_collision_point_for_outside_stop_obstacle(

0 commit comments

Comments
 (0)