ed
rgbd_data.h
Go to the documentation of this file.
1 #ifndef ED_RGBD_DATA_H_
2 #define ED_RGBD_DATA_H_
3 
4 #include <pcl/point_types.h>
5 #include <rgbd/image.h>
6 #include <geolib/datatypes.h>
7 #include <pcl/pcl_base.h>
8 
9 #include <vector>
10 
11 namespace ed
12 {
13 
15 typedef pcl::IndicesPtr PointCloudMaskPtr;
16 typedef pcl::IndicesConstPtr PointCloudMaskConstPtr;
18 
19 // TODO: check if this works!
20 const static PointCloudMask NO_MASK( 1, -1 );
21 
22 struct RGBDData
23 {
26 
28 
30  pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud;
31 
33  pcl::PointCloud<pcl::PointNormal>::Ptr point_cloud_with_normals;
34 
37 };
38 
39 }
40 
41 #endif
datatypes.h
std::shared_ptr< const Image >
vector
ed::RGBDData::image
rgbd::ImageConstPtr image
Original RGBD image received from the sensor.
Definition: rgbd_data.h:25
ed::RGBDData::point_cloud_with_normals
pcl::PointCloud< pcl::PointNormal >::Ptr point_cloud_with_normals
Point cloud constructed from the image (possibly voxelized)
Definition: rgbd_data.h:33
geo::Transform3T
ed::RGBDData
Definition: rgbd_data.h:22
ed::PointCloudMaskConstPtr
pcl::IndicesConstPtr PointCloudMaskConstPtr
Definition: rgbd_data.h:16
image.h
ed::PointCloudMaskPtr
pcl::IndicesPtr PointCloudMaskPtr
Definition: rgbd_data.h:15
ed::NO_MASK
const static PointCloudMask NO_MASK(1, -1)
ed::RGBDData::point_cloud
pcl::PointCloud< pcl::PointXYZ >::Ptr point_cloud
Point cloud constructed from the image (possibly voxelized)
Definition: rgbd_data.h:30
ed::RGBDData::sensor_pose
geo::Pose3D sensor_pose
Definition: rgbd_data.h:27
ed::PointCloudMask
std::vector< int > PointCloudMask
Definition: rgbd_data.h:14
ed::PointCloudToPixelsMapping
std::vector< std::vector< int > > PointCloudToPixelsMapping
Definition: rgbd_data.h:17
ed::RGBDData::point_cloud_to_pixels_mapping
PointCloudToPixelsMapping point_cloud_to_pixels_mapping
Mapping from point cloud to pixel indices in the full resolution depth image.
Definition: rgbd_data.h:36
ed
Definition: convex_hull.h:8