Main MRPT website > C++ reference for MRPT 1.9.9
COpenNI2Generic.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-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 
10 #include "hwdrivers-precomp.h" // Precompiled header
11 
15 
16 // Universal include for all versions of OpenCV
17 #include <mrpt/otherlibs/do_opencv_includes.h>
18 
19 #include <thread>
20 #include <mutex>
21 #include <atomic>
22 
23 #if MRPT_HAS_OPENNI2
24 
25 // This seems to be assumed by OpenNI.h and undefined for some reason in
26 // GCC/Ubuntu
27 #if !defined(_WIN32)
28 #define linux 1
29 #endif
30 
31 #include <OpenNI.h>
32 #include <PS1080.h>
33 #endif
34 
35 using namespace mrpt::hwdrivers;
36 using namespace mrpt::system;
37 using namespace mrpt::obs;
38 using namespace std;
39 
40 // Initialize static member
41 std::vector<std::shared_ptr<COpenNI2Generic::CDevice>> vDevices;
42 std::recursive_mutex vDevices_mx;
43 std::atomic<int> numInstances(0);
44 
45 #if MRPT_HAS_OPENNI2
46 bool setONI2StreamMode(
47  openni::VideoStream& stream, int w, int h, int fps,
48  openni::PixelFormat format);
49 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab = 0);
50 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2);
51 #endif // MRPT_HAS_OPENNI2
52 
54 
56 {
57  return numInstances; // get atomic
58 }
59 
60 /*-------------------------------------------------------------
61 ctor
62 -------------------------------------------------------------*/
64  : m_width(640),
65  m_height(480),
66  m_fps(30.0f),
67 #if MRPT_HAS_OPENNI2
68  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
69  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
70 #endif // MRPT_HAS_OPENNI2
71  m_verbose(false),
72  m_grab_image(true),
73  m_grab_depth(true),
74  m_grab_3D_points(true)
75 {
76  const char* sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
77  m_verbose = (sVerbose != nullptr) && atoi(sVerbose) != 0;
78  // Start automatically:
79  if (!this->start())
80  {
81 #if MRPT_HAS_OPENNI2
84  "After initialization:\n %s\n",
85  openni::OpenNI::getExtendedError()))
86 #endif
87  }
88 }
89 
91  int width, int height, float fps, bool open_streams_now)
92  : m_width(width),
93  m_height(height),
94  m_fps(fps),
95 #if MRPT_HAS_OPENNI2
96  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
97  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
98 #endif // MRPT_HAS_OPENNI2
99  m_verbose(false),
100  m_grab_image(true),
101  m_grab_depth(true),
102  m_grab_3D_points(true)
103 {
104  const char* sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
105  m_verbose = (sVerbose != nullptr) && atoi(sVerbose) != 0;
106  // Open?
107  if (open_streams_now)
108  {
109  if (!this->start())
110  {
111 #if MRPT_HAS_OPENNI2
113  mrpt::format(
114  "After initialization:\n %s\n",
115  openni::OpenNI::getExtendedError()))
116 #endif
117  }
118  }
119 }
120 
122 {
123 #if MRPT_HAS_OPENNI2
124  if (numInstances == 0)
125  {
126  if (openni::OpenNI::initialize() != openni::STATUS_OK)
127  {
128  return false;
129  }
130  else
131  {
132  std::cerr << "[" << __FUNCTION__ << "]" << std::endl
133  << " Initialized OpenNI2." << std::endl;
134  }
135  }
136  numInstances++;
137  return true;
138 #else
139  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
140 #endif // MRPT_HAS_OPENNI2
141 }
142 
143 /*-------------------------------------------------------------
144 dtor
145 -------------------------------------------------------------*/
147 {
148  numInstances--;
149  if (numInstances == 0)
150  {
151  kill();
152  }
153 }
154 
156 {
157  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
158  return vDevices.size();
159 }
160 void COpenNI2Generic::setVerbose(bool verbose) { m_verbose = verbose; }
161 bool COpenNI2Generic::isVerbose() const { return m_verbose; }
162 void COpenNI2Generic::showLog(const std::string& message) const
163 {
164  if (isVerbose() == false)
165  {
166  return;
167  }
168  std::cerr << message;
169 }
170 /** This method can or cannot be implemented in the derived class, depending on
171  * the need for it.
172  * \exception This method must throw an exception with a descriptive message if
173  * some critical error is found.
174  */
176 {
177 #if MRPT_HAS_OPENNI2
178  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
179  // Get devices list
180  openni::Array<openni::DeviceInfo> oni2InfoArray;
181  openni::OpenNI::enumerateDevices(&oni2InfoArray);
182 
183  const size_t numDevices = oni2InfoArray.getSize();
184  showLog(mrpt::format("[%s]\n", __FUNCTION__));
185  showLog(
186  mrpt::format(
187  " Get device list. %d devices connected.\n", (int)numDevices));
188 
189  // Search new devices.
190  std::set<int> newDevices;
191  for (unsigned i = 0; i < numDevices; i++)
192  {
193  const openni::DeviceInfo& info = oni2InfoArray[i];
194  showLog(mrpt::format(" Device[%d]\n", i));
195  showLog(oni2DevInfoStr(info, 3) + "\n");
196 
197  bool isExist = false;
198  for (unsigned int j = 0, j_end = vDevices.size();
199  j < j_end && isExist == false; ++j)
200  {
201  if (cmpONI2Device(info, vDevices[j]->getInfo()))
202  {
203  isExist = true;
204  }
205  }
206  if (isExist == false)
207  {
208  newDevices.insert(i);
209  }
210  }
211  // Add new devices to device list(static member).
212  for (std::set<int>::const_iterator it = newDevices.begin(),
213  it_end = newDevices.end();
214  it != it_end; ++it)
215  {
216  const openni::DeviceInfo& info = oni2InfoArray[*it];
217  CDevice::Ptr device = CDevice::create(
218  info, (openni::PixelFormat)m_rgb_format,
219  (openni::PixelFormat)m_depth_format, m_verbose);
220  vDevices.push_back(device);
221  {
222  unsigned int sn;
223  if (device->getSerialNumber(sn))
224  {
225  showLog(
226  mrpt::format("Device[%d]: serial number: `%u`\n", *it, sn));
227  }
228  }
229  }
230 
231  if (getNumDevices() == 0)
232  {
233  showLog(" No devices connected -> EXIT\n");
234  }
235  else
236  {
237  showLog(mrpt::format(" %d devices were found.\n", getNumDevices()));
238  }
239  return getNumDevices();
240 #else
241  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
242 #endif // MRPT_HAS_OPENNI2
243 }
244 
246 {
247  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
248 #if MRPT_HAS_OPENNI2
249  vDevices.clear();
250  openni::OpenNI::shutdown();
251 #else
252  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
253 #endif // MRPT_HAS_OPENNI2
254 }
255 
256 bool COpenNI2Generic::isOpen(const unsigned sensor_id) const
257 {
258 #if MRPT_HAS_OPENNI2
259  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
260  if ((int)sensor_id >= getNumDevices())
261  {
262  return false;
263  }
264  return vDevices[sensor_id]->isOpen();
265 #else
266  MRPT_UNUSED_PARAM(sensor_id);
267  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
268 #endif // MRPT_HAS_OPENNI2
269 }
270 
271 void COpenNI2Generic::open(unsigned sensor_id)
272 {
273 #if MRPT_HAS_OPENNI2
274  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
275  // Sensor index validation.
276  if (!getNumDevices())
277  {
278  THROW_EXCEPTION("No OpenNI2 devices found.");
279  }
280  if ((int)sensor_id >= getNumDevices())
281  {
283  "Sensor index is higher than the number of connected devices.")
284  }
285  showLog(mrpt::format("[%s]\n", __FUNCTION__));
286  showLog(mrpt::format(" open[%d] ...\n", sensor_id));
287 
288  if (isOpen(sensor_id))
289  {
290  showLog(
291  mrpt::format(" The sensor [%d] is already opened\n", sensor_id));
292  return;
293  }
294  if (m_verbose)
295  printf(
296  "[COpenNI2Generic] DBG: [%s] about to call vDevices[%d]->open()\n",
297  __FUNCTION__, sensor_id);
298  vDevices[sensor_id]->open(m_width, m_height, m_fps);
299  showLog(vDevices[sensor_id]->getLog() + "\n");
300  showLog(mrpt::format(" Device [%d] ", sensor_id));
301  if (vDevices[sensor_id]->isOpen())
302  {
303  showLog(" open successfully.\n");
304  }
305  else
306  {
307  showLog(" open failed.\n");
308  }
309  std::this_thread::sleep_for(1000ms); // Sleep
310 #else
311  MRPT_UNUSED_PARAM(sensor_id);
312  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
313 #endif // MRPT_HAS_OPENNI2
314 }
315 
317  const std::set<unsigned>& serial_required)
318 {
319 #if MRPT_HAS_OPENNI2
320  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
321  showLog(mrpt::format("[%s]\n", __FUNCTION__));
322  unsigned num_open_dev = 0;
323  for (unsigned sensor_id = 0; sensor_id < vDevices.size(); sensor_id++)
324  {
325  unsigned int serialNum;
326  if (vDevices[sensor_id]->getSerialNumber(serialNum) == false)
327  {
328  showLog(vDevices[sensor_id]->getLog());
329  continue;
330  }
331  if (m_verbose)
332  printf(
333  "[COpenNI2Generic::openDevicesBySerialNum] checking device "
334  "with serial '%d'\n",
335  serialNum);
336 
337  if (serial_required.find(serialNum) == serial_required.end())
338  {
339  vDevices[sensor_id]->close();
340  continue;
341  }
342  if (vDevices[sensor_id]->isOpen())
343  {
344  num_open_dev++;
345  continue;
346  }
347  int width = m_width;
348  int height = m_height;
349  if (m_verbose)
350  printf(
351  "[COpenNI2Generic] DBG: [%s] about to call "
352  "vDevices[%d]->open(%d,%d,%d)\n",
353  __FUNCTION__, sensor_id, width, height, (int)m_fps);
354  if (vDevices[sensor_id]->open(width, height, m_fps) == false)
355  {
356  showLog(vDevices[sensor_id]->getLog());
357  continue;
358  }
359  num_open_dev++;
360  if (m_verbose)
361  printf(
362  "[COpenNI2Generic] DBG: [%s] now has %d devices open\n",
363  __FUNCTION__, num_open_dev);
364  }
365  return num_open_dev;
366 #else
367  MRPT_UNUSED_PARAM(serial_required);
368  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
369 #endif // MRPT_HAS_OPENNI2
370 }
371 
373  const unsigned int SerialRequired)
374 {
375  std::set<unsigned> serial_required;
376  serial_required.insert(SerialRequired);
377  return openDevicesBySerialNum(serial_required);
378 }
379 
381  const unsigned int SerialRequired, int& sensor_id) const
382 {
383 #if MRPT_HAS_OPENNI2
384  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
385  for (size_t i = 0, i_end = vDevices.size(); i < i_end; ++i)
386  {
387  unsigned int sn;
388  if (vDevices[i]->getSerialNumber(sn) == false)
389  {
390  continue;
391  }
392  if (sn == SerialRequired)
393  {
394  sensor_id = (int)i;
395  return true;
396  }
397  }
398  return false;
399 #else
400  MRPT_UNUSED_PARAM(SerialRequired);
401  MRPT_UNUSED_PARAM(sensor_id);
402  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
403 #endif // MRPT_HAS_OPENNI2
404 }
405 
406 void COpenNI2Generic::close(unsigned sensor_id)
407 {
408 #if MRPT_HAS_OPENNI2
409  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
410  // Sensor index validation.
411  if (!getNumDevices())
412  {
413  THROW_EXCEPTION("No OpenNI2 devices found.");
414  }
415  if ((int)sensor_id >= getNumDevices())
416  {
418  "Sensor index is higher than the number of connected devices.")
419  }
420  vDevices[sensor_id]->close();
421 #else
422  MRPT_UNUSED_PARAM(sensor_id);
423  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
424 #endif // MRPT_HAS_OPENNI2
425 }
426 
427 /** The main data retrieving function, to be called after calling loadConfig()
428  * and initialize().
429  * \param out_obs The output retrieved observation (only if there_is_obs=true).
430  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
431  * \param there_is_obs If set to false, there was no new observation.
432  * \param hardware_error True on hardware/comms error.
433  * \param sensor_id The index of the sensor accessed.
434  *
435  */
437  mrpt::img::CImage& rgb_img, uint64_t& timestamp, bool& there_is_obs,
438  bool& hardware_error, unsigned sensor_id)
439 {
440 #if MRPT_HAS_OPENNI2
441  // Sensor index validation.
442  if (!getNumDevices())
443  {
444  THROW_EXCEPTION("No OpenNI2 devices found.");
445  }
446  if ((int)sensor_id >= getNumDevices())
447  {
449  "Sensor index is higher than the number of connected devices.")
450  }
451  if (vDevices[sensor_id]->getNextFrameRGB(
452  rgb_img, timestamp, there_is_obs, hardware_error) == false)
453  {
454  showLog(mrpt::format("[%s]\n", __FUNCTION__));
455  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
456  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
457  }
458 #else
459  MRPT_UNUSED_PARAM(rgb_img);
460  MRPT_UNUSED_PARAM(timestamp);
461  MRPT_UNUSED_PARAM(there_is_obs);
462  MRPT_UNUSED_PARAM(hardware_error);
463  MRPT_UNUSED_PARAM(sensor_id);
464  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
465 #endif // MRPT_HAS_OPENNI2
466 }
467 
468 /** The main data retrieving function, to be called after calling loadConfig()
469  * and initialize().
470  * \param depth_img The output retrieved depth image (only if
471  * there_is_obs=true).
472  * \param timestamp The timestamp of the capture (only if there_is_obs=true).
473  * \param there_is_obs If set to false, there was no new observation.
474  * \param hardware_error True on hardware/comms error.
475  * \param sensor_id The index of the sensor accessed.
476  *
477  */
479  mrpt::math::CMatrix& depth_img, uint64_t& timestamp, bool& there_is_obs,
480  bool& hardware_error, unsigned sensor_id)
481 {
482 #if MRPT_HAS_OPENNI2
483  // Sensor index validation.
484  if (getNumDevices() == 0)
485  {
486  THROW_EXCEPTION("No OpenNI2 devices found.");
487  }
488  if ((int)sensor_id >= getNumDevices())
489  {
491  "Sensor index is higher than the number of connected devices.")
492  }
493  if (vDevices[sensor_id]->getNextFrameD(
494  depth_img, timestamp, there_is_obs, hardware_error) == false)
495  {
496  showLog(mrpt::format("[%s]\n", __FUNCTION__));
497  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
498  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
499  }
500 #else
501  MRPT_UNUSED_PARAM(depth_img);
502  MRPT_UNUSED_PARAM(timestamp);
503  MRPT_UNUSED_PARAM(there_is_obs);
504  MRPT_UNUSED_PARAM(hardware_error);
505  MRPT_UNUSED_PARAM(sensor_id);
506  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
507 #endif // MRPT_HAS_OPENNI2
508 }
509 
510 /** The main data retrieving function, to be called after calling loadConfig()
511  * and initialize().
512  * \param out_obs The output retrieved observation (only if there_is_obs=true).
513  * \param there_is_obs If set to false, there was no new observation.
514  * \param hardware_error True on hardware/comms error.
515  * \param sensor_id The index of the sensor accessed.
516  *
517  */
519  mrpt::obs::CObservation3DRangeScan& out_obs, bool& there_is_obs,
520  bool& hardware_error, unsigned sensor_id)
521 {
522 #if MRPT_HAS_OPENNI2
523  // Sensor index validation.
524  if (!getNumDevices())
525  {
526  THROW_EXCEPTION("No OpenNI2 devices found.");
527  }
528  if ((int)sensor_id >= getNumDevices())
529  {
531  "Sensor index is higher than the number of connected devices.")
532  }
533  if (vDevices[sensor_id]->getNextFrameRGBD(
534  out_obs, there_is_obs, hardware_error) == false)
535  {
536  showLog(mrpt::format("[%s]\n", __FUNCTION__));
537  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
538  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
539  }
540 #else
541  MRPT_UNUSED_PARAM(out_obs);
542  MRPT_UNUSED_PARAM(there_is_obs);
543  MRPT_UNUSED_PARAM(hardware_error);
544  MRPT_UNUSED_PARAM(sensor_id);
545  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
546 #endif // MRPT_HAS_OPENNI2
547 }
548 
550  mrpt::img::TCamera& param, unsigned sensor_id) const
551 {
552 #if MRPT_HAS_OPENNI2
553  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
554  if (isOpen(sensor_id) == false)
555  {
556  return false;
557  }
558  return vDevices[sensor_id]->getCameraParam(CDevice::COLOR_STREAM, param);
559 #else
561  MRPT_UNUSED_PARAM(sensor_id);
562  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
563 #endif // MRPT_HAS_OPENNI2
564 }
565 
567  mrpt::img::TCamera& param, unsigned sensor_id) const
568 {
569 #if MRPT_HAS_OPENNI2
570  std::lock_guard<std::recursive_mutex> lock(vDevices_mx);
571  if (isOpen(sensor_id) == false)
572  {
573  return false;
574  }
575  return vDevices[sensor_id]->getCameraParam(CDevice::DEPTH_STREAM, param);
576 #else
578  MRPT_UNUSED_PARAM(sensor_id);
579  THROW_EXCEPTION("MRPT was built without OpenNI2 support");
580 #endif // MRPT_HAS_OPENNI2
581 }
582 
583 #if MRPT_HAS_OPENNI2
584 /*
585 void openni::VideoMode::setResolution()
586 Setter function for the resolution of this VideoMode. Application use of this
587 function is not recommended.
588 Instead, use SensorInfo::getSupportedVideoModes() to obtain a list of valid
589 video modes
590 
591 -- cited from OpenNI2 help. setResolution() is not recommended.
592 */
593 bool setONI2StreamMode(
594  openni::VideoStream& stream, int w, int h, int fps,
595  openni::PixelFormat format)
596 {
597  // std::cout << "[COpenNI2Generic] Ask mode: " << w << "x" << h << " " <<
598  // fps << " fps. format " << format << std::endl;
599  bool found = false;
600  const openni::Array<openni::VideoMode>& modes =
601  stream.getSensorInfo().getSupportedVideoModes();
602  for (int i = 0, i_end = modes.getSize(); i < i_end; ++i)
603  {
604  // if (m_verbose) std::cout << "[COpenNI2Generic] Mode: " <<
605  // modes[i].getResolutionX() << "x" << modes[i].getResolutionY() << " "
606  // << modes[i].getFps() << " fps. format " << modes[i].getPixelFormat()
607  // << std::endl;
608  if (modes[i].getResolutionX() != w)
609  {
610  continue;
611  }
612  if (modes[i].getResolutionY() != h)
613  {
614  continue;
615  }
616  if (modes[i].getFps() != fps)
617  {
618  continue;
619  }
620  if (modes[i].getPixelFormat() != format)
621  {
622  continue;
623  }
624  openni::Status rc = stream.setVideoMode(modes[i]);
625  if (rc != openni::STATUS_OK)
626  {
627  return false;
628  }
629  return true;
630  }
631  return false;
632 }
633 
634 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab)
635 {
636  std::stringstream sst;
637  std::string space;
638  for (int i = 0; i < tab; ++i)
639  {
640  space += " ";
641  }
642  sst << space << "name=" << info.getName() << std::endl;
643  sst << space << "uri=" << info.getUri() << std::endl;
644  sst << space << "vendor=" << info.getVendor() << std::endl;
645  sst << space << "product=" << info.getUsbProductId();
646  return sst.str();
647 }
648 
649 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2)
650 {
651  return (strcmp(i1.getUri(), i2.getUri()) == 0);
652 }
653 //
654 COpenNI2Generic::CDevice::CDevice(
655  const openni::DeviceInfo& info, openni::PixelFormat rgb,
656  openni::PixelFormat depth, bool verbose)
657  : m_info(info), m_mirror(true), m_verbose(verbose)
658 {
659  m_streams[COLOR_STREAM] =
660  CStream::create(m_device, openni::SENSOR_COLOR, rgb, m_log, m_verbose);
661  m_streams[IR_STREAM] =
662  CStream::create(m_device, openni::SENSOR_IR, rgb, m_log, m_verbose);
663  m_streams[DEPTH_STREAM] = CStream::create(
664  m_device, openni::SENSOR_DEPTH, depth, m_log, m_verbose);
665 }
666 
667 COpenNI2Generic::CDevice::~CDevice() { close(); }
668 bool COpenNI2Generic::CDevice::synchMirrorMode()
669 {
670  m_mirror = false;
671  // Check whether both stream support mirroring.
672  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
673  {
674  if (!m_streams[i]) continue;
675  bool mirror_support;
676  try
677  {
678  mirror_support = m_streams[i]->isMirrorSupported();
679  }
680  catch (std::logic_error& e)
681  {
682  throw(e);
683  }
684  if (mirror_support == false)
685  {
686  m_log << "[" << __FUNCTION__ << "]" << std::endl;
687  m_log << " openni::STREAM_PROPERTY_MIRRORING is not supported on "
688  << m_streams[i]->getName() << "." << std::endl;
689  m_log << " We assume this is MS Kinect and taken images are "
690  "inverted to right and left."
691  << std::endl;
692  // In this case, getMirroringEnabled() method always returns false.
693  // So we cannot confirm whether the images are inverted or not.
694  m_mirror = true;
695  break;
696  }
697  }
698  // Set both stream to same mirror mode.
699  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
700  {
701  if (!m_streams[i]) continue;
702  if (m_streams[i]->isMirrorSupported() == false)
703  {
704  break;
705  }
706  if (m_streams[i]->setMirror(m_mirror) == false)
707  {
708  return false;
709  }
710  }
711  return true;
712 }
713 
714 bool COpenNI2Generic::CDevice::startStreams()
715 {
716  MRPT_START
717  int num_ok = 0;
718  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
719  {
720  if (!m_streams[i]) continue;
721  if (m_verbose)
722  printf(" [%s] calling m_streams[%d]->start()\n", __FUNCTION__, i);
723  if (m_streams[i]->start() == false)
724  {
725  if (m_verbose)
726  printf(
727  " [%s] m_streams[%d]->start() returned FALSE!\n",
728  __FUNCTION__, i);
729  }
730  else
731  {
732  num_ok++;
733  }
734  if (m_verbose)
735  printf(
736  " [%s] m_streams[%d]->start() returned TRUE\n", __FUNCTION__,
737  i);
738  }
739  if (m_verbose)
740  printf(
741  " [COpenNI2Generic::CDevice::startStreams()] %d streams were "
742  "started.\n",
743  num_ok);
744  return num_ok > 0;
745  MRPT_END
746 }
747 
748 bool COpenNI2Generic::CDevice::isOpen() const
749 {
750  return (m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid()) ||
751  (m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid());
752 }
753 
754 void COpenNI2Generic::CDevice::close()
755 {
756  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
757  {
758  if (!m_streams[i]) continue;
759  m_streams[i]->destroy();
760  }
761  m_device.close();
762 }
763 
764 bool COpenNI2Generic::CDevice::open(int w, int h, int fps)
765 {
766  MRPT_START
767  if (m_verbose)
768  printf(
769  " [COpenNI2Generic::CDevice::open()] Called with w=%i h=%i "
770  "fps=%i\n",
771  w, h, fps);
772  clearLog();
773  close();
774  openni::Status rc = m_device.open(getInfo().getUri());
775  if (rc != openni::STATUS_OK)
776  {
777  m_log << "[" << __FUNCTION__ << "]" << std::endl
778  << " Failed to open device " << getInfo().getUri() << " "
779  << openni::OpenNI::getExtendedError() << std::endl;
780  return false;
781  }
782  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
783  {
784  if (!m_streams[i]) continue;
785  if (m_verbose)
786  printf(" [%s] calling m_streams[%d]->open()\n", __FUNCTION__, i);
787 
788  if (m_streams[i]->open(w, h, fps) == false)
789  {
790  if (m_verbose)
791  printf(
792  " [%s] m_streams[%d]->open() returned FALSE\n",
793  __FUNCTION__, i);
794  return false;
795  }
796  if (m_verbose)
797  printf(
798  " [%s] m_streams[%d]->open() returned OK\n", __FUNCTION__, i);
799  }
800 
801  if (synchMirrorMode() == false)
802  {
803  close();
804  return false;
805  }
806 
807  if (m_streams[DEPTH_STREAM])
808  {
809  int CloseRange = 0;
810  m_streams[DEPTH_STREAM]->setCloseRange(CloseRange);
811  m_log << " Close range: " << (CloseRange ? "On" : "Off") << std::endl;
812  }
813 
814  if (m_verbose)
815  printf(" DBG: checking if imageRegistrationMode is supported\n");
816  if (m_device.isImageRegistrationModeSupported(
817  openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) &&
818  m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid() &&
819  m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid())
820  {
821  // SEB
822  // if(m_device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF)
823  // != openni::STATUS_OK){
824  if (m_device.setImageRegistrationMode(
825  openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) != openni::STATUS_OK)
826  {
827  m_log << " setImageRegistrationMode() Failed:"
828  << openni::OpenNI::getExtendedError() << endl;
829  }
830  else
831  {
832  m_log << " setImageRegistrationMode() Success" << endl;
833  }
834  }
835  else
836  {
837  m_log << " Device doesn't do image registration!" << endl;
838  }
839 
840  if (0) // hasColor())
841  { // printf("DBG: hasColor() returned TRUE\n");
842  m_streams[COLOR_STREAM]->disableAutoExposure();
843  printf("DBG: returned from disableAutoExposure()\n");
844  }
845 
846  if (startStreams() == false)
847  {
848  close();
849  return false;
850  }
851  return true;
852  MRPT_END
853 }
854 
855 bool COpenNI2Generic::CDevice::getNextFrameRGB(
856  mrpt::img::CImage& img, uint64_t& timestamp, bool& there_is_obs,
857  bool& hardware_error)
858 {
859  MRPT_START
860  if (!hasColor())
861  {
862  THROW_EXCEPTION("This OpenNI2 device does not support color imaging");
863  }
864  openni::VideoFrameRef frame;
865  if (m_streams[COLOR_STREAM]->getFrame(
866  frame, timestamp, there_is_obs, hardware_error) == false)
867  {
868  return false;
869  }
870  copyFrame<openni::RGB888Pixel, mrpt::img::CImage>(frame, img);
871 
872  return true;
873  MRPT_END
874 }
875 
876 bool COpenNI2Generic::CDevice::getNextFrameD(
877  mrpt::math::CMatrix& img, uint64_t& timestamp, bool& there_is_obs,
878  bool& hardware_error)
879 {
880  MRPT_START
881  if (!hasDepth())
882  {
883  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging");
884  }
885  openni::VideoFrameRef frame;
886  if (m_streams[DEPTH_STREAM]->getFrame(
887  frame, timestamp, there_is_obs, hardware_error) == false)
888  {
889  return false;
890  }
891  copyFrame<openni::DepthPixel, mrpt::math::CMatrix>(frame, img);
892 
893  return true;
894  MRPT_END
895 }
896 
897 bool COpenNI2Generic::CDevice::getNextFrameRGBD(
898  mrpt::obs::CObservation3DRangeScan& obs, bool& there_is_obs,
899  bool& hardware_error)
900 {
901  MRPT_START
902  clearLog();
903  there_is_obs = false;
904  hardware_error = false;
905 
906  if (!hasColor())
907  {
908  THROW_EXCEPTION("This OpenNI2 device does not support color imaging");
909  }
910  if (!hasDepth())
911  {
912  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging");
913  }
914  // Read a frame (depth + rgb)
916  openni::VideoFrameRef frame[STREAM_TYPE_SIZE];
917  for (int i = 0; i < STREAM_TYPE_SIZE; ++i)
918  {
919  if (!m_streams[i] || !m_streams[i]->isValid()) continue;
920  if (m_streams[i]->getFrame(
921  frame[i], tm, there_is_obs, hardware_error) == false)
922  {
923  return false;
924  }
925  if (there_is_obs == false || hardware_error == true)
926  {
927  return false;
928  }
929  }
930 
931  const int width = frame[COLOR_STREAM].getWidth();
932  const int height = frame[COLOR_STREAM].getHeight();
933  if ((frame[DEPTH_STREAM].getWidth() != width) ||
934  (frame[DEPTH_STREAM].getHeight() != height))
935  {
936  m_log << "[" << __FUNCTION__ << "]" << std::endl
937  << " Both frames don't have the same size." << std::endl;
938  return false;
939  }
940  there_is_obs = true;
941  obs.hasConfidenceImage = false;
942  obs.hasIntensityImage = true;
943  obs.hasRangeImage = true;
944  obs.range_is_depth = true;
945  obs.hasPoints3D = false;
947  resize(obs, width, height);
948 
949  const char* data[STREAM_TYPE_SIZE] = {
950  (const char*)frame[COLOR_STREAM].getData(),
951  (const char*)frame[DEPTH_STREAM].getData()};
952  const int step[STREAM_TYPE_SIZE] = {frame[COLOR_STREAM].getStrideInBytes(),
953  frame[DEPTH_STREAM].getStrideInBytes()};
954 
955  for (int yc = 0; yc < height; ++yc)
956  {
957  const openni::RGB888Pixel* pRgb =
958  (const openni::RGB888Pixel*)data[COLOR_STREAM];
959  const openni::DepthPixel* pDepth =
960  (const openni::DepthPixel*)data[DEPTH_STREAM];
961  for (int xc = 0; xc < width; ++xc, ++pDepth, ++pRgb)
962  {
963  int x = xc;
964  if (isMirrorMode())
965  {
966  x = width - x - 1;
967  }
968  setPixel(*pRgb, obs.intensityImage, x, yc);
969  setPixel(*pDepth, obs.rangeImage, x, yc);
970  }
971  data[COLOR_STREAM] += step[COLOR_STREAM];
972  data[DEPTH_STREAM] += step[DEPTH_STREAM];
973  }
974 
975  return true;
976  MRPT_END
977 }
978 
979 COpenNI2Generic::CDevice::Ptr COpenNI2Generic::CDevice::create(
980  const openni::DeviceInfo& info, openni::PixelFormat rgb,
981  openni::PixelFormat depth, bool verbose)
982 {
983  return Ptr(new CDevice(info, rgb, depth, verbose));
984 }
985 
986 bool COpenNI2Generic::CDevice::getSerialNumber(std::string& sn)
987 {
988  clearLog();
989  openni::Status rc;
990  bool isOpened = isOpen();
991  if (isOpened == false)
992  {
993  rc = m_device.open(getInfo().getUri());
994  if (rc != openni::STATUS_OK)
995  {
996  m_log << "[" << __FUNCTION__ << "]" << std::endl
997  << " Failed to open device " << getInfo().getUri() << " "
998  << openni::OpenNI::getExtendedError() << std::endl;
999  return false;
1000  }
1001  }
1002  char serialNumber[16];
1003  rc = m_device.getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER, &serialNumber);
1004  if (rc != openni::STATUS_OK)
1005  {
1006  m_log << "[" << __FUNCTION__ << "]" << std::endl
1007  << " Failed to getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER) "
1008  << getInfo().getUri() << " " << openni::OpenNI::getExtendedError()
1009  << std::endl;
1010  return false;
1011  }
1012  sn = std::string(serialNumber);
1013  if (isOpened == false)
1014  {
1015  m_device.close();
1016  }
1017  return true;
1018 }
1019 
1020 bool COpenNI2Generic::CDevice::getSerialNumber(unsigned int& sn)
1021 {
1022  std::string str;
1023  if (getSerialNumber(str) == false)
1024  {
1025  return false;
1026  }
1027  std::stringstream sst;
1028  sst.str(str);
1029  sst >> sn;
1030  return !sst.fail();
1031 }
1032 //
1034  openni::Device& device, openni::SensorType type, openni::PixelFormat format,
1035  std::ostream& log, bool verbose)
1036  : m_log(log),
1037  m_device(device),
1038  m_strName("Unknown"),
1039  m_type(type),
1040  m_format(format),
1041  m_verbose(verbose)
1042 {
1043  if (m_type == openni::SENSOR_COLOR)
1044  {
1045  m_strName = "openni::SENSOR_COLOR";
1046  }
1047  else if (m_type == openni::SENSOR_DEPTH)
1048  {
1049  m_strName = "openni::SENSOR_DEPTH";
1050  }
1051  else if (m_type == openni::SENSOR_IR)
1052  {
1053  m_strName = "openni::SENSOR_IR";
1054  }
1055  else
1056  {
1057  m_log << "[" << __FUNCTION__ << "]" << std::endl
1058  << " Unknown SensorType -> " << m_type << std::endl;
1059  }
1060 }
1061 
1062 COpenNI2Generic::CDevice::CStream::~CStream() { destroy(); }
1063 bool COpenNI2Generic::CDevice::CStream::isMirrorSupported() const
1064 {
1065  if (isValid() == false)
1066  {
1067  THROW_EXCEPTION(getName() + " is not opened.");
1068  }
1069  return m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING);
1070 }
1071 
1072 bool COpenNI2Generic::CDevice::CStream::setMirror(bool flag)
1073 {
1074  if (isValid() == false)
1075  {
1076  m_log << "[" << __FUNCTION__ << "]" << std::endl
1077  << " " << getName() << " is not opened." << std::endl;
1078  return false;
1079  }
1080  if (m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING) ==
1081  false)
1082  {
1083  return false;
1084  }
1085  if (m_stream.setMirroringEnabled(flag) != openni::STATUS_OK)
1086  {
1087  m_log << "[" << __FUNCTION__ << "]" << std::endl
1088  << " setMirroringEnabled() failed: "
1089  << openni::OpenNI::getExtendedError() << std::endl;
1090  return false;
1091  }
1092  return true;
1093 }
1094 
1095 bool COpenNI2Generic::CDevice::CStream::isValid() const
1096 {
1097  return m_stream.isValid();
1098 }
1099 
1100 void COpenNI2Generic::CDevice::CStream::destroy() { m_stream.destroy(); }
1101 void COpenNI2Generic::CDevice::CStream::setCloseRange(int& value)
1102 {
1103  if (m_verbose)
1104  printf(
1105  " [CDevice::CStream::setCloseRange] entry with value=%d\n",
1106  value);
1107  m_stream.setProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, value);
1108  if (m_verbose)
1109  printf(
1110  " [CDevice::CStream::setCloseRange] returned from "
1111  "mstream.setProperty()\n");
1112  m_stream.getProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, &value);
1113  if (m_verbose)
1114  printf(
1115  " [CDevice::CStream::setCloseRange] returned from "
1116  "mstream.getProperty() ... value %d\n",
1117  value);
1118 }
1119 
1120 bool COpenNI2Generic::CDevice::CStream::open(int w, int h, int fps)
1121 {
1122  destroy();
1123  if (m_type != openni::SENSOR_COLOR && m_type != openni::SENSOR_DEPTH &&
1124  m_type != openni::SENSOR_IR)
1125  { // SEB added IR
1126  m_log << "[" << __FUNCTION__ << "]" << std::endl
1127  << " Unknown SensorType -> " << m_type << std::endl;
1128  return false;
1129  }
1130  if (m_verbose)
1131  printf(
1132  " [COpenNI2Generic::CDevice::CStream::open] opening sensor "
1133  "stream with m_type == %d\n",
1134  (int)m_type);
1135  openni::Status rc = openni::STATUS_OK;
1136  // if(m_type == openni::SENSOR_COLOR) {
1137  // m_type = openni::SENSOR_IR;
1138  // m_strName="openni::SENSOR_IR"; // SEB added
1139  // if (m_verbose) printf("DBG: changing type to SENSOR_IR
1140  //(%d)\n",(int)m_type);
1141  // } // added whole if stmt
1142  rc = m_stream.create(m_device, m_type);
1143  if (rc != openni::STATUS_OK)
1144  {
1145  m_log << "[" << __FUNCTION__ << "]" << std::endl
1146  << " Couldn't find sensor " << m_strName << ":"
1147  << openni::OpenNI::getExtendedError() << std::endl;
1148  if (m_type == openni::SENSOR_COLOR)
1149  {
1150  m_type = openni::SENSOR_IR;
1151  m_strName = "openni::SENSOR_IR"; // SEB added
1152  if (m_verbose)
1153  printf("DBG: changing type to SENSOR_IR (%d)\n", (int)m_type);
1154  rc = m_stream.create(m_device, m_type);
1155  } // SEB added whole if stmt
1156  else
1157  return false;
1158  }
1159  if (m_verbose) printf("returned OK from stream.create()\n");
1160  openni::VideoMode options = m_stream.getVideoMode();
1161  m_log << "[" << __FUNCTION__ << "]" << std::endl;
1162  m_log << " " << m_strName << std::endl;
1163  m_log << " " << mrpt::format(
1164  "Initial resolution (%d, %d) FPS %d Format %d",
1165  options.getResolutionX(), options.getResolutionY(),
1166  options.getFps(), options.getPixelFormat())
1167  << std::endl;
1168  if (m_verbose) printf("DBG: calling setONI2StreamMode()\n");
1169  if (setONI2StreamMode(m_stream, w, h, fps, m_format) == false)
1170  {
1171  m_log << " Can't find desired mode in the " << getName() << std::endl;
1172  destroy();
1173  return false;
1174  }
1175  if (m_verbose) printf("DBG: returned OK from setONI2StreamMode()\n");
1176  if (m_verbose) printf("DBG: calling stream.getVideoMode()\n");
1177  options = m_stream.getVideoMode();
1178  m_log << " " << mrpt::format(
1179  "-> (%d, %d) FPS %d Format %d",
1180  options.getResolutionX(), options.getResolutionY(),
1181  options.getFps(), options.getPixelFormat())
1182  << std::endl;
1183  if (m_verbose)
1184  printf(
1185  " [COpenNI2Generic::CDevice::CStream::open] returning TRUE\n");
1186  return true;
1187 }
1188 
1190 {
1191  if (isValid() == false)
1192  {
1193  m_log << "[" << __FUNCTION__ << "]" << std::endl
1194  << " " << getName() << " is not opened." << std::endl;
1195  return false;
1196  }
1197  if (m_stream.start() != openni::STATUS_OK)
1198  {
1199  m_log << "[" << __FUNCTION__ << "]" << std::endl
1200  << " Couldn't start " << getName()
1201  << " stream:" << openni::OpenNI::getExtendedError() << std::endl;
1202  this->destroy();
1203  return false;
1204  }
1205  return true;
1206 }
1207 
1208 COpenNI2Generic::CDevice::CStream::Ptr
1209  COpenNI2Generic::CDevice::CStream::create(
1210  openni::Device& device, openni::SensorType type,
1211  openni::PixelFormat format, std::ostream& log, bool verbose)
1212 {
1213  return Ptr(new CStream(device, type, format, log, verbose));
1214 }
1215 
1216 bool COpenNI2Generic::CDevice::CStream::getFrame(
1217  openni::VideoFrameRef& frame, uint64_t& timestamp, bool& there_is_obs,
1218  bool& hardware_error)
1219 {
1220  there_is_obs = false;
1221  hardware_error = false;
1222  if (isValid() == false)
1223  {
1224  return false;
1225  }
1226  openni::Status rc = m_stream.readFrame(&frame);
1227  if (rc != openni::STATUS_OK)
1228  {
1229  hardware_error = true;
1230  std::string message =
1231  mrpt::format("Failed to grab frame from %s", getName().c_str());
1232  THROW_EXCEPTION(message);
1233  }
1234  there_is_obs = true;
1235  timestamp = mrpt::system::getCurrentTime();
1236  return true;
1237 }
1238 
1239 #endif // MRPT_HAS_OPENNI2
mrpt::hwdrivers::COpenNI2Generic::getNumDevices
int getNumDevices() const
The number of available devices at initialization.
Definition: COpenNI2Generic.cpp:155
mrpt::hwdrivers::COpenNI2Generic::CDevice::DEPTH_STREAM
@ DEPTH_STREAM
Definition: COpenNI2Generic_CDevice.h:25
mrpt::hwdrivers::COpenNI2Generic::getDepthSensorParam
bool getDepthSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
Definition: COpenNI2Generic.cpp:566
format
GLenum GLsizei GLenum format
Definition: glext.h:3531
mrpt::hwdrivers::COpenNI2Generic::getNextFrameRGB
void getNextFrameRGB(mrpt::img::CImage &rgb_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Definition: COpenNI2Generic.cpp:436
mrpt::obs::CObservation3DRangeScan::range_is_depth
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
Definition: CObservation3DRangeScan.h:448
const_iterator
const Scalar * const_iterator
Definition: eigen_plugins.h:27
mrpt::obs::CObservation3DRangeScan::hasPoints3D
bool hasPoints3D
true means the field points3D contains valid data.
Definition: CObservation3DRangeScan.h:396
mrpt::hwdrivers::SensorType
SensorType
Definition: CPhidgetInterfaceKitProximitySensors.h:96
mrpt::hwdrivers::COpenNI2Generic::setVerbose
void setVerbose(bool verbose)
Definition: COpenNI2Generic.cpp:160
mrpt::utils::CStream
mrpt::io::CStream CStream
Definition: utils/CStream.h:7
COpenNI2Generic.h
start
GLuint start
Definition: glext.h:3528
mrpt::hwdrivers::COpenNI2Generic::COpenNI2Generic
COpenNI2Generic()
Default ctor (width=640, height=480, fps=30)
Definition: COpenNI2Generic.cpp:63
mrpt::hwdrivers::COpenNI2Generic::m_verbose
bool m_verbose
Definition: COpenNI2Generic.h:158
mrpt::hwdrivers::COpenNI2Generic::m_depth_format
int m_depth_format
Definition: COpenNI2Generic.h:157
COpenNI2Generic_CDevice.h
MRPT_UNUSED_PARAM
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186
mrpt::hwdrivers::COpenNI2Generic::getNextFrameRGBD
void getNextFrameRGBD(mrpt::obs::CObservation3DRangeScan &out_obs, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Definition: COpenNI2Generic.cpp:518
mrpt::hwdrivers
Contains classes for various device interfaces.
Definition: C2DRangeFinderAbstract.h:22
mrpt::hwdrivers::COpenNI2Generic::m_width
int m_width
The same options (width, height and fps) are set for all the sensors.
Definition: COpenNI2Generic.h:155
depth
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:3601
CObservation3DRangeScan.h
w
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:4178
type
GLuint GLuint GLsizei GLenum type
Definition: glext.h:3528
THROW_EXCEPTION
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:41
mrpt::obs
This namespace contains representation of robot actions and observations.
Definition: CParticleFilter.h:17
mrpt::hwdrivers::COpenNI2Generic::start
bool start()
Open all sensor streams (normally called automatically at constructor, no need to call it manually).
Definition: COpenNI2Generic.cpp:121
mrpt::obs::CObservation::timestamp
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
mrpt::system::TTimeStamp
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
Definition: datetime.h:31
mrpt::hwdrivers::COpenNI2Generic::kill
void kill()
Kill the OpenNI2 driver.
Definition: COpenNI2Generic.cpp:245
mrpt::hwdrivers::COpenNI2Generic::isOpen
bool isOpen(const unsigned sensor_id) const
Whether there is a working connection to the sensor.
Definition: COpenNI2Generic.cpp:256
mrpt::hwdrivers::COpenNI2Generic::openDeviceBySerial
unsigned int openDeviceBySerial(const unsigned int SerialRequired)
Open a RGBD device specified by its serial number.
Definition: COpenNI2Generic.cpp:372
mrpt::hwdrivers::COpenNI2Generic::getNumInstances
static int getNumInstances()
Get the number of OpenNI2 cameras currently open via COpenNI2Generic.
Definition: COpenNI2Generic.cpp:55
mrpt::hwdrivers::COpenNI2Generic::close
void close(unsigned sensor_id=0)
Close the connection to the sensor (no need to call it manually unless desired for some reason,...
Definition: COpenNI2Generic.cpp:406
mrpt::hwdrivers::COpenNI2Generic::getColorSensorParam
bool getColorSensorParam(mrpt::img::TCamera &param, unsigned sensor_id=0) const
Definition: COpenNI2Generic.cpp:549
data
GLsizei GLsizei GLenum GLenum const GLvoid * data
Definition: glext.h:3547
mrpt::obs::CObservation3DRangeScan::intensityImage
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
Definition: CObservation3DRangeScan.h:502
mrpt::math::CMatrix
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:24
Status
enum Status { eInsideTag=0, eOutsideTag } Status
Definition: xmlParser.cpp:804
mrpt::obs::CObservation3DRangeScan
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
Definition: CObservation3DRangeScan.h:224
MRPT_START
#define MRPT_START
Definition: exceptions.h:262
mrpt::format
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
mrpt::obs::CObservation3DRangeScan::hasIntensityImage
bool hasIntensityImage
true means the field intensityImage contains valid data
Definition: CObservation3DRangeScan.h:499
uint64_t
unsigned __int64 uint64_t
Definition: rptypes.h:50
mrpt::obs::CObservation3DRangeScan::hasRangeImage
bool hasRangeImage
true means the field rangeImage contains valid data
Definition: CObservation3DRangeScan.h:441
mrpt::img::TCamera
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:29
mrpt::hwdrivers::COpenNI2Generic::m_fps
float m_fps
Definition: COpenNI2Generic.h:156
mrpt::hwdrivers::COpenNI2Generic::getNextFrameD
void getNextFrameD(mrpt::math::CMatrix &depth_img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error, unsigned sensor_id=0)
The main data retrieving function, to be called after calling loadConfig() and initialize().
Definition: COpenNI2Generic.cpp:478
mrpt::hwdrivers::COpenNI2Generic::openDevicesBySerialNum
unsigned int openDevicesBySerialNum(const std::set< unsigned > &vSerialRequired)
Open a set of RGBD devices specified by their serial number.
Definition: COpenNI2Generic.cpp:316
height
GLenum GLsizei GLsizei height
Definition: glext.h:3554
getHeight
double getHeight(const TPolygon3D &p, const TPoint3D &c)
Definition: CPolyhedron.cpp:448
mrpt::img::CImage
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:130
mrpt::hwdrivers::COpenNI2Generic::m_height
int m_height
Definition: COpenNI2Generic.h:155
numInstances
std::atomic< int > numInstances(0)
mrpt::obs::CObservation3DRangeScan::hasConfidenceImage
bool hasConfidenceImage
true means the field confidenceImage contains valid data
Definition: CObservation3DRangeScan.h:511
mrpt::system::getCurrentTime
mrpt::system::TTimeStamp getCurrentTime()
Returns the current (UTC) system time.
Definition: datetime.cpp:74
mrpt::hwdrivers::COpenNI2Generic::getConnectedDevices
int getConnectedDevices()
Get a list of the connected OpenNI2 sensors.
Definition: COpenNI2Generic.cpp:175
mrpt::hwdrivers::COpenNI2Generic::isVerbose
bool isVerbose() const
Definition: COpenNI2Generic.cpp:161
mrpt::hwdrivers::COpenNI2Generic::CDevice::Ptr
std::shared_ptr< CDevice > Ptr
Definition: COpenNI2Generic_CDevice.h:21
mrpt::obs::CObservation3DRangeScan::rangeImage
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
Definition: CObservation3DRangeScan.h:444
img
GLint GLvoid * img
Definition: glext.h:3763
CTimeLogger.h
vDevices_mx
std::recursive_mutex vDevices_mx
Definition: COpenNI2Generic.cpp:42
mrpt::hwdrivers::COpenNI2Generic::getDeviceIDFromSerialNum
bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int &sensor_id) const
Get the ID of the device corresponding to 'SerialRequired'.
Definition: COpenNI2Generic.cpp:380
value
GLsizei const GLfloat * value
Definition: glext.h:4117
width
GLenum GLsizei width
Definition: glext.h:3531
MRPT_END
#define MRPT_END
Definition: exceptions.h:266
mrpt::hwdrivers::COpenNI2Generic::CDevice::COLOR_STREAM
@ COLOR_STREAM
Definition: COpenNI2Generic_CDevice.h:24
mrpt::hwdrivers::COpenNI2Generic::m_rgb_format
int m_rgb_format
Definition: COpenNI2Generic.h:157
mrpt::hwdrivers::COpenNI2Generic::open
void open(unsigned sensor_id=0)
Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - us...
Definition: COpenNI2Generic.cpp:271
string
GLsizei const GLchar ** string
Definition: glext.h:4101
vDevices
std::vector< std::shared_ptr< COpenNI2Generic::CDevice > > vDevices
Definition: COpenNI2Generic.cpp:41
mrpt::hwdrivers::COpenNI2Generic::showLog
void showLog(const std::string &message) const
Definition: COpenNI2Generic.cpp:162
mrpt::hwdrivers::COpenNI2Generic::~COpenNI2Generic
~COpenNI2Generic()
Default ctor.
Definition: COpenNI2Generic.cpp:146
x
GLenum GLint x
Definition: glext.h:3538
param
GLfloat param
Definition: glext.h:3831
mrpt::system
This namespace provides a OS-independent interface to many useful functions: filenames manipulation,...
Definition: math_frwds.h:25
hwdrivers-precomp.h



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST