Skip to content

Commit

Permalink
fix(autoware_pointcloud_preprocessor): fix 0 division
Browse files Browse the repository at this point in the history
Signed-off-by: Shumpei Wakabayashi <shumpei.wakabayashi@tier4.jp>
  • Loading branch information
shmpwk committed Feb 13, 2025
1 parent f6dd2bd commit b0a2364
Showing 1 changed file with 7 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,13 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter(
const float inverse_voxel_size_x = 1.0 / voxel_size_x_;
const float inverse_voxel_size_y = 1.0 / voxel_size_y_;
const float inverse_voxel_size_z = 1.0 / voxel_size_z_;
const float inverse_voxel_size_x = (voxel_size_x_ > 0) ? (1.0f / voxel_size_x_) : 0.0f;
const float inverse_voxel_size_y = (voxel_size_y_ > 0) ? (1.0f / voxel_size_y_) : 0.0f;
const float inverse_voxel_size_z = (voxel_size_z_ > 0) ? (1.0f / voxel_size_z_) : 0.0f;

if (voxel_size_x_ <= 0 || voxel_size_y_ <= 0 || voxel_size_z_ <= 0) {
RCLCPP_DEBUG(get_logger(), "Some voxel sizes are 0. Those axes will not be used for downsampling.");
}

const int x_offset = input->fields[pcl::getFieldIndex(*input, "x")].offset;
const int y_offset = input->fields[pcl::getFieldIndex(*input, "y")].offset;
Expand Down

0 comments on commit b0a2364

Please sign in to comment.