Main MRPT website > C++ reference for MRPT 1.9.9
COpenNI2Sensor.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-2018, 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 mrpt_COpenNI2Sensor_H
10 #define mrpt_COpenNI2Sensor_H
11 
16 
17 namespace mrpt
18 {
19 namespace hwdrivers
20 {
21 /** A class for grabing "range images", intensity images (either RGB or IR) and
22  *other information from an OpenNI2 sensor.
23  * This class permits to access several sensors simultaneously. The same
24  *options (resolution, fps, etc.) are used for every sensor.
25  *
26  * <h2>Configuration and usage:</h2> <hr>
27  * Data is returned as observations of type mrpt::obs::CObservation3DRangeScan.
28  * See those classes for documentation on their fields.
29  *
30  * As with any other CGenericSensor class, the normal sequence of methods to be
31  *called is:
32  * - CGenericSensor::loadConfig() - Or calls to the individual setXXX() to
33  *configure the sensor parameters.
34  * - COpenNI2Sensor::initialize() - to start the communication with the
35  *sensor.
36  * - call COpenNI2Sensor::getNextObservation() for getting the data.
37  *
38  * <h2>Calibration parameters</h2><hr>
39  * In this class we employ the OpenNI2 method to return depth images refered
40  *to the RGB camera. Otherwise we could specify
41  * an accurate transformation of depth images to 3D points, you'll have to
42  *calibrate your RGBD sensor for that, and supply
43  * the following <b>threee pieces of information</b> (default calibration
44  *data will be used otherwise, but they'll be not optimal for all sensors!):
45  * - Camera parameters for the RGB camera. See
46  *COpenNI2Sensor::setCameraParamsIntensity()
47  * - Camera parameters for the depth camera. See
48  *COpenNI2Sensor::setCameraParamsDepth()
49  * - The 3D relative pose of the two cameras. See
50  *COpenNI2Sensor::setRelativePoseIntensityWrtDepth()
51  *
52  * See http://www.mrpt.org/Kinect_calibration for a procedure to calibrate
53  *RGBD sensors with an interactive GUI program.
54  *
55  * <h2>Coordinates convention</h2><hr>
56  * The origin of coordinates is the focal point of the depth camera, with the
57  *axes oriented as in the
58  * diagram shown in mrpt::obs::CObservation3DRangeScan. Notice in that
59  *picture that the RGB camera is
60  * assumed to have axes as usual in computer vision, which differ from those
61  *for the depth camera.
62  *
63  * The X,Y,Z axes used to report the data from accelerometers coincide with
64  *those of the depth camera
65  * (e.g. the camera standing on a table would have an ACC_Z=-9.8m/s2).
66  *
67  * Notice however that, for consistency with stereo cameras, when loading the
68  *calibration parameters from
69  * a configuration file, the left-to-right pose increment is expected as if
70  *both RGB & IR cameras had
71  * their +Z axes pointing forward, +X to the right, +Y downwards (just like
72  *it's the standard in stereo cameras
73  * and in computer vision literature). In other words: the pose stored in
74  *this class uses a different
75  * axes convention for the depth camera than in a stereo camera, so when a
76  *pose L2R is loaded from a calibration file
77  * it's actually converted like:
78  *
79  * L2R(this class convention) = CPose3D(0,0,0,-90deg,0deg,-90deg) (+)
80  *L2R(in the config file)
81  *
82  *
83  * <h2>Some general comments</h2><hr>
84  * - Depth is grabbed in millimeters
85  * - This sensor can be also used from within rawlog-grabber to grab
86  *datasets
87  *within a robot with more sensors.
88  * - There is no built-in threading support, so if you use this class
89  *manually
90  *(not with-in rawlog-grabber),
91  * the ideal would be to create a thread and continuously request data
92  *from
93  *that thread (see mrpt::system::createThread ).
94  * - The intensity channel default to the RGB images, but it can be changed
95  *with setVideoChannel() to read the IR camera images (useful for calibrating).
96  * - There is a built-in support for an optional preview of the data on a
97  *window, so you don't need to even worry on creating a window to show them.
98  * - This class relies on an embedded version of libfreenect (you do NOT
99  *need
100  *to install it in your system). Thanks guys for the great job!
101  *
102  * <h2>Converting to 3D point cloud </h2><hr>
103  * You can convert the 3D observation into a 3D point cloud with this piece
104  *of code:
105  *
106  * \code
107  * mrpt::obs::CObservation3DRangeScan obs3D;
108  * mrpt::maps::CColouredPointsMap pntsMap;
109  * pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;
110  * pntsMap.loadFromRangeScan(obs3D);
111  * \endcode
112  *
113  * Then the point cloud mrpt::maps::CColouredPointsMap can be converted into
114  *an OpenGL object for
115  * rendering with mrpt::maps::CMetricMap::getAs3DObject() or alternatively
116  *with:
117  *
118  * \code
119  * mrpt::opengl::CPointCloudColoured::Ptr gl_points =
120  *mrpt::make_aligned_shared<mrpt::opengl::CPointCloudColoured>();
121  * gl_points->loadFromPointsMap(&pntsMap);
122  * \endcode
123  *
124  *
125  * <h2>Platform-specific comments</h2><hr>
126  * For more details, refer to <a href="http://openkinect.org/wiki/Main_Page"
127  *>libfreenect</a> documentation:
128  * - Linux: You'll need root privileges to access Kinect. Or, install
129  *<code>
130  *MRPT/scripts/51-kinect.rules </code> in <code>/etc/udev/rules.d/</code> to
131  *allow access to all users.
132  * - Windows:
133  * - Since MRPT 0.9.4 you'll only need to install <a
134  *href="http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/"
135  *>libusb-win32</a>: download and extract the latest
136  *libusb-win32-bin-x.x.x.x.zip
137  * - To install the drivers, read this:
138  *http://openkinect.org/wiki/Getting_Started#Windows
139  * - MacOS: (write me!)
140  *
141  *
142  * <h2>Format of parameters for loading from a .ini file</h2><hr>
143  *
144  * \code
145  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
146  * -------------------------------------------------------
147  * [supplied_section_name]
148  * sensorLabel = OPENNI2 // A text description
149  * preview_window = false // Show a window with a preview of the
150  *grabbed data in real-time
151  *
152  * device_number = 0 // Device index to open (0:first Kinect,
153  *1:second Kinect,...)
154  *
155  * grab_image = true // Grab the RGB image channel?
156  *(Default=true)
157  * grab_depth = true // Grab the depth channel? (Default=true)
158  * grab_3D_points = true // Grab the 3D point cloud? (Default=true)
159  *If disabled, points can be generated later on.
160  *
161  * video_channel = VIDEO_CHANNEL_RGB // Optional. Can be:
162  *VIDEO_CHANNEL_RGB (default) or VIDEO_CHANNEL_IR
163  *
164  * pose_x=0 // Camera position in the robot (meters)
165  * pose_y=0
166  * pose_z=0
167  * pose_yaw=0 // Angles in degrees
168  * pose_pitch=0
169  * pose_roll=0
170  *
171  *
172  * // Kinect sensor calibration:
173  * // See http://www.mrpt.org/Kinect_and_MRPT
174  *
175  * // Left/Depth camera
176  * [supplied_section_name_LEFT]
177  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
178  *section (it is not a separate device!)
179  *
180  * resolution = [640 488]
181  * cx = 314.649173
182  * cy = 240.160459
183  * fx = 572.882768
184  * fy = 542.739980
185  * dist = [-4.747169e-03 -4.357976e-03 0.000000e+00 0.000000e+00
186  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
187  *
188  * // Right/RGB camera
189  * [supplied_section_name_RIGHT]
190  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
191  *section (it is not a separate device!)
192  *
193  * resolution = [640 480]
194  * cx = 322.515987
195  * cy = 259.055966
196  * fx = 521.179233
197  * fy = 493.033034
198  * dist = [5.858325e-02 3.856792e-02 0.000000e+00 0.000000e+00
199  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
200  *
201  * // Relative pose of the right camera wrt to the left camera:
202  * // This assumes that both camera frames are such that +Z points
203  * // forwards, and +X and +Y to the right and downwards.
204  * // For the actual coordinates employed in 3D observations, see figure in
205  *mrpt::obs::CObservation3DRangeScan
206  * [supplied_section_name_LEFT2RIGHT_POSE]
207  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
208  *section (it is not a separate device!)
209  *
210  * pose_quaternion = [0.025575 -0.000609 -0.001462 0.999987 0.002038
211  *0.004335 -0.001693]
212  *
213  * \endcode
214  *
215  * More references to read:IMPEXP mrpt
216  * - http://http://www.openni.org/
217  * \ingroup mrpt_hwdrivers_grp
218  */
221 {
223 
224  public:
225  /** Default ctor
226  */
227  COpenNI2Sensor();
228  /** Default ctor
229  */
230  ~COpenNI2Sensor();
231 
232  /** Set the serial number of the device to open.
233  * \exception This method must throw an exception when such serial number
234  * is not found among the connected devices.
235  */
236  inline void setSerialToOpen(const unsigned serial)
237  {
238  m_serial_number = serial;
239  }
240 
241  /** Set the sensor_id of the device to open.
242  * \exception This method must throw an exception when such serial number
243  * is not found among the connected devices.
244  */
245  inline void setSensorIDToOpen(const unsigned sensor_id)
246  {
247  m_user_device_number = sensor_id;
248  }
249 
250  /** Initializes the 3D camera - should be invoked after calling loadConfig()
251  * or setting the different parameters with the set*() methods.
252  * \exception This method must throw an exception with a descriptive
253  * message if some critical error is found.
254  */
255  virtual void initialize();
256 
257  /** To be called at a high rate (>XX Hz), this method populates the
258  * internal buffer of received observations.
259  * This method is mainly intended for usage within rawlog-grabber or
260  * similar programs.
261  * For an alternative, see getNextObservation()
262  * \exception This method must throw an exception with a descriptive
263  * message if some critical error is found.
264  * \sa getNextObservation
265  */
266  virtual void doProcess();
267 
268  /** The main data retrieving function, to be called after calling
269  * loadConfig() and initialize().
270  * \param out_obs The output retrieved observation (only if
271  * there_is_obs=true).
272  * \param there_is_obs If set to false, there was no new observation.
273  * \param hardware_error True on hardware/comms error.
274  *
275  * \sa doProcess
276  */
277  void getNextObservation(
278  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
279  bool& hardware_error);
280 
281  /** Set the path where to save off-rawlog image files (this class DOES take
282  * into account this path).
283  * An empty string (the default value at construction) means to save
284  * images embedded in the rawlog, instead of on separate files.
285  * \exception std::exception If the directory doesn't exists and cannot be
286  * created.
287  */
288  virtual void setPathForExternalImages(const std::string& directory);
289 
290  /** @name Sensor parameters (alternative to \a loadConfig ) and manual
291  control
292  @{ */
293 
294  /** Get the maximum range (meters) that can be read in the observation field
295  * "rangeImage" */
296  inline double getMaxRange() const { return m_maxRange; }
297  /** Get the row count in the camera images, loaded automatically upon camera
298  * open(). */
299  inline size_t rows() const { return m_cameraParamsRGB.nrows; }
300  /** Get the col count in the camera images, loaded automatically upon camera
301  * open(). */
302  inline size_t cols() const { return m_cameraParamsRGB.ncols; }
303  /** Get a const reference to the depth camera calibration parameters */
305  {
306  return m_cameraParamsRGB;
307  }
309  {
311  }
312 
313  /** Get a const reference to the depth camera calibration parameters */
315  {
316  return m_cameraParamsDepth;
317  }
319  {
321  }
322 
323  /** Set the pose of the intensity camera wrt the depth camera \sa See
324  * mrpt::obs::CObservation3DRangeScan for a 3D diagram of this pose */
326  {
328  }
330  {
332  }
333 
334  /** Enable/disable the grabbing of the RGB channel */
335  inline void enableGrabRGB(bool enable = true) { m_grab_image = enable; }
336  inline bool isGrabRGBEnabled() const { return m_grab_image; }
337  /** Enable/disable the grabbing of the depth channel */
338  inline void enableGrabDepth(bool enable = true) { m_grab_depth = enable; }
339  inline bool isGrabDepthEnabled() const { return m_grab_depth; }
340  /** Enable/disable the grabbing of the 3D point clouds */
341  inline void enableGrab3DPoints(bool enable = true)
342  {
343  m_grab_3D_points = enable;
344  }
345  inline bool isGrab3DPointsEnabled() const { return m_grab_3D_points; }
346  /** @} */
347 
348  protected:
349  virtual void loadConfig_sensorSpecific(
350  const mrpt::config::CConfigFileBase& configSource,
351  const std::string& section);
352 
354 
355  /** Show preview window while grabbing
356  */
358  /** If preview is enabled, only show 1 out of N images.
359  */
363 
364  /** Params for the RGB camera
365  */
367  /** Params for the Depth camera
368  */
370  /** See mrpt::obs::CObservation3DRangeScan for a diagram of this pose
371  */
373 
374  /** Sensor max range (meters)
375  */
376  double m_maxRange;
377 
378  /** Number of device to open (0:first,...)
379  */
381  /** Serial number of device to open
382  */
384 
385 }; // End of class
386 } // End of NS
387 
388 } // End of NS
389 
390 #endif
mrpt::hwdrivers::COpenNI2Sensor::isGrabRGBEnabled
bool isGrabRGBEnabled() const
Definition: COpenNI2Sensor.h:336
mrpt::hwdrivers::COpenNI2Sensor::cols
size_t cols() const
Get the col count in the camera images, loaded automatically upon camera open().
Definition: COpenNI2Sensor.h:302
mrpt::hwdrivers::COpenNI2Generic::m_grab_image
bool m_grab_image
The data that the RGBD sensors can return.
Definition: COpenNI2Generic.h:163
mrpt::hwdrivers::COpenNI2Sensor::m_win_range
mrpt::gui::CDisplayWindow::Ptr m_win_range
Definition: COpenNI2Sensor.h:362
mrpt::hwdrivers::COpenNI2Sensor::COpenNI2Sensor
COpenNI2Sensor()
Default ctor.
Definition: COpenNI2Sensor.cpp:39
COpenNI2Generic.h
mrpt::hwdrivers::COpenNI2Sensor::m_preview_decim_counter_range
size_t m_preview_decim_counter_range
Definition: COpenNI2Sensor.h:361
mrpt::hwdrivers::COpenNI2Sensor::doProcess
virtual void doProcess()
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
Definition: COpenNI2Sensor.cpp:157
mrpt::hwdrivers::COpenNI2Sensor::m_cameraParamsDepth
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
Definition: COpenNI2Sensor.h:369
mrpt::hwdrivers::COpenNI2Sensor::initialize
virtual void initialize()
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
Definition: COpenNI2Sensor.cpp:93
mrpt::hwdrivers::COpenNI2Sensor::isGrab3DPointsEnabled
bool isGrab3DPointsEnabled() const
Definition: COpenNI2Sensor.h:345
mrpt::hwdrivers::COpenNI2Sensor::setCameraParamsIntensity
void setCameraParamsIntensity(const mrpt::img::TCamera &p)
Definition: COpenNI2Sensor.h:308
mrpt::img::TCamera::ncols
uint32_t ncols
Camera resolution.
Definition: TCamera.h:41
mrpt::hwdrivers::COpenNI2Sensor::m_cameraParamsRGB
mrpt::img::TCamera m_cameraParamsRGB
Params for the RGB camera.
Definition: COpenNI2Sensor.h:366
mrpt::hwdrivers::COpenNI2Sensor::getNextObservation
void getNextObservation(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Definition: COpenNI2Sensor.cpp:285
mrpt::hwdrivers::COpenNI2Generic
An abstract class for accessing OpenNI2 compatible sensors.
Definition: COpenNI2Generic.h:26
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::hwdrivers::COpenNI2Sensor::setSerialToOpen
void setSerialToOpen(const unsigned serial)
Set the serial number of the device to open.
Definition: COpenNI2Sensor.h:236
DEFINE_GENERIC_SENSOR
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
Definition: CGenericSensor.h:314
mrpt::hwdrivers::COpenNI2Sensor::~COpenNI2Sensor
~COpenNI2Sensor()
Default ctor.
Definition: COpenNI2Sensor.cpp:81
p
GLfloat GLfloat p
Definition: glext.h:6305
mrpt::hwdrivers::COpenNI2Sensor::getRelativePoseIntensityWrtDepth
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
Definition: COpenNI2Sensor.h:329
mrpt::hwdrivers::COpenNI2Sensor::isGrabDepthEnabled
bool isGrabDepthEnabled() const
Definition: COpenNI2Sensor.h:339
mrpt::hwdrivers::COpenNI2Sensor::enableGrabRGB
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
Definition: COpenNI2Sensor.h:335
mrpt::gui::CDisplayWindow::Ptr
std::shared_ptr< CDisplayWindow > Ptr
Definition: CDisplayWindow.h:33
mrpt::hwdrivers::COpenNI2Sensor::m_preview_decim_counter_rgb
size_t m_preview_decim_counter_rgb
Definition: COpenNI2Sensor.h:361
mrpt::hwdrivers::COpenNI2Sensor::m_sensorPoseOnRobot
mrpt::poses::CPose3D m_sensorPoseOnRobot
Definition: COpenNI2Sensor.h:353
mrpt::hwdrivers::COpenNI2Sensor::getMaxRange
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
Definition: COpenNI2Sensor.h:296
mrpt::obs::CObservation3DRangeScan
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
Definition: CObservation3DRangeScan.h:224
mrpt::hwdrivers::COpenNI2Sensor::m_serial_number
int m_serial_number
Serial number of device to open.
Definition: COpenNI2Sensor.h:383
mrpt::hwdrivers::COpenNI2Sensor::setCameraParamsDepth
void setCameraParamsDepth(const mrpt::img::TCamera &p)
Definition: COpenNI2Sensor.h:318
mrpt::hwdrivers::COpenNI2Sensor::setSensorIDToOpen
void setSensorIDToOpen(const unsigned sensor_id)
Set the sensor_id of the device to open.
Definition: COpenNI2Sensor.h:245
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::hwdrivers::COpenNI2Sensor::m_maxRange
double m_maxRange
Sensor max range (meters)
Definition: COpenNI2Sensor.h:376
mrpt::img::TCamera::nrows
uint32_t nrows
Definition: TCamera.h:41
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
CGenericSensor.h
TEnumType.h
mrpt::hwdrivers::COpenNI2Sensor::m_relativePoseIntensityWRTDepth
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
Definition: COpenNI2Sensor.h:372
mrpt::hwdrivers::COpenNI2Sensor::enableGrab3DPoints
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
Definition: COpenNI2Sensor.h:341
mrpt::hwdrivers::COpenNI2Sensor::getCameraParamsDepth
const mrpt::img::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
Definition: COpenNI2Sensor.h:314
mrpt::img::TCamera
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:29
mrpt::hwdrivers::CGenericSensor
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
Definition: CGenericSensor.h:70
mrpt::hwdrivers::COpenNI2Sensor::m_user_device_number
int m_user_device_number
Number of device to open (0:first,...)
Definition: COpenNI2Sensor.h:380
mrpt::hwdrivers::COpenNI2Sensor::setPathForExternalImages
virtual void setPathForExternalImages(const std::string &directory)
Set the path where to save off-rawlog image files (this class DOES take into account this path).
Definition: COpenNI2Sensor.cpp:375
mrpt::hwdrivers::COpenNI2Sensor::setRelativePoseIntensityWrtDepth
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
Definition: COpenNI2Sensor.h:325
mrpt::hwdrivers::COpenNI2Sensor::rows
size_t rows() const
Get the row count in the camera images, loaded automatically upon camera open().
Definition: COpenNI2Sensor.h:299
mrpt::hwdrivers::COpenNI2Generic::m_grab_3D_points
bool m_grab_3D_points
Definition: COpenNI2Generic.h:163
mrpt::hwdrivers::COpenNI2Sensor::m_preview_window_decimation
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
Definition: COpenNI2Sensor.h:360
mrpt::hwdrivers::COpenNI2Generic::m_grab_depth
bool m_grab_depth
Definition: COpenNI2Generic.h:163
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::hwdrivers::COpenNI2Sensor::loadConfig_sensorSpecific
virtual void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
Loads specific configuration for the device from a given source of configuration parameters,...
Definition: COpenNI2Sensor.cpp:197
mrpt::hwdrivers::COpenNI2Sensor::m_preview_window
bool m_preview_window
Show preview window while grabbing.
Definition: COpenNI2Sensor.h:357
mrpt::hwdrivers::COpenNI2Sensor::enableGrabDepth
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
Definition: COpenNI2Sensor.h:338
mrpt::hwdrivers::COpenNI2Sensor::m_win_int
mrpt::gui::CDisplayWindow::Ptr m_win_int
Definition: COpenNI2Sensor.h:362
CDisplayWindow.h
mrpt::hwdrivers::COpenNI2Sensor
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
Definition: COpenNI2Sensor.h:219
mrpt::hwdrivers::COpenNI2Sensor::getCameraParamsIntensity
const mrpt::img::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
Definition: COpenNI2Sensor.h:304



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST