Main MRPT website > C++ reference for MRPT 1.5.7
obs/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  DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE( CObservationRGBD360, CObservation, OBS_IMPEXP )
27 
28 // namespace detail {
29 // // Implemented in CObservationRGBD360_project3D_impl.h
30 // template <class POINTMAP>
31 // void project3DPointsFromDepthImageInto(CObservationRGBD360 &src_obs, POINTMAP &dest_pointcloud, const bool takeIntoAccountSensorPoseOnRobot, const 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 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 "rangeImage(ROW,COLUMN)" contains a distance or a depth (in meters), depending on \a range_is_depth.
39  * - 2D intensity (grayscale or RGB) image (as a mrpt::utils::CImage): For SwissRanger cameras, a logarithmic A-law compression is used to convert the original 16bit intensity to a more standard 8bit graylevel.
40  *
41  * The coordinates of the 3D point cloud are in millimeters with respect to the RGB camera origin of coordinates
42  *
43  * The 2D images and matrices are stored as common images, with an up->down rows order and left->right, as usual.
44  * Optionally, the intensity and confidence channels can be set to delayed-load images for off-rawlog storage so it saves
45  * memory by having loaded in memory just the needed images. See the methods load() and unload().
46  * Due to the intensive storage requirements of this kind of observations, this observation is the only one in MRPT
47  * for which it's recommended to always call "load()" and "unload()" before and after using the observation, *ONLY* when
48  * the observation was read from a rawlog dataset, in order to make sure that all the externally stored data fields are
49  * loaded and ready in memory.
50  *
51  * Classes that grab observations of this type are:
52  * - mrpt::hwdrivers::CSwissRanger3DCamera
53  * - mrpt::hwdrivers::CKinect
54  *
55  *
56  * 3D point clouds can be generated at any moment after grabbing with CObservationRGBD360::project3DPointsFromDepthImage() and CObservationRGBD360::project3DPointsFromDepthImageInto(), provided the correct
57  * calibration parameters.
58  *
59  * \note Starting at serialization version 3 (MRPT 0.9.1+), the 3D point cloud and the rangeImage can both be stored externally to save rawlog space.
60  * \note Starting at serialization version 5 (MRPT 0.9.5+), the new field \a range_is_depth
61  * \note Starting at serialization version 6 (MRPT 0.9.5+), the new field \a intensityImageChannel
62  *
63  * \sa mrpt::hwdrivers::CSwissRanger3DCamera, mrpt::hwdrivers::COpenNI2_RGBD360, CObservation
64  * \ingroup mrpt_obs_grp
65  */
67  {
68  // This must be added to any CSerializable derived class:
70 
71  protected:
72  bool m_points3D_external_stored; //!< If set to true, m_points3D_external_file is valid.
73  std::string m_points3D_external_file; //!< 3D points are in CImage::IMAGES_PATH_BASE+<this_file_name>
74 
75  bool m_rangeImage_external_stored; //!< If set to true, m_rangeImage_external_file is valid.
76  std::string m_rangeImage_external_file; //!< rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name>
77 
78  public:
79  CObservationRGBD360( ); //!< Default constructor
80  virtual ~CObservationRGBD360( ); //!< Destructor
81 
82  static const unsigned int NUM_SENSORS = 2;
83 
84  mrpt::system::TTimeStamp timestamps[NUM_SENSORS];
85 
86  bool hasRangeImage; //!< true means the field rangeImage contains valid data
87  mrpt::math::CMatrix rangeImages[NUM_SENSORS]; //!< If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) \sa range_is_depth
88 
89  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 memory allocation.
90 
91  bool hasIntensityImage; //!< true means the field intensityImage contains valid data
92  mrpt::utils::CImage intensityImages[NUM_SENSORS]; //!< If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"
93  mrpt::utils::TCamera sensorParamss[NUM_SENSORS]; //!< Projection parameters of the 8 RGBD sensor.
94 
95  float maxRange; //!< The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
96  mrpt::poses::CPose3D sensorPose; //!< The 6D pose of the sensor on the robot.
97  float stdError; //!< The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid.
98 
99  // See base class docs
100  void getSensorPose( mrpt::poses::CPose3D &out_sensorPose ) const MRPT_OVERRIDE { out_sensorPose = sensorPose; }
101  void setSensorPose( const mrpt::poses::CPose3D &newSensorPose ) MRPT_OVERRIDE { sensorPose = newSensorPose; }
102  void getDescriptionAsText(std::ostream &o) const MRPT_OVERRIDE;
103 
104  }; // End of class def.
105  DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE( CObservationRGBD360, CObservation, OBS_IMPEXP )
106 
107 
108  } // End of namespace
109 
110 } // End of namespace
111 
112 #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:30
std::string m_rangeImage_external_file
rangeImage is in CImage::IMAGES_PATH_BASE+<this_file_name>
Declares a class derived from "CObservation" that encapsules an omnidirectional RGBD measurement from...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:101
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
#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...
float maxRange
The maximum range allowed by the device, in meters (e.g. 8.0m, 5.0m,...)
GLsizei const GLchar ** string
Definition: glext.h:3919
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...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:72
Declares a class that represents any robot&#39;s observation.
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
A general method to change the sensor pose on the robot.
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
A general method to retrieve the sensor pose on the robot.
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:30
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
std::string m_points3D_external_file
3D points are in CImage::IMAGES_PATH_BASE+<this_file_name>
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:31
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.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019