MRPT  2.0.0
CKinect.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 
16 
17 // MRPT implements a common interface to Kinect disregarding the
18 // actual underlying library. These macros defined in "mrpt/config.h"
19 // let us know which library is actually used:
20 // - [DEPRECATED AS OF MRPT 1.3.0] MRPT_HAS_KINECT_CL_NUI = 0 or 1
21 // - MRPT_HAS_KINECT_FREENECT = 0 or 1
22 
23 // Depth of Kinect ranges:
24 #if MRPT_HAS_KINECT_FREENECT
25 #define MRPT_KINECT_DEPTH_10BIT
26 #define KINECT_RANGES_TABLE_LEN 1024
27 #define KINECT_RANGES_TABLE_MASK 0x03FF
28 #else // MRPT_HAS_KINECT_CL_NUI or none:
29 #define MRPT_KINECT_DEPTH_11BIT
30 #define KINECT_RANGES_TABLE_LEN 2048
31 #define KINECT_RANGES_TABLE_MASK 0x07FF
32 #endif
33 
34 namespace mrpt::hwdrivers
35 {
36 /** A class for grabing "range images", intensity images (either RGB or IR) and
37  *other information from an Xbox Kinect sensor.
38  * To use Kinect for Windows or ASUS/Primesense RGBD cameras, use the class
39  *COpenNI2.
40  *
41  * <h2>Configuration and usage:</h2> <hr>
42  * Data is returned as observations of type mrpt::obs::CObservation3DRangeScan
43  *(and mrpt::obs::CObservationIMU for accelerometers data).
44  * See those classes for documentation on their fields.
45  *
46  * As with any other CGenericSensor class, the normal sequence of methods to be
47  *called is:
48  * - CGenericSensor::loadConfig() - Or calls to the individual setXXX() to
49  *configure the sensor parameters.
50  * - CKinect::initialize() - to start the communication with the sensor.
51  * - call CKinect::getNextObservation() for getting the data.
52  *
53  * <h2>Calibration parameters</h2><hr>
54  * For an accurate transformation of depth images to 3D points, you'll have to
55  *calibrate your Kinect, and supply
56  * the following <b>threee pieces of information</b> (default calibration
57  *data will be used otherwise, but they'll be not optimal for all sensors!):
58  * - Camera parameters for the RGB camera. See
59  *CKinect::setCameraParamsIntensity()
60  * - Camera parameters for the depth camera. See
61  *CKinect::setCameraParamsDepth()
62  * - The 3D relative pose of the two cameras. See
63  *CKinect::setRelativePoseIntensityWrtDepth()
64  *
65  * See https://www.mrpt.org/Kinect_calibration for a procedure to calibrate
66  *Kinect sensors with an interactive GUI program.
67  *
68  * <h2>Coordinates convention</h2><hr>
69  * The origin of coordinates is the focal point of the depth camera, with the
70  *axes oriented as in the
71  * diagram shown in mrpt::obs::CObservation3DRangeScan. Notice in that
72  *picture that the RGB camera is
73  * assumed to have axes as usual in computer vision, which differ from those
74  *for the depth camera.
75  *
76  * The X,Y,Z axes used to report the data from accelerometers coincide with
77  *those of the depth camera
78  * (e.g. the camera standing on a table would have an ACC_Z=-9.8m/s2).
79  *
80  * Notice however that, for consistency with stereo cameras, when loading the
81  *calibration parameters from
82  * a configuration file, the left-to-right pose increment is expected as if
83  *both RGB & IR cameras had
84  * their +Z axes pointing forward, +X to the right, +Y downwards (just like
85  *it's the standard in stereo cameras
86  * and in computer vision literature). In other words: the pose stored in
87  *this class uses a different
88  * axes convention for the depth camera than in a stereo camera, so when a
89  *pose L2R is loaded from a calibration file
90  * it's actually converted like:
91  *
92  * L2R(this class convention) = CPose3D(0,0,0,-90deg,0deg,-90deg) (+)
93  *L2R(in the config file)
94  *
95  *
96  * <h2>Some general comments</h2><hr>
97  * - Depth is grabbed in 10bit depth, and a range N it's converted to
98  *meters
99  *as: range(m) = 0.1236 * tan(N/2842.5 + 1.1863)
100  * - This sensor can be also used from within rawlog-grabber to grab
101  *datasets
102  *within a robot with more sensors.
103  * - There is no built-in threading support, so if you use this class
104  *manually
105  *(not with-in rawlog-grabber),
106  * the ideal would be to create a thread and continuously request data
107  *from
108  *that thread (see mrpt::system::createThread ).
109  * - The intensity channel default to the RGB images, but it can be changed
110  *with setVideoChannel() to read the IR camera images (useful for calibrating).
111  * - There is a built-in support for an optional preview of the data on a
112  *window, so you don't need to even worry on creating a window to show them.
113  * - This class relies on an embedded version of libfreenect (you do NOT
114  *need
115  *to install it in your system). Thanks guys for the great job!
116  *
117  * <h2>Converting to 3D point cloud </h2><hr>
118  * You can convert the 3D observation into a 3D point cloud with this piece
119  *of code:
120  *
121  * \code
122  * mrpt::obs::CObservation3DRangeScan obs3D;
123  * mrpt::maps::CColouredPointsMap pntsMap;
124  * pntsMap.colorScheme.scheme = CColouredPointsMap::cmFromIntensityImage;
125  * pntsMap.loadFromRangeScan(obs3D);
126  * \endcode
127  *
128  * Then the point cloud mrpt::maps::CColouredPointsMap can be converted into
129  *an OpenGL object for
130  * rendering with mrpt::maps::CMetricMap::getAs3DObject() or alternatively
131  *with:
132  *
133  * \code
134  * mrpt::opengl::CPointCloudColoured::Ptr gl_points =
135  *mrpt::opengl::CPointCloudColoured::Create();
136  * gl_points->loadFromPointsMap(&pntsMap);
137  * \endcode
138  *
139  *
140  * <h2>Raw depth to range conversion</h2><hr>
141  * At construction, this class builds an internal array for converting raw 10
142  *or 11bit depths into ranges in meters.
143  * Users can read that array or modify it (if you have a better calibration,
144  *for example) by calling CKinect::getRawDepth2RangeConversion().
145  * If you replace it, remember to set the first and last entries (index 0 and
146  *KINECT_RANGES_TABLE_LEN-1) to zero, to indicate that those are invalid
147  *ranges.
148  *
149  * <table width="100%" >
150  * <tr>
151  * <td align="center" >
152  * <img src="kinect_depth2range_10bit.png" > <br>
153  * R(d) = k3 * tan(d/k2 + k1); <br>
154  * k1 = 1.1863, k2 = 2842.5, k3 = 0.1236 <br>
155  * </td>
156  * <td align="center" >
157  * </td>
158  * </tr>
159  * </table>
160  *
161  *
162  * <h2>Platform-specific comments</h2><hr>
163  * For more details, refer to <a href="http://openkinect.org/wiki/Main_Page"
164  *>libfreenect</a> documentation:
165  * - Linux: You'll need root privileges to access Kinect. Or, install
166  *<code>
167  *MRPT/scripts/51-kinect.rules </code> in <code>/etc/udev/rules.d/</code> to
168  *allow access to all users.
169  * - Windows:
170  * - Since MRPT 0.9.4 you'll only need to install <a
171  *href="http://sourceforge.net/projects/libusb-win32/files/libusb-win32-releases/"
172  *>libusb-win32</a>: download and extract the latest
173  *libusb-win32-bin-x.x.x.x.zip
174  * - To install the drivers, read this:
175  *http://openkinect.org/wiki/Getting_Started#Windows
176  * - MacOS: (write me!)
177  *
178  *
179  * <h2>Format of parameters for loading from a .ini file</h2><hr>
180  *
181  * \code
182  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
183  * -------------------------------------------------------
184  * [supplied_section_name]
185  * sensorLabel = KINECT // A text description
186  * preview_window = false // Show a window with a preview of the
187  *grabbed data in real-time
188  *
189  * device_number = 0 // Device index to open (0:first Kinect,
190  *1:second Kinect,...)
191  *
192  * grab_image = true // Grab the RGB image channel?
193  *(Default=true)
194  * grab_depth = true // Grab the depth channel? (Default=true)
195  * grab_3D_points = true // Grab the 3D point cloud? (Default=true)
196  *If disabled, points can be generated later on.
197  * grab_IMU = true // Grab the accelerometers? (Default=true)
198  *
199  * video_channel = VIDEO_CHANNEL_RGB // Optional. Can be:
200  *VIDEO_CHANNEL_RGB (default) or VIDEO_CHANNEL_IR
201  *
202  * pose_x=0 // Camera position in the robot (meters)
203  * pose_y=0
204  * pose_z=0
205  * pose_yaw=0 // Angles in degrees
206  * pose_pitch=0
207  * pose_roll=0
208  *
209  * // Optional: Set the initial tilt angle of Kinect: upon initialization,
210  *the motor is sent a command to
211  * // rotate to this angle (in degrees). Note: You must be aware
212  *of the tilt when interpreting the sensor readings.
213  * // If not present or set to "360", no motor command will be
214  *sent at start up.
215  * initial_tilt_angle = 0
216  *
217  * // Kinect sensor calibration:
218  * // See https://www.mrpt.org/Kinect_and_MRPT
219  *
220  * // Left/Depth camera
221  * [supplied_section_name_LEFT]
222  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
223  *section (it is not a separate device!)
224  *
225  * resolution = [640 488]
226  * cx = 314.649173
227  * cy = 240.160459
228  * fx = 572.882768
229  * fy = 542.739980
230  * dist = [-4.747169e-03 -4.357976e-03 0.000000e+00 0.000000e+00
231  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
232  *
233  * // Right/RGB camera
234  * [supplied_section_name_RIGHT]
235  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
236  *section (it is not a separate device!)
237  *
238  * resolution = [640 480]
239  * cx = 322.515987
240  * cy = 259.055966
241  * fx = 521.179233
242  * fy = 493.033034
243  * dist = [5.858325e-02 3.856792e-02 0.000000e+00 0.000000e+00
244  *0.000000e+00] // The order is: [K1 K2 T1 T2 K3]
245  *
246  * // Relative pose of the right camera wrt to the left camera:
247  * // This assumes that both camera frames are such that +Z points
248  * // forwards, and +X and +Y to the right and downwards.
249  * // For the actual coordinates employed in 3D observations, see figure in
250  *mrpt::obs::CObservation3DRangeScan
251  * [supplied_section_name_LEFT2RIGHT_POSE]
252  * rawlog-grabber-ignore = true // Instructs rawlog-grabber to ignore this
253  *section (it is not a separate device!)
254  *
255  * pose_quaternion = [0.025575 -0.000609 -0.001462 0.999987 0.002038
256  *0.004335 -0.001693]
257  *
258  * \endcode
259  *
260  * More references to read:
261  * - http://openkinect.org/wiki/Imaging_Information
262  * - http://nicolas.burrus.name/index.php/Research/KinectCalibration
263  * \ingroup mrpt_hwdrivers_grp
264  */
266 {
268 
269  public:
270  /** A type for an array that converts raw depth to ranges in millimeters. */
272 
273  /** RGB or IR video channel identifiers \sa setVideoChannel */
275  {
278  };
279 
280  /** Default ctor */
281  CKinect();
282  /** Default ctor */
283  ~CKinect() override;
284 
285  /** Initializes the 3D camera - should be invoked after calling loadConfig()
286  * or setting the different parameters with the set*() methods.
287  * \exception This method must throw an exception with a descriptive
288  * message if some critical error is found.
289  */
290  void initialize() override;
291 
292  /** To be called at a high rate (>XX Hz), this method populates the
293  * internal buffer of received observations.
294  * This method is mainly intended for usage within rawlog-grabber or
295  * similar programs.
296  * For an alternative, see getNextObservation()
297  * \exception This method must throw an exception with a descriptive
298  * message if some critical error is found.
299  * \sa getNextObservation
300  */
301  void doProcess() override;
302 
303  /** The main data retrieving function, to be called after calling
304  * loadConfig() and initialize().
305  * \param out_obs The output retrieved observation (only if
306  * there_is_obs=true).
307  * \param there_is_obs If set to false, there was no new observation.
308  * \param hardware_error True on hardware/comms error.
309  *
310  * \sa doProcess
311  */
312  void getNextObservation(
313  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
314  bool& hardware_error);
315 
316  /** \overload
317  * \note This method also grabs data from the accelerometers, returning
318  * them in out_obs_imu
319  */
320  void getNextObservation(
322  mrpt::obs::CObservationIMU& out_obs_imu, bool& there_is_obs,
323  bool& hardware_error);
324 
325  /** Set the path where to save off-rawlog image files (this class DOES take
326  * into account this path).
327  * An empty string (the default value at construction) means to save
328  * images embedded in the rawlog, instead of on separate files.
329  * \exception std::exception If the directory doesn't exists and cannot be
330  * created.
331  */
332  void setPathForExternalImages(const std::string& directory) override;
333 
334  /** @name Sensor parameters (alternative to \a loadConfig ) and manual
335  control
336  @{ */
337 
338  /** Try to open the camera (set all the parameters before calling this) -
339  * users may also call initialize(), which in turn calls this method.
340  * Raises an exception upon error.
341  * \exception std::exception A textual description of the error.
342  */
343  void open();
344 
345  /** Whether there is a working connection to the sensor */
346  bool isOpen() const;
347 
348  /** Close the Connection to the sensor (not need to call it manually unless
349  * desired for some reason,
350  * since it's called at destructor) */
351  void close();
352 
353  /** Changes the video channel to open (RGB or IR) - you can call this method
354  before start grabbing or in the middle of streaming and the video source
355  will change on the fly.
356  Default is RGB channel. */
357  void setVideoChannel(const TVideoChannel vch);
358  /** Return the current video channel (RGB or IR) \sa setVideoChannel */
359  inline TVideoChannel getVideoChannel() const { return m_video_channel; }
360  /** Set the sensor index to open (if there're several sensors attached to
361  * the computer); default=0 -> the first one. */
362  inline void setDeviceIndexToOpen(int index)
363  {
364  m_user_device_number = index;
365  }
366  inline int getDeviceIndexToOpen() const { return m_user_device_number; }
367  /** Change tilt angle \note Sensor must be open first. */
368  void setTiltAngleDegrees(double angle);
369  double getTiltAngleDegrees();
370 
371  /** Default: disabled */
372  inline void enablePreviewRGB(bool enable = true)
373  {
374  m_preview_window = enable;
375  }
376  inline void disablePreviewRGB() { m_preview_window = false; }
377  inline bool isPreviewRGBEnabled() const { return m_preview_window; }
378  /** If preview is enabled, show only one image out of N (default: 1=show
379  * all) */
380  inline void setPreviewDecimation(size_t decimation_factor)
381  {
382  m_preview_window_decimation = decimation_factor;
383  }
384  inline size_t getPreviewDecimation() const
385  {
387  }
388 
389  /** Get the maximum range (meters) that can be read in the observation field
390  * "rangeImage" */
391  inline double getMaxRange() const { return m_maxRange; }
392  /** Get the row count in the camera images, loaded automatically upon camera
393  * open(). */
394  inline size_t rows() const { return m_cameraParamsRGB.nrows; }
395  /** Get the col count in the camera images, loaded automatically upon camera
396  * open(). */
397  inline size_t cols() const { return m_cameraParamsRGB.ncols; }
398  /** Get a const reference to the depth camera calibration parameters */
400  {
401  return m_cameraParamsRGB;
402  }
404  {
405  m_cameraParamsRGB = p;
406  }
407 
408  /** Get a const reference to the depth camera calibration parameters */
410  {
411  return m_cameraParamsDepth;
412  }
414  {
416  }
417 
418  /** Set the pose of the intensity camera wrt the depth camera \sa See
419  * mrpt::obs::CObservation3DRangeScan for a 3D diagram of this pose */
421  {
423  }
425  {
427  }
428 
429  /** Get a reference to the array that convert raw depth values (10 or 11
430  * bit) into ranges in mm, so it can be read or replaced by the user.
431  * If you replace it, remember to set the first and last entries (index 0
432  * and KINECT_RANGES_TABLE_LEN-1) to zero, to indicate that those are
433  * invalid ranges.
434  */
436  {
437  return m_range2meters;
438  }
440  {
441  return m_range2meters;
442  }
443 
444  /** Enable/disable the grabbing of the RGB channel */
445  inline void enableGrabRGB(bool enable = true) { m_grab_image = enable; }
446  inline bool isGrabRGBEnabled() const { return m_grab_image; }
447  /** Enable/disable the grabbing of the depth channel */
448  inline void enableGrabDepth(bool enable = true) { m_grab_depth = enable; }
449  inline bool isGrabDepthEnabled() const { return m_grab_depth; }
450  /** Enable/disable the grabbing of the inertial data */
451  inline void enableGrabAccelerometers(bool enable = true)
452  {
453  m_grab_IMU = enable;
454  }
455  inline bool isGrabAccelerometersEnabled() const { return m_grab_IMU; }
456  /** Enable/disable the grabbing of the 3D point clouds */
457  inline void enableGrab3DPoints(bool enable = true)
458  {
459  m_grab_3D_points = enable;
460  }
461  inline bool isGrab3DPointsEnabled() const { return m_grab_3D_points; }
462  /** @} */
463 
464 #if MRPT_HAS_KINECT_FREENECT
465  // Auxiliary getters/setters (we can't declare the libfreenect callback as
466  // friend since we
467  // want to avoid including the API headers here).
468  inline mrpt::obs::CObservation3DRangeScan& internal_latest_obs()
469  {
470  return m_latest_obs;
471  }
472  inline volatile uint32_t& internal_tim_latest_depth()
473  {
474  return m_tim_latest_depth;
475  }
476  inline volatile uint32_t& internal_tim_latest_rgb()
477  {
478  return m_tim_latest_rgb;
479  }
480  inline std::mutex& internal_latest_obs_cs() { return m_latest_obs_cs; }
481 #endif
482 
483  protected:
484  /** See the class documentation at the top for expected parameters */
486  const mrpt::config::CConfigFileBase& configSource,
487  const std::string& section) override;
488 
490 
491  /** Show preview window while grabbing */
492  bool m_preview_window{false};
493  /** If preview is enabled, only show 1 out of N images. */
497 
498 #if MRPT_HAS_KINECT_FREENECT
499  /** The "freenect_context", or nullptr if closed */
500  void* m_f_ctx{nullptr};
501  /** The "freenect_device", or nullptr if closed */
502  void* m_f_dev{nullptr};
503 
504  // Data fields for use with the callback function:
506  volatile uint32_t m_tim_latest_depth{0},
507  m_tim_latest_rgb{0}; // 0 = not updated
508  std::mutex m_latest_obs_cs;
509 #endif
510 
511  /** Params for the RGB camera */
513  /** Params for the Depth camera */
515  /** See mrpt::obs::CObservation3DRangeScan for a diagram of this pose */
517 
518  /** Set Kinect tilt to an initial deegre (it should be take in account in
519  * the sensor pose by the user) */
521 
522  /** Sensor max range (meters) */
523  double m_maxRange;
524 
525  /** Number of device to open (0:first,...) */
527 
528  /** Default: all true */
529  bool m_grab_image{true}, m_grab_depth{true}, m_grab_3D_points{true},
530  m_grab_IMU{true};
531 
532  /** The video channel to open: RGB or IR */
534 
535  private:
536  /** Temporary buffers for image grabbing. */
537  std::vector<uint8_t> m_buf_depth, m_buf_rgb;
538  /** The table raw depth -> range in meters */
540 
541  /** Compute m_range2meters at construction */
542  void calculate_range2meters();
543 
544 }; // End of class
545 } // namespace mrpt::hwdrivers
547 using namespace mrpt::hwdrivers;
548 MRPT_FILL_ENUM_MEMBER(CKinect, VIDEO_CHANNEL_RGB);
549 MRPT_FILL_ENUM_MEMBER(CKinect, VIDEO_CHANNEL_IR);
mrpt::img::TCamera m_cameraParamsRGB
Params for the RGB camera.
Definition: CKinect.h:512
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
size_t getPreviewDecimation() const
Definition: CKinect.h:384
mrpt::img::TCamera m_cameraParamsDepth
Params for the Depth camera.
Definition: CKinect.h:514
uint32_t nrows
Definition: TCamera.h:40
void setCameraParamsIntensity(const mrpt::img::TCamera &p)
Definition: CKinect.h:403
void doProcess() override
To be called at a high rate (>XX Hz), this method populates the internal buffer of received observati...
Definition: CKinect.cpp:140
void setPreviewDecimation(size_t decimation_factor)
If preview is enabled, show only one image out of N (default: 1=show all)
Definition: CKinect.h:380
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
Definition: CKinect.h:533
const mrpt::img::TCamera & getCameraParamsIntensity() const
Get a const reference to the depth camera calibration parameters.
Definition: CKinect.h:399
double getTiltAngleDegrees()
Definition: CKinect.cpp:733
mrpt::gui::CDisplayWindow::Ptr m_win_int
Definition: CKinect.h:496
size_t m_preview_window_decimation
If preview is enabled, only show 1 out of N images.
Definition: CKinect.h:494
void setTiltAngleDegrees(double angle)
Change tilt angle.
Definition: CKinect.cpp:724
void setRelativePoseIntensityWrtDepth(const mrpt::poses::CPose3D &p)
Set the pose of the intensity camera wrt the depth camera.
Definition: CKinect.h:420
void setDeviceIndexToOpen(int index)
Set the sensor index to open (if there&#39;re several sensors attached to the computer); default=0 -> the...
Definition: CKinect.h:362
double m_maxRange
Sensor max range (meters)
Definition: CKinect.h:523
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
Contains classes for various device interfaces.
bool isGrab3DPointsEnabled() const
Definition: CKinect.h:461
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
TVideoChannel getVideoChannel() const
Return the current video channel (RGB or IR)
Definition: CKinect.h:359
#define KINECT_RANGES_TABLE_LEN
Definition: CKinect.h:30
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section) override
See the class documentation at the top for expected parameters.
Definition: CKinect.cpp:175
void close()
Close the Connection to the sensor (not need to call it manually unless desired for some reason...
Definition: CKinect.cpp:447
std::vector< uint8_t > m_buf_rgb
Definition: CKinect.h:537
void calculate_range2meters()
Compute m_range2meters at construction.
Definition: CKinect.cpp:57
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
Definition: CKinect.h:265
This class allows loading and storing values and vectors of different types from a configuration text...
const TDepth2RangeArray & getRawDepth2RangeConversion() const
Definition: CKinect.h:439
void enableGrabDepth(bool enable=true)
Enable/disable the grabbing of the depth channel.
Definition: CKinect.h:448
void setCameraParamsDepth(const mrpt::img::TCamera &p)
Definition: CKinect.h:413
int m_initial_tilt_angle
Set Kinect tilt to an initial deegre (it should be take in account in the sensor pose by the user) ...
Definition: CKinect.h:520
void enablePreviewRGB(bool enable=true)
Default: disabled.
Definition: CKinect.h:372
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
Definition: CKinect.h:539
void initialize() override
Initializes the 3D camera - should be invoked after calling loadConfig() or setting the different par...
Definition: CKinect.cpp:135
void enableGrabAccelerometers(bool enable=true)
Enable/disable the grabbing of the inertial data.
Definition: CKinect.h:451
Parameters for the Brown-Conrady camera lens distortion model.
Definition: TCamera.h:26
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:78
void enableGrab3DPoints(bool enable=true)
Enable/disable the grabbing of the 3D point clouds.
Definition: CKinect.h:457
bool isPreviewRGBEnabled() const
Definition: CKinect.h:377
void setPathForExternalImages(const std::string &directory) override
Set the path where to save off-rawlog image files (this class DOES take into account this path)...
Definition: CKinect.cpp:706
MRPT_FILL_ENUM_MEMBER(CKinect, VIDEO_CHANNEL_RGB)
int m_user_device_number
Number of device to open (0:first,...)
Definition: CKinect.h:526
void setVideoChannel(const TVideoChannel vch)
Changes the video channel to open (RGB or IR) - you can call this method before start grabbing or in ...
Definition: CKinect.cpp:468
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: CKinect.cpp:504
CKinect()
Default ctor.
Definition: CKinect.cpp:82
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
~CKinect() override
Default ctor.
Definition: CKinect.cpp:129
bool isGrabDepthEnabled() const
Definition: CKinect.h:449
size_t m_preview_decim_counter_range
Definition: CKinect.h:495
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
size_t rows() const
Get the row count in the camera images, loaded automatically upon camera open().
Definition: CKinect.h:394
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
Definition: CKinect.h:516
TDepth2RangeArray & getRawDepth2RangeConversion()
Get a reference to the array that convert raw depth values (10 or 11 bit) into ranges in mm...
Definition: CKinect.h:435
bool isOpen() const
Whether there is a working connection to the sensor.
Definition: CKinect.cpp:249
const mrpt::poses::CPose3D & getRelativePoseIntensityWrtDepth() const
Definition: CKinect.h:424
bool m_preview_window
Show preview window while grabbing.
Definition: CKinect.h:492
int getDeviceIndexToOpen() const
Definition: CKinect.h:366
std::vector< uint8_t > m_buf_depth
Temporary buffers for image grabbing.
Definition: CKinect.h:537
const mrpt::img::TCamera & getCameraParamsDepth() const
Get a const reference to the depth camera calibration parameters.
Definition: CKinect.h:409
void enableGrabRGB(bool enable=true)
Enable/disable the grabbing of the RGB channel.
Definition: CKinect.h:445
bool isGrabRGBEnabled() const
Definition: CKinect.h:446
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:62
uint16_t[KINECT_RANGES_TABLE_LEN] TDepth2RangeArray
A type for an array that converts raw depth to ranges in millimeters.
Definition: CKinect.h:271
size_t cols() const
Get the col count in the camera images, loaded automatically upon camera open().
Definition: CKinect.h:397
double getMaxRange() const
Get the maximum range (meters) that can be read in the observation field "rangeImage".
Definition: CKinect.h:391
uint32_t ncols
Camera resolution.
Definition: TCamera.h:40
mrpt::gui::CDisplayWindow::Ptr m_win_range
Definition: CKinect.h:496
bool m_grab_image
Default: all true.
Definition: CKinect.h:529
size_t m_preview_decim_counter_rgb
Definition: CKinect.h:495
mrpt::poses::CPose3D m_sensorPoseOnRobot
Definition: CKinect.h:489
bool isGrabAccelerometersEnabled() const
Definition: CKinect.h:455
TVideoChannel
RGB or IR video channel identifiers.
Definition: CKinect.h:274
void open()
Try to open the camera (set all the parameters before calling this) - users may also call initialize(...
Definition: CKinect.cpp:362



Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020