Class CObservationRGBD360
Defined in File CObservationRGBD360.h
Inheritance Relationships
Base Type
public mrpt::obs::CObservation(Class CObservation)
Class Documentation
-
class CObservationRGBD360 : public mrpt::obs::CObservation
Declares a class derived from “CObservation” that encapsules an omnidirectional RGBD measurement from a set of RGBD sensors. This kind of observations can carry one or more of these data fields:
3D point cloud (as float’s).
2D range image (as a matrix): Each entry in the matrix “rangeImage(ROW,COLUMN)” contains a distance or a depth (in meters), depending on range_is_depth.
2D intensity (grayscale or RGB) image (as a mrpt::img::CImage): For SwissRanger cameras, a logarithmic A-law compression is used to convert the original 16bit intensity to a more standard 8bit graylevel.
The coordinates of the 3D point cloud are in millimeters with respect to the RGB camera origin of coordinates
The 2D images and matrices are stored as common images, with an up->down rows order and left->right, as usual. Optionally, the intensity and confidence channels can be set to delayed-load images for off-rawlog storage so it saves memory by having loaded in memory just the needed images. See the methods load() and unload(). Due to the intensive storage requirements of this kind of observations, this observation is the only one in MRPT for which it’s recommended to always call “load()” and “unload()” before and after using the observation, ONLY when the observation was read from a rawlog dataset, in order to make sure that all the externally stored data fields are loaded and ready in memory.
Classes that grab observations of this type are:
3D point clouds can be generated at any moment after grabbing with CObservationRGBD360::unprojectInto() and CObservationRGBD360::unprojectInto(), provided the correct calibration parameters.
See also
mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::COpenNI2_RGBD360, CObservation
Note
Starting at serialization version 3 (MRPT 0.9.1+), the 3D point cloud and the rangeImage can both be stored externally to save rawlog space.
Note
Starting at serialization version 5 (MRPT 0.9.5+), the new field range_is_depth
Note
Starting at serialization version 6 (MRPT 0.9.5+), the new field intensityImageChannel
Public Functions
-
CObservationRGBD360()
Default constructor
-
~CObservationRGBD360() override
Destructor
-
void rangeImage_setSize(const int HEIGHT, const int WIDTH, const unsigned sensor_id)
Similar to calling “rangeImage.setSize(H,W)” but this method provides memory pooling to speed-up the memory allocation.
-
inline virtual void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot. Note that most sensors will return a full (6D) CPose3D, but see the derived classes for more details or special cases.
See also
-
inline virtual void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot. Note that most sensors will use the full (6D) CPose3D, but see the derived classes for more details or special cases.
See also
-
virtual void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the output stream.
Note
If overried by derived classes, call base CObservation::getDescriptionAsText() first to show common information.
Note
This is the text that appears in RawLogViewer when selecting an object in the dataset
Public Members
-
mrpt::system::TTimeStamp timestamps[NUM_SENSORS]
-
bool hasRangeImage = {false}
true means the field rangeImage contains valid data
-
mrpt::math::CMatrix_u16 rangeImages[NUM_SENSORS]
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
See also
range_is_depth
-
float rangeUnits = 0.001f
Units for integer depth values in rangeImages
-
bool hasIntensityImage = {false}
true means the field intensityImage contains valid data
-
mrpt::img::CImage intensityImages[NUM_SENSORS]
If hasIntensityImage=true, a color or gray-level intensity image of the same size than “rangeImage”
-
mrpt::img::TCamera sensorParamss[NUM_SENSORS]
Projection parameters of the 8 RGBD sensor.
-
float maxRange = {10.0f}
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,…)
-
float stdError = {0.01f}
The “sigma” error of the device in meters, used while inserting the scan in an occupancy grid.
Public Static Attributes
-
static const unsigned int NUM_SENSORS = 2
Protected Attributes
-
bool m_points3D_external_stored = {false}
If set to true, m_points3D_external_file is valid.
-
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+ this_file_name
-
bool m_rangeImage_external_stored = {false}
If set to true, m_rangeImage_external_file is valid.
-
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+ this_file_name