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



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