MRPT  1.9.9
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-2019, 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 project3DPointsFromDepthImageInto(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::project3DPointsFromDepthImage() and
69  *CObservationRGBD360::project3DPointsFromDepthImageInto(), 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  /** Similar to calling "rangeImage.setSize(H,W)" but this method provides
115  * memory pooling to speed-up the memory allocation. */
116  void rangeImage_setSize(
117  const int HEIGHT, const int WIDTH, const unsigned sensor_id);
118 
119  /** true means the field intensityImage contains valid data */
120  bool hasIntensityImage{false};
121  /** If hasIntensityImage=true, a color or gray-level intensity image of the
122  * same size than "rangeImage" */
124  /** Projection parameters of the 8 RGBD sensor. */
126 
127  /** The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
128  */
129  float maxRange{10.0f};
130  /** The 6D pose of the sensor on the robot. */
132  /** The "sigma" error of the device in meters, used while inserting the scan
133  * in an occupancy grid. */
134  float stdError{0.01f};
135 
136  // See base class docs
137  void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
138  {
139  out_sensorPose = sensorPose;
140  }
141  void setSensorPose(const mrpt::poses::CPose3D& newSensorPose) override
142  {
143  sensorPose = newSensorPose;
144  }
145  void getDescriptionAsText(std::ostream& o) const override;
146 
147 }; // End of class def.
148 
149 } // namespace obs
150 
151 } // namespace mrpt
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
~CObservationRGBD360() override
Destructor.
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
mrpt::img::TCamera sensorParamss[NUM_SENSORS]
Projection parameters of the 8 RGBD sensor.
mrpt::img::CImage intensityImages[NUM_SENSORS]
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
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 ...
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
mrpt::system::TTimeStamp timestamps[NUM_SENSORS]
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
CObservationRGBD360()
Default constructor.
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
static const unsigned int NUM_SENSORS
float maxRange
The maximum range allowed by the device, in meters (e.g.
mrpt::math::CMatrixF rangeImages[NUM_SENSORS]
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:25
GLsizei const GLchar ** string
Definition: glext.h:4116
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) override
A general method to change the sensor pose on the robot.
bool hasIntensityImage
true means the field intensityImage contains valid data
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrixF.h:22
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const override
A general method to retrieve the sensor pose on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:84
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
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>
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:147
bool hasRangeImage
true means the field rangeImage contains valid data
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019