Generating 3D point clouds from RGB+D observations (CObservation3DRangeScan objects)

 

 

See also: Kinect and MRPT

1. Calibration parameters

Firstly, you must have very clear the calibration parameters involved in the process. 

Each "RGB+D observation" is stored in MRPT as one object of type mrpt::slam::CObservation3DRangeScan (click to see its full description), which for this tutorial will be assumed that contains:

These observations can be captured from a sensor (e.g. Kinect) in real-time, or loaded from a dataset, as explained here

In any case, the calibration parameters of both cameras will come already filled in with their correct values (or, at least, those the user provided in the moment of capturing/grabbing the dataset!). 

This set of three pieces of data that must be calibrated (for example, see the tutorial for Kinect calibration) before generating precise 3D point clouds from RGB+D observations are: the two sets of camera parameters and the relative 6D pose between them.

3D camera reference systems

 

 


2. Projection equations

 

(Write me!) In the meanwhile, please refer to the source code in: http://mrpt.googlecode.com/svn/trunk/libs/obs/include/mrpt/slam/CObservation3DRangeScan_project3D_impl.h

and this example: http://mrpt.googlecode.com/svn/trunk/samples/kinect_online_offline_demo/

 

2.1. General case

...

 

2.2. "Rectified" depth image

...

 


There exist different possibilities:

 

3.1. RGB+D --> local 3D point cloud

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever 
obsRGBD->project3DPointsFromDepthImage(); // Project points into the internal buffers of "obsRGBD"

// Points are now in the object buffers as std::vector<float>: 
cout << obsRGBD->points3D_x[0] << endl;
cout << obsRGBD->points3D_y[0] << endl;
cout << obsRGBD->points3D_z[0] << endl;

 

3.2. RGB+D --> local 3D point cloud --> CPointsMap (& derived)

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever 
obsRGBD->project3DPointsFromDepthImage(); // Project points into the internal buffers of "obsRGBD"

// Load into an XYZ point map: 
CSimplePointsMap pntsMap;
pntsMap.minDistBetweenLaserPoints = 0.05; // In meters
pntsMap.loadFromRangeScan(*obsRGBD);

// *OR* into an XYZ+RGB point map:
CColouredPointsMap pntsMap;
pntsMap.minDistBetweenLaserPoints = 0.05; // In meters
pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;
pntsMap.loadFromRangeScan(*obsRGBD);

 

3.3. RGB+D --> CPointsMap (& derived)

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever 
CSimplePointsMap pntsMap;  // Or any other class derived from CPointsMap. If it has RGB data it will get filled.
obsRGBD->project3DPointsFromDepthImageInto(
    pntsMap,
    false /* without obs.sensorPose */
    );

3.4. RGB+D --> mrpt::opengl::CPointCloud

 
CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever
mrpt::opengl::CPointCloudPtr gl_points = mrpt::opengl::CPointCloud::Create();  // Smart pointer to opengl point cloud (with XYZ data)
obsRGBD->project3DPointsFromDepthImageInto(
    *gl_points,
    false /* without obs.sensorPose */
    );
 

3.5. RGB+D --> mrpt::opengl::CPointCloudColoured

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever
mrpt::opengl::CPointCloudColouredPtr gl_points = mrpt::opengl::CPointCloudColoured::Create();  // Smart pointer to opengl point cloud (with XYZ & RGB data)
obsRGBD->project3DPointsFromDepthImageInto(
    *gl_points,
    false /* without obs.sensorPose */
    );

 

3.6. RGB+D --> pcl::PointCloud<PointXYZ> 

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever 
pcl::PointCloud<pcl::PointXYZ> cloud;
obsRGBD->project3DPointsFromDepthImageInto(
    cloud,
    false /* without obs.sensorPose */
    );

 

3.7. RGB+D --> pcl::PointCloud<PointXYZRGB>

 

CObservation3DRangeScanPtr obsRGBD = ...  // Get a smart pointer to the RGB+D observation data from wherever
pcl::PointCloud<pcl::PointXYZRGB> cloud;
obsRGBD->project3DPointsFromDepthImageInto(
    cloud,
    false /* without obs.sensorPose */
    );

 

Syndicate content

The Mobile Robot Programming Toolkit (MRPT) initiative (C) 2012