MRPT  2.0.4
CObservationRGBD360.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/img/CImage.h>
12 #include <mrpt/math/CMatrixF.h>
13 #include <mrpt/math/CPolygon.h>
14 #include <mrpt/obs/CObservation.h>
17 #include <mrpt/poses/CPose2D.h>
18 #include <mrpt/poses/CPose3D.h>
20 
21 namespace mrpt
22 {
23 namespace obs
24 {
25 // namespace detail {
26 // // Implemented in CObservationRGBD360_project3D_impl.h
27 // template <class POINTMAP>
28 // void unprojectInto(CObservationRGBD360 &src_obs,
29 // POINTMAP &dest_pointcloud, const bool takeIntoAccountSensorPoseOnRobot, const
30 // mrpt::poses::CPose3D * robotPoseInTheWorld, const bool PROJ3D_USE_LUT);
31 // }
32 
33 /** Declares a class derived from "CObservation" that
34  * encapsules an omnidirectional RGBD measurement from a set of RGBD
35  *sensors.
36  * This kind of observations can carry one or more of these data fields:
37  * - 3D point cloud (as float's).
38  * - 2D range image (as a matrix): Each entry in the matrix
39  *"rangeImage(ROW,COLUMN)" contains a distance or a depth (in meters), depending
40  *on \a range_is_depth.
41  * - 2D intensity (grayscale or RGB) image (as a mrpt::img::CImage): For
42  *SwissRanger cameras, a logarithmic A-law compression is used to convert the
43  *original 16bit intensity to a more standard 8bit graylevel.
44  *
45  * The coordinates of the 3D point cloud are in millimeters with respect to the
46  *RGB camera origin of coordinates
47  *
48  * The 2D images and matrices are stored as common images, with an up->down
49  *rows order and left->right, as usual.
50  * Optionally, the intensity and confidence channels can be set to
51  *delayed-load images for off-rawlog storage so it saves
52  * memory by having loaded in memory just the needed images. See the methods
53  *load() and unload().
54  * Due to the intensive storage requirements of this kind of observations, this
55  *observation is the only one in MRPT
56  * for which it's recommended to always call "load()" and "unload()" before
57  *and after using the observation, *ONLY* when
58  * the observation was read from a rawlog dataset, in order to make sure that
59  *all the externally stored data fields are
60  * loaded and ready in memory.
61  *
62  * Classes that grab observations of this type are:
63  * - mrpt::hwdrivers::CSwissRanger3DCamera
64  * - mrpt::hwdrivers::CKinect
65  *
66  *
67  * 3D point clouds can be generated at any moment after grabbing with
68  *CObservationRGBD360::unprojectInto() and
69  *CObservationRGBD360::unprojectInto(), provided the correct
70  * calibration parameters.
71  *
72  * \note Starting at serialization version 3 (MRPT 0.9.1+), the 3D point cloud
73  *and the rangeImage can both be stored externally to save rawlog space.
74  * \note Starting at serialization version 5 (MRPT 0.9.5+), the new field \a
75  *range_is_depth
76  * \note Starting at serialization version 6 (MRPT 0.9.5+), the new field \a
77  *intensityImageChannel
78  *
79  * \sa mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::COpenNI2_RGBD360,
80  *CObservation
81  * \ingroup mrpt_obs_grp
82  */
84 {
86 
87  protected:
88  /** If set to true, m_points3D_external_file is valid. */
90  /** 3D points are in CImage::getImagesPathBase()+<this_file_name> */
92 
93  /** If set to true, m_rangeImage_external_file is valid. */
95  /** rangeImage is in CImage::getImagesPathBase()+<this_file_name> */
97 
98  public:
99  /** Default constructor */
101  /** Destructor */
102  ~CObservationRGBD360() override;
103 
104  static const unsigned int NUM_SENSORS = 2;
105 
107 
108  /** true means the field rangeImage contains valid data */
109  bool hasRangeImage{false};
110  /** If hasRangeImage=true, a matrix of floats with the range data as
111  * captured by the camera (in meters) \sa range_is_depth */
113 
114  /** Units for integer depth values in rangeImages */
115  float rangeUnits = 0.001f;
116 
117  /** Similar to calling "rangeImage.setSize(H,W)" but this method provides
118  * memory pooling to speed-up the memory allocation. */
119  void rangeImage_setSize(
120  const int HEIGHT, const int WIDTH, const unsigned sensor_id);
121 
122  /** true means the field intensityImage contains valid data */
123  bool hasIntensityImage{false};
124  /** If hasIntensityImage=true, a color or gray-level intensity image of the
125  * same size than "rangeImage" */
127  /** Projection parameters of the 8 RGBD sensor. */
129 
130  /** The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
131  */
132  float maxRange{10.0f};
133  /** The 6D pose of the sensor on the robot. */
135  /** The "sigma" error of the device in meters, used while inserting the scan
136  * in an occupancy grid. */
137  float stdError{0.01f};
138 
139  // See base class docs
140  void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
141  {
142  out_sensorPose = sensorPose;
143  }
144  void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) override
145  {
146  sensorPose = newSensorPose;
147  }
148  void getDescriptionAsText(std::ostream& o) const override;
149 
150 }; // End of class def.
151 
152 } // namespace obs
153 
154 } // namespace mrpt
mrpt::obs::CObservationRGBD360::CObservationRGBD360
CObservationRGBD360()
Default constructor.
Definition: CObservationRGBD360.cpp:30
mrpt::obs::CObservationRGBD360::~CObservationRGBD360
~CObservationRGBD360() override
Destructor.
Definition: CObservationRGBD360.cpp:34
DEFINE_SERIALIZABLE
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
Definition: CSerializable.h:152
mrpt::obs::CObservationRGBD360::rangeImage_setSize
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 ...
Definition: CObservationRGBD360.cpp:110
mrpt::obs::CObservationRGBD360::timestamps
mrpt::system::TTimeStamp timestamps[NUM_SENSORS]
Definition: CObservationRGBD360.h:106
mrpt::obs::CObservationRGBD360::stdError
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
Definition: CObservationRGBD360.h:137
mrpt::obs::CObservationRGBD360::intensityImages
mrpt::img::CImage intensityImages[NUM_SENSORS]
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
Definition: CObservationRGBD360.h:126
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: BaseAppDataSource.h:15
CPose2D.h
mrpt::obs
This namespace contains representation of robot actions and observations.
Definition: CParticleFilter.h:17
mrpt::obs::CObservationRGBD360::NUM_SENSORS
static const unsigned int NUM_SENSORS
Definition: CObservationRGBD360.h:104
mrpt::obs::CObservationRGBD360::maxRange
float maxRange
The maximum range allowed by the device, in meters (e.g.
Definition: CObservationRGBD360.h:132
mrpt::obs::CObservationRGBD360::sensorPose
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
Definition: CObservationRGBD360.h:134
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
mrpt::obs::CObservationRGBD360::setSensorPose
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
Definition: CObservationRGBD360.h:144
mrpt::system::TTimeStamp
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
Definition: datetime.h:40
mrpt::obs::CObservationRGBD360::rangeUnits
float rangeUnits
Units for integer depth values in rangeImages.
Definition: CObservationRGBD360.h:115
mrpt::img::TCamera
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:26
mrpt::obs::CObservationRGBD360::rangeImages
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)
Definition: CObservationRGBD360.h:112
mrpt::img::CImage
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:148
CPolygon.h
CPose3D.h
mrpt::obs::CObservationRGBD360::hasRangeImage
bool hasRangeImage
true means the field rangeImage contains valid data
Definition: CObservationRGBD360.h:109
mrpt::obs::CObservationRGBD360::hasIntensityImage
bool hasIntensityImage
true means the field intensityImage contains valid data
Definition: CObservationRGBD360.h:123
mrpt::obs::CObservationRGBD360::sensorParamss
mrpt::img::TCamera sensorParamss[NUM_SENSORS]
Projection parameters of the 8 RGBD sensor.
Definition: CObservationRGBD360.h:128
CObservation.h
pointcloud_adapters.h
mrpt::obs::CObservationRGBD360
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
Definition: CObservationRGBD360.h:83
mrpt::obs::CObservation
Declares a class that represents any robot's observation.
Definition: CObservation.h:43
mrpt::obs::CObservationRGBD360::getSensorPose
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
Definition: CObservationRGBD360.h:140
mrpt::obs::CObservationRGBD360::m_rangeImage_external_file
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
Definition: CObservationRGBD360.h:96
CImage.h
mrpt::obs::CObservationRGBD360::m_points3D_external_stored
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.
Definition: CObservationRGBD360.h:89
mrpt::obs::CObservationRGBD360::m_rangeImage_external_stored
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
Definition: CObservationRGBD360.h:94
CMatrixF.h
CSerializable.h
mrpt::obs::CObservationRGBD360::m_points3D_external_file
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+<this_file_name>
Definition: CObservationRGBD360.h:91
mrpt::math::CMatrixDynamic< uint16_t >
CObservation2DRangeScan.h
mrpt::obs::CObservationRGBD360::getDescriptionAsText
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
Definition: CObservationRGBD360.cpp:117



Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Sun Jul 19 17:54:30 UTC 2020