Main MRPT website > C++ reference for MRPT 1.9.9
CKinect.cpp
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 
10 #include "hwdrivers-precomp.h" // Precompiled headers
11 
12 #include <mrpt/hwdrivers/CKinect.h>
13 #include <mrpt/utils/CTimeLogger.h>
15 
16 // Universal include for all versions of OpenCV
17 #include <mrpt/otherlibs/do_opencv_includes.h>
18 
19 using namespace mrpt::hwdrivers;
20 using namespace mrpt::system;
21 using namespace mrpt::utils;
22 using namespace mrpt::math;
23 using namespace mrpt::obs;
24 using namespace mrpt::poses;
25 using namespace std;
26 
28 
29 // Whether to profile memory allocations:
30 //#define KINECT_PROFILE_MEM_ALLOC
31 
32 #if MRPT_HAS_KINECT_FREENECT
33 #if defined(__APPLE__)
34 #include <libfreenect/libfreenect.h>
35 #else
36 #include <libfreenect.h>
37 #endif
38 #else
39 #define KINECT_W 640
40 #define KINECT_H 480
41 #endif
42 
43 #if MRPT_HAS_KINECT_FREENECT
44 // Macros to convert the opaque pointers in the class header:
45 #define f_ctx reinterpret_cast<freenect_context*>(m_f_ctx)
46 #define f_ctx_ptr reinterpret_cast<freenect_context**>(&m_f_ctx)
47 #define f_dev reinterpret_cast<freenect_device*>(m_f_dev)
48 #define f_dev_ptr reinterpret_cast<freenect_device**>(&m_f_dev)
49 #endif // MRPT_HAS_KINECT_FREENECT
50 
51 #ifdef KINECT_PROFILE_MEM_ALLOC
52 mrpt::utils::CTimeLogger alloc_tim;
53 #endif
54 // int int a;
55 
57 {
58 #ifdef MRPT_KINECT_DEPTH_10BIT
59  const float k1 = 1.1863f;
60  const float k2 = 2842.5f;
61  const float k3 = 0.1236f;
62 
63  for (size_t i = 0; i < KINECT_RANGES_TABLE_LEN; i++)
64  m_range2meters[i] = k3 * tanf(i / k2 + k1);
65 
66 #else
67  for (size_t i = 0; i < KINECT_RANGES_TABLE_LEN; i++)
68  m_range2meters[i] = 1.0f / (i * (-0.0030711016) + 3.3309495161);
69 #endif
70 
71  // Minimum/Maximum range means error:
72  m_range2meters[0] = 0;
73  m_range2meters[KINECT_RANGES_TABLE_LEN - 1] = 0;
74 }
75 
76 /*-------------------------------------------------------------
77  ctor
78  -------------------------------------------------------------*/
80  : m_sensorPoseOnRobot(),
81  m_preview_window(false),
82  m_preview_window_decimation(1),
83  m_preview_decim_counter_range(0),
84  m_preview_decim_counter_rgb(0),
85 
86 #if MRPT_HAS_KINECT_FREENECT
87  m_f_ctx(nullptr), // The "freenect_context", or nullptr if closed
88  m_f_dev(nullptr), // The "freenect_device", or nullptr if closed
89  m_tim_latest_depth(0),
90  m_tim_latest_rgb(0),
91 #endif
92  m_relativePoseIntensityWRTDepth(
93  0, -0.02, 0, DEG2RAD(-90), DEG2RAD(0), DEG2RAD(-90)),
94  m_initial_tilt_angle(360),
95  m_user_device_number(0),
96  m_grab_image(true),
97  m_grab_depth(true),
98  m_grab_3D_points(true),
99  m_grab_IMU(true)
100 {
102 
103  // Get maximum range:
105  2]; // Recall: r[Max-1] means error.
106 
107  // Default label:
108  m_sensorLabel = "KINECT";
109 
110  // =========== Default params ===========
111  // ----- RGB -----
113  640; // By default set 640x480, on connect we'll update this.
114  m_cameraParamsRGB.nrows = 480;
115 
116  m_cameraParamsRGB.cx(328.94272028759258);
117  m_cameraParamsRGB.cy(267.48068171871557);
118  m_cameraParamsRGB.fx(529.2151);
119  m_cameraParamsRGB.fy(525.5639);
120 
121  m_cameraParamsRGB.dist.zeros();
122 
123  // ----- Depth -----
126 
127  m_cameraParamsDepth.cx(339.30781);
128  m_cameraParamsDepth.cy(242.7391);
129  m_cameraParamsDepth.fx(594.21434);
130  m_cameraParamsDepth.fy(591.04054);
131 
132  m_cameraParamsDepth.dist.zeros();
133 
134 #if !MRPT_HAS_KINECT
136  "MRPT was compiled without support for Kinect. Please, rebuild it.")
137 #endif
138 }
139 
140 /*-------------------------------------------------------------
141  dtor
142  -------------------------------------------------------------*/
143 CKinect::~CKinect() { this->close(); }
144 /** This method can or cannot be implemented in the derived class, depending on
145 * the need for it.
146 * \exception This method must throw an exception with a descriptive message if
147 * some critical error is found.
148 */
150 /** This method will be invoked at a minimum rate of "process_rate" (Hz)
151 * \exception This method must throw an exception with a descriptive message if
152 * some critical error is found.
153 */
155 {
156  bool thereIs, hwError;
157 
159  mrpt::make_aligned_shared<CObservation3DRangeScan>();
160  CObservationIMU::Ptr newObs_imu =
161  mrpt::make_aligned_shared<CObservationIMU>();
162 
163  getNextObservation(*newObs, *newObs_imu, thereIs, hwError);
164 
165  if (hwError)
166  {
167  m_state = ssError;
168  THROW_EXCEPTION("Couldn't communicate to the Kinect sensor!");
169  }
170 
171  if (thereIs)
172  {
173  m_state = ssWorking;
174 
175  vector<CSerializable::Ptr> objs;
177  objs.push_back(newObs);
178  if (m_grab_IMU) objs.push_back(newObs_imu);
179 
180  appendObservations(objs);
181  }
182 }
183 
184 /** Loads specific configuration for the device from a given source of
185 * configuration parameters, for example, an ".ini" file, loading from the
186 * section "[iniSection]" (see utils::CConfigFileBase and derived classes)
187 * \exception This method must throw an exception with a descriptive message if
188 * some critical parameter is missing or has an invalid value.
189 */
191  const mrpt::utils::CConfigFileBase& configSource,
192  const std::string& iniSection)
193 {
195  configSource.read_float(iniSection, "pose_x", 0),
196  configSource.read_float(iniSection, "pose_y", 0),
197  configSource.read_float(iniSection, "pose_z", 0),
198  DEG2RAD(configSource.read_float(iniSection, "pose_yaw", 0)),
199  DEG2RAD(configSource.read_float(iniSection, "pose_pitch", 0)),
200  DEG2RAD(configSource.read_float(iniSection, "pose_roll", 0)));
201 
203  configSource.read_bool(iniSection, "preview_window", m_preview_window);
204 
205  // "Stereo" calibration data:
206  // [<SECTION>_LEFT] // Depth
207  // ...
208  // [<SECTION>_RIGHT] // RGB
209  // ...
210  // [<SECTION>_LEFT2RIGHT_POSE]
211  // pose_quaternion = [x y z qr qx qy qz]
212 
213  const mrpt::poses::CPose3D twist(
214  0, 0, 0, DEG2RAD(-90), DEG2RAD(0), DEG2RAD(-90));
215 
217  sc.leftCamera = m_cameraParamsDepth; // Load default values so that if we
218  // fail to load from cfg at least we
219  // have some reasonable numbers.
221  sc.rightCameraPose =
223 
224  try
225  {
226  sc.loadFromConfigFile(iniSection, configSource);
227  }
228  catch (std::exception& e)
229  {
230  std::cout << "[CKinect::loadConfig_sensorSpecific] Warning: Ignoring "
231  "error loading calibration parameters:\n"
232  << e.what();
233  }
238 
239  // Id:
240  m_user_device_number = configSource.read_int(
241  iniSection, "device_number", m_user_device_number);
242 
243  m_grab_image =
244  configSource.read_bool(iniSection, "grab_image", m_grab_image);
245  m_grab_depth =
246  configSource.read_bool(iniSection, "grab_depth", m_grab_depth);
248  configSource.read_bool(iniSection, "grab_3D_points", m_grab_3D_points);
249  m_grab_IMU = configSource.read_bool(iniSection, "grab_IMU", m_grab_IMU);
250 
251  m_video_channel = configSource.read_enum<TVideoChannel>(
252  iniSection, "video_channel", m_video_channel);
253 
254  {
255  std::string s = configSource.read_string(
256  iniSection, "relativePoseIntensityWRTDepth", "");
258  }
259 
260  m_initial_tilt_angle = configSource.read_int(
261  iniSection, "initial_tilt_angle", m_initial_tilt_angle);
262 }
263 
264 bool CKinect::isOpen() const
265 {
266 #if MRPT_HAS_KINECT_FREENECT
267  return f_dev != nullptr;
268 #else
269  return false;
270 #endif
271 
272 #
273 }
274 
275 #if MRPT_HAS_KINECT_FREENECT
276 // ======== GLOBAL CALLBACK FUNCTIONS ========
277 void depth_cb(freenect_device* dev, void* v_depth, uint32_t timestamp)
278 {
279  const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
280 
281  uint16_t* depth = reinterpret_cast<uint16_t*>(v_depth);
282 
283  CKinect* obj = reinterpret_cast<CKinect*>(freenect_get_user(dev));
284 
285  // Update of the timestamps at the end:
286  std::lock_guard<std::mutex> lock(obj->internal_latest_obs_cs());
287  CObservation3DRangeScan& obs = obj->internal_latest_obs();
288 
289  obs.hasRangeImage = true;
290  obs.range_is_depth = true;
291 
292 #ifdef KINECT_PROFILE_MEM_ALLOC
293  alloc_tim.enter("depth_cb alloc");
294 #endif
295 
296  // This method will try to exploit memory pooling if possible:
297  obs.rangeImage_setSize(frMode.height, frMode.width);
298 
299 #ifdef KINECT_PROFILE_MEM_ALLOC
300  alloc_tim.leave("depth_cb alloc");
301 #endif
302 
303  const CKinect::TDepth2RangeArray& r2m = obj->getRawDepth2RangeConversion();
304  for (int r = 0; r < frMode.height; r++)
305  for (int c = 0; c < frMode.width; c++)
306  {
307  // For now, quickly save the depth as it comes from the sensor,
308  // it'll
309  // transformed later on in getNextObservation()
310  const uint16_t v = *depth++;
311  obs.rangeImage.coeffRef(r, c) = r2m[v & KINECT_RANGES_TABLE_MASK];
312  }
313  obj->internal_tim_latest_depth() = timestamp;
314 }
315 
316 void rgb_cb(freenect_device* dev, void* img_data, uint32_t timestamp)
317 {
318  CKinect* obj = reinterpret_cast<CKinect*>(freenect_get_user(dev));
319  const freenect_frame_mode frMode = freenect_get_current_video_mode(dev);
320 
321  // Update of the timestamps at the end:
322  std::lock_guard<std::mutex> lock(obj->internal_latest_obs_cs());
323  CObservation3DRangeScan& obs = obj->internal_latest_obs();
324 
325 #ifdef KINECT_PROFILE_MEM_ALLOC
326  alloc_tim.enter("depth_rgb loadFromMemoryBuffer");
327 #endif
328 
329  obs.hasIntensityImage = true;
330  if (obj->getVideoChannel() == CKinect::VIDEO_CHANNEL_RGB)
331  {
332  // Color image: We asked for Bayer data, so we can decode it outselves
333  // here
334  // and avoid having to reorder Green<->Red channels, as would be needed
335  // with
336  // the RGB image from freenect.
337  obs.intensityImageChannel =
339  obs.intensityImage.resize(
340  frMode.width, frMode.height, CH_RGB, true /* origin=top-left */);
341 
342 #if MRPT_HAS_OPENCV
343 #if MRPT_OPENCV_VERSION_NUM < 0x200
344  // Version for VERY OLD OpenCV versions:
345  IplImage* src_img_bayer =
346  cvCreateImageHeader(cvSize(frMode.width, frMode.height), 8, 1);
347  src_img_bayer->imageDataOrigin = reinterpret_cast<char*>(img_data);
348  src_img_bayer->imageData = src_img_bayer->imageDataOrigin;
349  src_img_bayer->widthStep = frMode.width;
350 
351  IplImage* dst_img_RGB = obs.intensityImage.getAs<IplImage>();
352 
353  // Decode Bayer image:
354  cvCvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
355 
356 #else
357  // Version for modern OpenCV:
358  const cv::Mat src_img_bayer(
359  frMode.height, frMode.width, CV_8UC1, img_data, frMode.width);
360 
361  cv::Mat dst_img_RGB = cv::cvarrToMat(
362  obs.intensityImage.getAs<IplImage>(),
363  false /* dont copy buffers */);
364 
365  // Decode Bayer image:
366  cv::cvtColor(src_img_bayer, dst_img_RGB, CV_BayerGB2BGR);
367 #endif
368 #else
369  THROW_EXCEPTION("Need building with OpenCV!")
370 #endif
371  }
372  else
373  {
374  // IR data: grayscale 8bit
375  obs.intensityImageChannel = mrpt::obs::CObservation3DRangeScan::CH_IR;
376  obs.intensityImage.loadFromMemoryBuffer(
377  frMode.width, frMode.height,
378  false, // Color image?
379  reinterpret_cast<unsigned char*>(img_data));
380  }
381 
382 // obs.intensityImage.setChannelsOrder_RGB();
383 
384 #ifdef KINECT_PROFILE_MEM_ALLOC
385  alloc_tim.leave("depth_rgb loadFromMemoryBuffer");
386 #endif
387 
388  obj->internal_tim_latest_rgb() = timestamp;
389 }
390 // ======== END OF GLOBAL CALLBACK FUNCTIONS ========
391 #endif // MRPT_HAS_KINECT_FREENECT
392 
394 {
395  if (isOpen()) close();
396 
397  // Alloc memory, if this is the first time:
398  m_buf_depth.resize(640 * 480 * 3); // We'll resize this below if needed
399  m_buf_rgb.resize(640 * 480 * 3);
400 
401 #if MRPT_HAS_KINECT_FREENECT // ----> libfreenect
402  // Try to open the device:
403  if (freenect_init(f_ctx_ptr, nullptr) < 0)
404  THROW_EXCEPTION("freenect_init() failed")
405 
406  freenect_set_log_level(
407  f_ctx,
408 #ifdef _DEBUG
409  FREENECT_LOG_DEBUG
410 #else
411  FREENECT_LOG_WARNING
412 #endif
413  );
414 
415  int nr_devices = freenect_num_devices(f_ctx);
416  // printf("[CKinect] Number of devices found: %d\n", nr_devices);
417 
418  if (!nr_devices) THROW_EXCEPTION("No Kinect devices found.")
419 
420  // Open the given device number:
421  if (freenect_open_device(f_ctx, f_dev_ptr, m_user_device_number) < 0)
423  "Error opening Kinect sensor with index: %d", m_user_device_number)
424 
425  // Setup:
426  if (m_initial_tilt_angle != 360) // 360 means no motor command.
428  freenect_set_led(f_dev, LED_RED);
429  freenect_set_depth_callback(f_dev, depth_cb);
430  freenect_set_video_callback(f_dev, rgb_cb);
431 
432  // rgb or IR channel:
433  const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
434  FREENECT_RESOLUTION_MEDIUM,
436  ? FREENECT_VIDEO_IR_8BIT
437  : FREENECT_VIDEO_BAYER // FREENECT_VIDEO_RGB: Use Bayer instead so
438  // we can directly decode it here
439  );
440 
441  // Switch to that video mode:
442  if (freenect_set_video_mode(f_dev, desiredFrMode) < 0)
443  THROW_EXCEPTION("Error setting Kinect video mode.")
444 
445  // Get video mode:
446  const freenect_frame_mode frMode = freenect_get_current_video_mode(f_dev);
447 
448  // Realloc mem:
449  m_buf_depth.resize(frMode.width * frMode.height * 3);
450  m_buf_rgb.resize(frMode.width * frMode.height * 3);
451 
452  // Save resolution:
453  m_cameraParamsRGB.ncols = frMode.width;
454  m_cameraParamsRGB.nrows = frMode.height;
455 
456  m_cameraParamsDepth.ncols = frMode.width;
457  m_cameraParamsDepth.nrows = frMode.height;
458 
459  freenect_set_video_buffer(f_dev, &m_buf_rgb[0]);
460  freenect_set_depth_buffer(f_dev, &m_buf_depth[0]);
461 
462  freenect_set_depth_mode(
463  f_dev, freenect_find_depth_mode(
464  FREENECT_RESOLUTION_MEDIUM, FREENECT_DEPTH_10BIT));
465 
466  // Set user data = pointer to "this":
467  freenect_set_user(f_dev, this);
468 
469  if (freenect_start_depth(f_dev) < 0)
470  THROW_EXCEPTION("Error starting depth streaming.")
471 
472  if (freenect_start_video(f_dev) < 0)
473  THROW_EXCEPTION("Error starting video streaming.")
474 
475 #endif // MRPT_HAS_KINECT_FREENECT
476 }
477 
479 {
480 #if MRPT_HAS_KINECT_FREENECT
481  if (f_dev)
482  {
483  freenect_stop_depth(f_dev);
484  freenect_stop_video(f_dev);
485  freenect_close_device(f_dev);
486  }
487  m_f_dev = nullptr;
488 
489  if (f_ctx) freenect_shutdown(f_ctx);
490  m_f_ctx = nullptr;
491 #endif // MRPT_HAS_KINECT_FREENECT
492 }
493 
494 /** Changes the video channel to open (RGB or IR) - you can call this method
495  before start grabbing or in the middle of streaming and the video source will
496  change on the fly.
497  Default is RGB channel.
498 */
500 {
501 #if MRPT_HAS_KINECT_FREENECT
502  m_video_channel = vch;
503  if (!isOpen()) return; // Nothing else to do here.
504 
505  // rgb or IR channel:
506  freenect_stop_video(f_dev);
507 
508  // rgb or IR channel:
509  const freenect_frame_mode desiredFrMode = freenect_find_video_mode(
510  FREENECT_RESOLUTION_MEDIUM,
512  ? FREENECT_VIDEO_IR_8BIT
513  : FREENECT_VIDEO_BAYER // FREENECT_VIDEO_RGB: Use Bayer instead so
514  // we can directly decode it here
515  );
516 
517  // Switch to that video mode:
518  if (freenect_set_video_mode(f_dev, desiredFrMode) < 0)
519  THROW_EXCEPTION("Error setting Kinect video mode.")
520 
521  freenect_start_video(f_dev);
522 
523 #else
524  MRPT_UNUSED_PARAM(vch);
525 #endif // MRPT_HAS_KINECT_FREENECT
526 }
527 
528 /** The main data retrieving function, to be called after calling loadConfig()
529  * and initialize().
530  * \param out_obs The output retrieved observation (only if
531  * there_is_obs=true).
532  * \param there_is_obs If set to false, there was no new observation.
533  * \param hardware_error True on hardware/comms error.
534  *
535  * \sa doProcess
536  */
538  mrpt::obs::CObservation3DRangeScan& _out_obs, bool& there_is_obs,
539  bool& hardware_error)
540 {
541  there_is_obs = false;
542  hardware_error = false;
543 
544 #if MRPT_HAS_KINECT_FREENECT
545 
546  static const double max_wait_seconds = 1. / 25.;
547  static const TTimeStamp max_wait =
548  mrpt::system::secondsToTimestamp(max_wait_seconds);
549 
550  // Mark previous observation's timestamp as out-dated:
551  m_latest_obs.hasPoints3D = false;
552  m_latest_obs.hasRangeImage = false;
553  m_latest_obs.hasIntensityImage = false;
554  m_latest_obs.hasConfidenceImage = false;
555 
556  const TTimeStamp tim0 = mrpt::system::now();
557 
558  // Reset these timestamp flags so if they are !=0 in the next call we're
559  // sure they're new frames.
560  m_latest_obs_cs.lock();
561  m_tim_latest_rgb = 0;
562  m_tim_latest_depth = 0;
563  m_latest_obs_cs.unlock();
564 
565  while (freenect_process_events(f_ctx) >= 0 &&
566  mrpt::system::now() < (tim0 + max_wait))
567  {
568  // Got a new frame?
569  if ((!m_grab_image ||
570  m_tim_latest_rgb != 0) && // If we are NOT grabbing RGB or we are
571  // and there's a new frame...
572  (!m_grab_depth ||
573  m_tim_latest_depth != 0) // If we are NOT grabbing Depth or we are
574  // and there's a new frame...
575  )
576  {
577  // Approx: 0.5ms delay between depth frame (first) and RGB frame
578  // (second).
579  // cout << "m_tim_latest_rgb: " << m_tim_latest_rgb << "
580  // m_tim_latest_depth: "<< m_tim_latest_depth <<endl;
581  there_is_obs = true;
582  break;
583  }
584  }
585 
586  // Handle the case when there is NOT depth frames (if there's something very
587  // close blocking the IR sensor) but we have RGB:
588  if ((m_grab_image && m_tim_latest_rgb != 0) &&
589  (m_grab_depth && m_tim_latest_depth == 0))
590  {
591  // Mark the entire range data as invalid:
592  m_latest_obs.hasRangeImage = true;
593  m_latest_obs.range_is_depth = true;
594 
595  m_latest_obs_cs.lock(); // Important: if system is running slow, etc.
596  // we cannot tell for sure that the depth
597  // buffer is not beeing filled right now:
598  m_latest_obs.rangeImage.setSize(
600  m_latest_obs.rangeImage.setConstant(0); // "0" means: error in range
601  m_latest_obs_cs.unlock();
602  there_is_obs = true;
603  }
604 
605  if (!there_is_obs) return;
606 
607  // We DO have a fresh new observation:
608 
609  // Quick save the observation to the user's object:
610  m_latest_obs_cs.lock();
611  _out_obs.swap(m_latest_obs);
612  m_latest_obs_cs.unlock();
613 #endif
614 
615  // Set common data into observation:
616  // --------------------------------------
617  _out_obs.sensorLabel = m_sensorLabel;
618  _out_obs.timestamp = mrpt::system::now();
619  _out_obs.sensorPose = m_sensorPoseOnRobot;
621 
624 
625  // 3D point cloud:
626  if (_out_obs.hasRangeImage && m_grab_3D_points)
627  {
629 
630  if (!m_grab_depth)
631  {
632  _out_obs.hasRangeImage = false;
633  _out_obs.rangeImage.resize(0, 0);
634  }
635  }
636 
637  // preview in real-time?
638  if (m_preview_window)
639  {
640  if (_out_obs.hasRangeImage)
641  {
643  {
645  if (!m_win_range)
646  {
647  m_win_range =
648  mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
649  "Preview RANGE");
650  m_win_range->setPos(5, 5);
651  }
652 
653  // Normalize the image
655  img.setFromMatrix(_out_obs.rangeImage);
656  CMatrixFloat r =
657  _out_obs.rangeImage * float(1.0 / this->m_maxRange);
658  m_win_range->showImage(img);
659  }
660  }
661  if (_out_obs.hasIntensityImage)
662  {
664  {
666  if (!m_win_int)
667  {
668  m_win_int =
669  mrpt::make_aligned_shared<mrpt::gui::CDisplayWindow>(
670  "Preview INTENSITY");
671  m_win_int->setPos(300, 5);
672  }
673  m_win_int->showImage(_out_obs.intensityImage);
674  }
675  }
676  }
677  else
678  {
679  if (m_win_range) m_win_range.reset();
680  if (m_win_int) m_win_int.reset();
681  }
682 }
683 
684 /* -----------------------------------------------------
685  getNextObservation (with IMU)
686 ----------------------------------------------------- */
689  mrpt::obs::CObservationIMU& out_obs_imu, bool& there_is_obs,
690  bool& hardware_error)
691 {
692  // First, try getting the RGB+Depth data:
693  getNextObservation(out_obs, there_is_obs, hardware_error);
694 
695  // If successful, fill out the accelerometer data:
696  if (there_is_obs && this->m_grab_IMU)
697  {
698  double acc_x = 0, acc_y = 0, acc_z = 0; // In m/s^2
699  bool has_good_acc = false;
700 
701 #if MRPT_HAS_KINECT_FREENECT
702  {
703  freenect_update_tilt_state(f_dev);
704  freenect_raw_tilt_state* state = freenect_get_tilt_state(f_dev);
705  if (state)
706  {
707  has_good_acc = true;
708  double lx, ly, lz;
709  freenect_get_mks_accel(state, &lx, &ly, &lz);
710 
711  // Convert to a unified coordinate system:
712  // +x: forward
713  // +y: left
714  // +z: upward
715  acc_x = -lz;
716  acc_y = -lx;
717  acc_z = -ly;
718  }
719  }
720 #endif
721 
722  // Common part for any implementation:
723  if (has_good_acc)
724  {
725  out_obs_imu.sensorLabel = out_obs.sensorLabel + "_IMU";
726  out_obs_imu.timestamp = out_obs.timestamp;
727  out_obs_imu.sensorPose = out_obs.sensorPose;
728 
729  for (size_t i = 0; i < out_obs_imu.dataIsPresent.size(); i++)
730  out_obs_imu.dataIsPresent[i] = false;
731 
732  out_obs_imu.dataIsPresent[IMU_X_ACC] = true;
733  out_obs_imu.dataIsPresent[IMU_Y_ACC] = true;
734  out_obs_imu.dataIsPresent[IMU_Z_ACC] = true;
735 
736  out_obs_imu.rawMeasurements[IMU_X_ACC] = acc_x;
737  out_obs_imu.rawMeasurements[IMU_Y_ACC] = acc_y;
738  out_obs_imu.rawMeasurements[IMU_Z_ACC] = acc_z;
739  }
740  }
741 }
742 
743 /* -----------------------------------------------------
744  setPathForExternalImages
745 ----------------------------------------------------- */
747 {
748  MRPT_UNUSED_PARAM(directory);
749  // Ignore for now. It seems performance is better grabbing everything
750  // to a single big file than creating hundreds of smaller files per
751  // second...
752  return;
753 
754  // if (!mrpt::system::createDirectory( directory ))
755  // {
756  // THROW_EXCEPTION_FMT("Error: Cannot create the directory for
757  // externally
758  // saved images: %s",directory.c_str() )
759  // }
760  // m_path_for_external_images = directory;
761 }
762 
763 /** Change tilt angle \note Sensor must be open first. */
765 {
766  ASSERTMSG_(isOpen(), "Sensor must be open first")
767 
768 #if MRPT_HAS_KINECT_FREENECT
769  freenect_set_tilt_degs(f_dev, angle);
770 #else
771  MRPT_UNUSED_PARAM(angle);
772 #endif
773 }
774 
776 {
777  ASSERTMSG_(isOpen(), "Sensor must be open first")
778 
779 #if MRPT_KINECT_WITH_FREENECT
780  freenect_update_tilt_state(f_dev);
781  freenect_raw_tilt_state* ts = freenect_get_tilt_state(f_dev);
782  return freenect_get_tilt_degs(ts);
783 #else
784  return 0;
785 #endif
786 }
std::shared_ptr< CObservationIMU > Ptr
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:32
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
unsigned __int16 uint16_t
Definition: rptypes.h:44
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
Definition: math_frwds.h:30
TVideoChannel m_video_channel
The video channel to open: RGB or IR.
Definition: CKinect.h:534
float read_float(const std::string &section, const std::string &name, float defaultValue, bool failIfNotFound=false) const
mrpt::utils::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:118
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
std::string m_sensorLabel
See CGenericSensor.
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
#define THROW_EXCEPTION(msg)
void project3DPointsFromDepthImage(const bool PROJ3D_USE_LUT=true)
This method is equivalent to project3DPointsFromDepthImageInto() storing the projected 3D points (wit...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:176
void setTiltAngleDegrees(double angle)
Change tilt angle.
Definition: CKinect.cpp:764
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
std::shared_ptr< CObservation3DRangeScan > Ptr
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:76
Contains classes for various device interfaces.
std::string read_string(const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:3600
y-axis acceleration (local/vehicle frame) (m/sec2)
STL namespace.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
z-axis acceleration (local/vehicle frame) (m/sec2)
GLdouble s
Definition: glext.h:3676
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
GLsizei GLsizei GLuint * obj
Definition: glext.h:4070
#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:478
std::vector< uint8_t > m_buf_rgb
Definition: CKinect.h:538
#define KINECT_RANGES_TABLE_MASK
Definition: CKinect.h:32
Structure to hold the parameters of a pinhole stereo camera model.
Definition: TStereoCamera.h:25
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
mrpt::utils::TCamera cameraParams
Projection parameters of the depth camera.
void calculate_range2meters()
Compute m_range2meters at construction.
Definition: CKinect.cpp:56
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:178
int read_int(const std::string &section, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void fromString(const std::string &s)
Set the current object value from a string generated by &#39;asString&#39; (eg: "[x y z yaw pitch roll]"...
Definition: CPose3D.h:627
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:180
A class for grabing "range images", intensity images (either RGB or IR) and other information from an...
Definition: CKinect.h:268
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
const GLubyte * c
Definition: glext.h:6313
GLint GLvoid * img
Definition: glext.h:3763
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 swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
#define CH_RGB
Definition: CImage.h:43
TDepth2RangeArray m_range2meters
The table raw depth -> range in meters.
Definition: CKinect.h:540
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
This namespace contains representation of robot actions and observations.
uint32_t ncols
Camera resolution.
Definition: TCamera.h:54
bool hasRangeImage
true means the field rangeImage contains valid data
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:48
#define DEG2RAD
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
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:174
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
ENUMTYPE read_enum(const std::string &section, const std::string &name, const ENUMTYPE &defaultValue, bool failIfNotFound=false) const
Reads an "enum" value, where the value in the config file can be either a numerical value or the symb...
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
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
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:60
const GLdouble * v
Definition: glext.h:3678
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:58
void loadFromConfigFile(const std::string &section, const mrpt::utils::CConfigFileBase &cfg)
Load all the params from a config source, in the same format that used in saveToConfigFile().
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
size_t m_preview_decim_counter_range
Definition: CKinect.h:498
mrpt::math::CArrayDouble< 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
Definition: TCamera.h:60
mrpt::poses::CPose3D sensorPose
The pose of the sensor on the robot.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
TCamera leftCamera
Intrinsic and distortion parameters of the left and right cameras.
Definition: TStereoCamera.h:30
mrpt::poses::CPose3D m_relativePoseIntensityWRTDepth
See mrpt::obs::CObservation3DRangeScan for a diagram of this pose.
Definition: CKinect.h:518
bool hasIntensityImage
true means the field intensityImage contains valid data
uint32_t nrows
Definition: TCamera.h:54
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
Definition: CPose3D.cpp:248
bool isOpen() const
Whether there is a working connection to the sensor.
Definition: CKinect.cpp:264
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
Definition: CTimeLogger.h:45
double leave(const char *func_name)
End of a named section.
Definition: CTimeLogger.h:123
bool m_preview_window
Show preview window while grabbing.
Definition: CKinect.h:495
std::vector< uint8_t > m_buf_depth
Temporary buffers for image grabbing.
Definition: CKinect.h:538
mrpt::system::TTimeStamp secondsToTimestamp(const double nSeconds)
Transform a time interval (in seconds) into TTimeStamp (e.g.
Definition: datetime.cpp:223
mrpt::utils::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
unsigned __int32 uint32_t
Definition: rptypes.h:47
void enter(const char *func_name)
Start of a named section.
Definition: CTimeLogger.h:117
#define ASSERTMSG_(f, __ERROR_MSG)
x-axis acceleration (local/vehicle frame) (m/sec2)
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
Grayscale or RGB visible channel of the camera sensor.
vector_bool dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
mrpt::poses::CPose3DQuat rightCameraPose
Pose of the right camera with respect to the coordinate origin of the left camera.
Definition: TStereoCamera.h:33
void appendObservations(const std::vector< mrpt::utils::CSerializable::Ptr > &obj)
This method must be called by derived classes to enqueue a new observation in the list to be returned...
TVideoChannel
RGB or IR video channel identifiers.
Definition: CKinect.h:277
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