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