Skip to content

the "crop_box_filter" can cause error in the subsequent module. #705

Closed
@plane-li

Description

Checklist

  • I've read the contribution guidelines.
  • I've searched other issues and no duplicate issues were found.
  • I'm convinced that this is not my fault but a bug.

Description

When run the autoware_launch,It always throw the error Invalid input! and the warning: Invalid PointCloud (data = 513168, width = 167,height = 64,step = 48)
I think it was caused by the crop_box_filter_nodelet.cpp.
And the subsequent module(common_ground_filter and random_downsample_filter ) can not publish any topic.

Expected behavior

there should not be any error about the pointcloud_preprocessor when run the autoware.

Actual behavior

common_ground_filter throws out error:"Invalid input" and the warning: "Invalid PointCloud"
20220415-pointcloud_preprocessor

Steps to reproduce

ros2 launch autoware_launch autoware.launch.xml map_path:=/home/adlink/workspace/autoware.universe/map vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit

Versions

  • OS:ubuntu20.04
  • ROS: ros-galactic
  • Autoware: autoware:main

Possible causes

The errors are printed in
https://github.com/autowarefoundation/autoware.universe/blob/main/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/filter.hpp#L224-L235:
inline bool isValid(
const PointCloud2ConstPtr & cloud, const std::string & /topic_name/ = "input")
{
if (cloud->width * cloud->height * cloud->point_step != cloud->data.size()) {
RCLCPP_WARN(
this->get_logger(),
"Invalid PointCloud (data = %zu, width = %d, height = %d, step = %d) with stamp %f, "
"and frame %s received!",
cloud->data.size(), cloud->width, cloud->height, cloud->point_step,
rclcpp::Time(cloud->header.stamp).seconds(), cloud->header.frame_id.c_str());
return false;
}

The problem was cause by the (cloud->width * cloud->height * cloud->point_step != cloud->data.size()).And in the
sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp
https://github.com/autowarefoundation/autoware.universe/blob/main/sensing/pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_nodelet.cpp#L124-L130
output.data.resize(j);
output.header.frame_id = input->header.frame_id;
output.height = input->height;
output.fields = input->fields;
output.is_bigendian = input->is_bigendian;
output.point_step = input->point_step;
output.is_dense = input->is_dense;

and I think in output.data.size() is less the the input pointcloud size before crop_box_filter.And the out.width,height and step are equal to the input. So It may cause the problem.

At present,I solve it by using the pcl as below:

pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, outpu

Additional context

No response

Metadata

Assignees

Labels

component:perceptionAdvanced sensor data processing and environment understanding. (auto-assigned)component:sensingData acquisition from sensors, drivers, preprocessing. (auto-assigned)type:bugSoftware flaws or errors.

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions