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

Bug in CropBox regarding keep organized? #3471

Closed
mvieth opened this issue Nov 16, 2019 · 11 comments
Closed

Bug in CropBox regarding keep organized? #3471

mvieth opened this issue Nov 16, 2019 · 11 comments

Comments

@mvieth
Copy link
Member

mvieth commented Nov 16, 2019

The CropBox filter (possibly other filters too) on pcl::PCLPointCloud2 seems to not keep the cloud organized, even if requested with setKeepOrganized(true).

Your Environment

  • Operating System and version: Ubuntu 19.04 disco
  • Compiler: GCC 8.3.0
  • PCL Version: tested with 1.9.1 and 1.9.1.99 (current trunk)

Context

First noticed in pcl ros, see ros-perception/perception_pcl#216

Expected Behavior

The height and width of the output cloud should be the same as of the organized input cloud, meaning it is still organized.

Current Behavior

The height of the output cloud is 1, meaning it is not organized any more. The code below has this output:

PointCloud before filtering: 307200 data points (x y z rgba).
sor.getKeepOrganized()=true
cloud->height=480 cloud->width=640     cloud_filtered->height=1 cloud_filtered->width=173035
PointCloud after filtering: 173035 data points (x y z rgba).

Code to Reproduce

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/filters/crop_box.h>

// Adapted from http://www.pointclouds.org/documentation/tutorials/voxel_grid.php#voxelgrid
int
main (int argc, char** argv)
{
  pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2 ());
  pcl::PCLPointCloud2::Ptr cloud_filtered (new pcl::PCLPointCloud2 ());

  // Fill in the cloud data
  pcl::PCDReader reader;
  // Replace the path below with the path where you saved your file
  reader.read ("milk_cartoon_all_small_clorox.pcd", *cloud); // Remember to download the file first!

  std::cerr << "PointCloud before filtering: " << cloud->width * cloud->height 
       << " data points (" << pcl::getFieldsList (*cloud) << ")." << std::endl;

  // Create the filtering object
  pcl::CropBox<pcl::PCLPointCloud2> sor;
  sor.setInputCloud (cloud);
  sor.setKeepOrganized(true);
  sor.filter (*cloud_filtered);
  
  std::cerr << "sor.getKeepOrganized()=" << (sor.getKeepOrganized()?"true":"false") << std::endl;
  std::cerr << "cloud->height=" << cloud->height << " cloud->width=" << cloud->width << "     cloud_filtered->height=" << cloud_filtered->height << " cloud_filtered->width=" << cloud_filtered->width << std::endl;
  std::cerr << "PointCloud after filtering: " << cloud_filtered->width * cloud_filtered->height 
       << " data points (" << pcl::getFieldsList (*cloud_filtered) << ")." << std::endl;

  //pcl::PCDWriter writer;
  //writer.write ("table_scene_lms400_downsampled.pcd", *cloud_filtered, 
  //       Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), false);

  return (0);
}

CMakeLists.txt:

cmake_minimum_required(VERSION 2.8 FATAL_ERROR)

project(crop_box_test)

message("CMAKE_MODULE_PATH=${CMAKE_MODULE_PATH}")
find_package(PCL 1.9.1.99 REQUIRED)

include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

add_executable (crop_box_test crop_box_test.cpp)
target_link_libraries (crop_box_test ${PCL_LIBRARIES})

Download the pcd file here: https://github.com/PointCloudLibrary/pcl/blob/master/test/milk_cartoon_all_small_clorox.pcd?raw=true

Possible Solution

Is this a bug or do I have false expectations?

@SergioRAgostinho
Copy link
Member

Technically it can be considered a bug, but I suspect is is simply a not implemented functionality. In the case of a CropBox filter which takes organized point clouds as input, it is definitely possible to filter points and preserve the organization by inserting nans wherever needed.

@SergioRAgostinho SergioRAgostinho added module: filters needs: code review Specify why not closed/merged yet labels Nov 17, 2019
@mvieth
Copy link
Member Author

mvieth commented Nov 18, 2019

I looked a bit into it to see which filters offer the keep-organized functionality (I only looked at PCLPointCloud2 filters). It seems like ExtractIndices, PassThrough, and StatisticalOutlierRemoval offer it, while CropBox, ProjectInliers, RadiusOutlierRemoval, RandomSample, and Voxelgrid don't. I am not sure if the functionality makes sense for all of the latter ones, though.
I will see if I find the time to provide a PR that adds that functionality.

@mvieth
Copy link
Member Author

mvieth commented Nov 18, 2019

A little update:
PassThrough<pcl::PCLPointCloud2> inherits from Filter, not from FilterIndices like the "normal" PassThrough. The same applies to RadiusOutlierRemoval. I think that should change.
For ProjectInliers and VoxelGrid, the keep-organized functionality makes no sense, so no change needed there.
That means that CropBox, RadiusOutlierRemoval, and RandomSample need the functionality added.

@taketwo
Copy link
Member

taketwo commented Nov 20, 2019

pcl::PCLPointCloud2 specializations should be aligned with the "normal" implementations in terms of both API and behavior. So ideally we should change the base class of the filters you mentioned.

@yzl96
Copy link

yzl96 commented Nov 22, 2019

pcl::PCLPointCloud2 specializations should be aligned with the "normal" implementations in terms of both API and behavior. So ideally we should change the base class of the filters you mentioned.

meet same bug, 1.9.1.99 cropbox return wrong, but 1.7.2 is ok.

@mvieth
Copy link
Member Author

mvieth commented Nov 22, 2019

@yzl96 Are you sure? I don't think that the keep-organized functionality was ever implemented in those classes.

@yzl96
Copy link

yzl96 commented Nov 22, 2019

@yzl96 Are you sure? I don't think that the keep-organized functionality was ever implemented in those classes.
what do you mean by Are you sure? I want to use cropbox to get points from a pointcloud in a bounding box, I recent update to pcl 1.9.1, the cropbox return is wrong, then I return to 1.7.2, cropbox return is right.

@mvieth
Copy link
Member Author

mvieth commented Nov 22, 2019

@yzl96 What do you mean exactly by "wrong"? Did you use my code from above? The topic of this issue is that the filtered clouds are not organized, meaning the height is 1. Is that what you are experiencing, too? I think this problem is present in every PCL version, because the relevant source code has not been changed for years. So I am wondering if we are talking about the same issue.

@mvieth
Copy link
Member Author

mvieth commented Jan 18, 2020

Since the two PRs are now merged, the problem should be fixed and this issue can, as far as I am concerned, be closed.

@taketwo taketwo closed this as completed Jan 19, 2020
@taketwo taketwo removed the needs: code review Specify why not closed/merged yet label Jan 19, 2020
@peci1
Copy link

peci1 commented Mar 20, 2020

This could be backported to 1.9 and 1.8 if the policy allows for that. If not, then the cropbox and other affected classes should at least issue a warning about missing functionality, shouldn't they?

@taketwo
Copy link
Member

taketwo commented Mar 21, 2020

Unfortunately, we don't have resources to backport and make additional patch releases. Please update to 1.10.1, 1.10.1, or current HEAD.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

5 participants