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



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