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



Page generated by Doxygen 1.9.8 for MRPT 1.4.0 SVN: at Thu Dec 14 16:41:50 UTC 2023