Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_lidar_centerpoint): added a check to notify if we are dropping pillars (#9488) #1676

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 15 additions & 2 deletions perception/lidar_centerpoint/lib/centerpoint_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,15 +115,28 @@ bool CenterPointTRT::detect(
cudaMemsetAsync(spatial_features_d_.get(), 0, spatial_features_size_ * sizeof(float), stream_));

if (!preprocess(input_pointcloud_msg, tf_buffer)) {
RCLCPP_WARN_STREAM(
rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect.");
RCLCPP_WARN(rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect.");
return false;
}

inference();

postProcess(det_boxes3d);

// Check the actual number of pillars after inference to avoid unnecessary synchronization.
unsigned int num_pillars = 0;
CHECK_CUDA_ERROR(
cudaMemcpy(&num_pillars, num_voxels_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost));

if (num_pillars >= config_.max_voxel_size_) {
rclcpp::Clock clock{RCL_ROS_TIME};
RCLCPP_WARN_THROTTLE(
rclcpp::get_logger("lidar_centerpoint"), clock, 1000,
"The actual number of pillars (%u) exceeds its maximum value (%zu). "
"Please considering increasing it since it may limit the detection performance.",
num_pillars, config_.max_voxel_size_);
}

return true;
}

Expand Down
Loading