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



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020