Go to the documentation of this file.
120 const int HEIGHT,
const int WIDTH,
const unsigned sensor_id);
CObservationRGBD360()
Default constructor.
~CObservationRGBD360() override
Destructor.
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
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 ...
mrpt::system::TTimeStamp timestamps[NUM_SENSORS]
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
mrpt::img::CImage intensityImages[NUM_SENSORS]
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
This namespace contains representation of robot actions and observations.
static const unsigned int NUM_SENSORS
float maxRange
The maximum range allowed by the device, in meters (e.g.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
float rangeUnits
Units for integer depth values in rangeImages.
Parameters for the Brown-Conrady camera lens distortion model.
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)
A class for storing images as grayscale or RGB bitmaps.
bool hasRangeImage
true means the field rangeImage contains valid data
bool hasIntensityImage
true means the field intensityImage contains valid data
mrpt::img::TCamera sensorParamss[NUM_SENSORS]
Projection parameters of the 8 RGBD sensor.
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
Declares a class that represents any robot's observation.
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
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.
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+<this_file_name>
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
Page generated by Doxygen 1.8.18 for MRPT 2.0.4 at Thu Sep 24 07:14:18 UTC 2020 | |