Skip to content

Commit

Permalink
feat(autoware_lidar_centerpoint): added a check to notify if we are d…
Browse files Browse the repository at this point in the history
…ropping pillars (autowarefoundation#9488)

* feat: added a check to notify if we are dropping pillars

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: updated text

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* chore: throttled the message

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

---------

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>
  • Loading branch information
knzo25 authored and technolojin committed Dec 5, 2024
1 parent db51b36 commit d7882f3
Showing 1 changed file with 15 additions and 2 deletions.
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

0 comments on commit d7882f3

Please sign in to comment.