Go to the documentation of this file. 1 #ifndef ED_RGBD_DATA_H_
2 #define ED_RGBD_DATA_H_
4 #include <pcl/point_types.h>
7 #include <pcl/pcl_base.h>
rgbd::ImageConstPtr image
Original RGBD image received from the sensor.
pcl::PointCloud< pcl::PointNormal >::Ptr point_cloud_with_normals
Point cloud constructed from the image (possibly voxelized)
pcl::IndicesConstPtr PointCloudMaskConstPtr
pcl::IndicesPtr PointCloudMaskPtr
const static PointCloudMask NO_MASK(1, -1)
pcl::PointCloud< pcl::PointXYZ >::Ptr point_cloud
Point cloud constructed from the image (possibly voxelized)
std::vector< int > PointCloudMask
std::vector< std::vector< int > > PointCloudToPixelsMapping
PointCloudToPixelsMapping point_cloud_to_pixels_mapping
Mapping from point cloud to pixel indices in the full resolution depth image.