9#ifndef CObservationRGBD360_H
10#define CObservationRGBD360_H
82 static const unsigned int NUM_SENSORS = 2;
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
This class is a "CSerializable" wrapper for "CMatrixFloat".
Declares a class that represents any robot's observation.
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
A general method to change the sensor pose on the robot.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
float maxRange
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
std::string m_points3D_external_file
3D points are in CImage::IMAGES_PATH_BASE+<this_file_name>
virtual ~CObservationRGBD360()
Destructor.
CObservationRGBD360()
Default constructor.
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 ...
std::string m_rangeImage_external_file
rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name>
bool hasRangeImage
true means the field rangeImage contains valid data
bool hasIntensityImage
true means the field intensityImage contains valid data
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
A general method to retrieve the sensor pose on the robot.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
void getDescriptionAsText(std::ostream &o) const MRPT_OVERRIDE
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
A class for storing images as grayscale or RGB bitmaps.
Structure to hold the parameters of a pinhole camera model.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.