Main MRPT website > C++ reference for MRPT 1.5.5
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 #include <mrpt/system/threads.h>
16 
17 // Universal include for all versions of OpenCV
18 #include <mrpt/otherlibs/do_opencv_includes.h>
19 
20 #if MRPT_HAS_OPENNI2
21 
22 // This seems to be assumed by OpenNI.h and undefined for some reason in GCC/Ubuntu
23 #if !defined(MRPT_OS_WINDOWS)
24 # define linux 1
25 #endif
26 
27 # include <OpenNI.h>
28 # include <PS1080.h>
29 #endif
30 
31 using namespace mrpt::hwdrivers;
32 using namespace mrpt::system;
33 using namespace mrpt::obs;
34 using namespace mrpt::synch;
35 using namespace std;
36 
37 
38 // Initialize static member
39 std::vector<stlplus::smart_ptr<COpenNI2Generic::CDevice> > COpenNI2Generic::vDevices = std::vector<stlplus::smart_ptr<COpenNI2Generic::CDevice> >();
41 
42 #if MRPT_HAS_OPENNI2
43 bool setONI2StreamMode(openni::VideoStream& stream, int w, int h, int fps, openni::PixelFormat format);
44 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab = 0);
45 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2);
46 #endif // MRPT_HAS_OPENNI2
47 
48 
50 /*-------------------------------------------------------------
51 ctor
52 -------------------------------------------------------------*/
54  m_width(640),
55  m_height(480),
56  m_fps(30.0f),
57 #if MRPT_HAS_OPENNI2
58  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
59  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
60 #endif // MRPT_HAS_OPENNI2
61  m_verbose(false),
62  m_grab_image(true),
63  m_grab_depth(true),
64  m_grab_3D_points(true)
65 {
66  const char * sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
67  m_verbose = (sVerbose!=NULL) && atoi(sVerbose)!=0;
68  // Start automatically:
69  if (!this->start()) {
70 #if MRPT_HAS_OPENNI2
71  THROW_EXCEPTION(mrpt::format("After initialization:\n %s\n", openni::OpenNI::getExtendedError()))
72 #endif
73  }
74 }
75 
76 COpenNI2Generic::COpenNI2Generic(int width, int height, float fps, bool open_streams_now ) :
77  m_width(width),
78  m_height(height),
79  m_fps(fps),
80 #if MRPT_HAS_OPENNI2
81  m_rgb_format(openni::PIXEL_FORMAT_RGB888),
82  m_depth_format(openni::PIXEL_FORMAT_DEPTH_1_MM),
83 #endif // MRPT_HAS_OPENNI2
84  m_verbose(false),
85  m_grab_image(true),
86  m_grab_depth(true),
87  m_grab_3D_points(true)
88 {
89  const char * sVerbose = getenv("MRPT_HWDRIVERS_VERBOSE");
90  m_verbose = (sVerbose!=NULL) && atoi(sVerbose)!=0;
91  // Open?
92  if (open_streams_now) {
93  if (!this->start()) {
94 #if MRPT_HAS_OPENNI2
95  THROW_EXCEPTION(mrpt::format("After initialization:\n %s\n", openni::OpenNI::getExtendedError()))
96 #endif
97  }
98  }
99 }
100 
102 {
103 #if MRPT_HAS_OPENNI2
104  if(numInstances == 0){
105  if(openni::OpenNI::initialize() != openni::STATUS_OK){
106  return false;
107  }else{
108  std::cerr << "[" << __FUNCTION__ << "]" << std::endl << " Initialized OpenNI2." << std::endl;
109  }
110  }
111  numInstances++;
112  return true;
113 #else
114  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
115 #endif // MRPT_HAS_OPENNI2
116 }
117 
118 /*-------------------------------------------------------------
119 dtor
120 -------------------------------------------------------------*/
122 {
123  numInstances--;
124  if(numInstances == 0){
125  kill();
126  }
127 }
128 
130  return vDevices.size();
131 }
132 
133 void COpenNI2Generic::setVerbose(bool verbose){
134  m_verbose = verbose;
135 }
136 
138  return m_verbose;
139 }
140 
141 void COpenNI2Generic::showLog(const std::string& message)const{
142  if(isVerbose() == false){
143  return;
144  }
145  std::cerr << message;
146 }
147 /** This method can or cannot be implemented in the derived class, depending on the need for it.
148 * \exception This method must throw an exception with a descriptive message if some critical error is found.
149 */
151 {
152 #if MRPT_HAS_OPENNI2
153  // Get devices list
154  openni::Array<openni::DeviceInfo> oni2InfoArray;
155  openni::OpenNI::enumerateDevices(&oni2InfoArray);
156 
157  const size_t numDevices = oni2InfoArray.getSize();
158  showLog(mrpt::format("[%s]\n", __FUNCTION__));
159  showLog(mrpt::format(" Get device list. %d devices connected.\n", (int)numDevices));
160 
161  // Search new devices.
162  std::set<int> newDevices;
163  for(unsigned i=0; i < numDevices; i++){
164  const openni::DeviceInfo& info = oni2InfoArray[i];
165  showLog(mrpt::format(" Device[%d]\n", i));
166  showLog(oni2DevInfoStr(info, 3) + "\n");
167 
168  bool isExist = false;
169  for(unsigned int j = 0, j_end = vDevices.size();j < j_end && isExist == false;++j){
170  if(cmpONI2Device(info, vDevices[j]->getInfo())){
171  isExist = true;
172  }
173  }
174  if(isExist == false){
175  newDevices.insert(i);
176  }
177  }
178  // Add new devices to device list(static member).
179  for(std::set<int>::const_iterator it = newDevices.begin(), it_end = newDevices.end();it != it_end;++it){
180  const openni::DeviceInfo& info = oni2InfoArray[*it];
181  CDevice::Ptr device = CDevice::create(info, (openni::PixelFormat)m_rgb_format, (openni::PixelFormat)m_depth_format, m_verbose);
182  vDevices.push_back(device);
183  {
184  unsigned int sn;
185  if (device->getSerialNumber(sn)) {
186  showLog(mrpt::format("Device[%d]: serial number: `%u`\n",*it,sn) );
187  }
188  }
189  }
190 
191  if(getNumDevices() == 0){
192  showLog(" No devices connected -> EXIT\n");
193  }else{
194  showLog(mrpt::format(" %d devices were found.\n", getNumDevices()));
195  }
196  return getNumDevices();
197 #else
198  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
199 #endif // MRPT_HAS_OPENNI2
200 }
201 
203 {
204 #if MRPT_HAS_OPENNI2
205  vDevices.clear();
206  openni::OpenNI::shutdown();
207 #else
208  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
209 #endif // MRPT_HAS_OPENNI2
210 }
211 
212 bool COpenNI2Generic::isOpen(const unsigned sensor_id) const
213 {
214 #if MRPT_HAS_OPENNI2
215  if((int)sensor_id >= getNumDevices()){
216  return false;
217  }
218  return vDevices[sensor_id]->isOpen();
219 #else
220  MRPT_UNUSED_PARAM(sensor_id);
221  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
222 #endif // MRPT_HAS_OPENNI2
223 }
224 
225 void COpenNI2Generic::open(unsigned sensor_id)
226 {
227 #if MRPT_HAS_OPENNI2
228  // Sensor index validation.
229  if (!getNumDevices()){
230  THROW_EXCEPTION("No OpenNI2 devices found.")
231  }
232  if ((int)sensor_id >= getNumDevices()){
233  THROW_EXCEPTION("Sensor index is higher than the number of connected devices.")
234  }
235  showLog(mrpt::format("[%s]\n", __FUNCTION__));
236  showLog(mrpt::format(" open[%d] ...\n", sensor_id));
237 
238  if(isOpen(sensor_id)){
239  showLog(mrpt::format(" The sensor [%d] is already opened\n", sensor_id));
240  return;
241  }
242  if (m_verbose) printf("[COpenNI2Generic] DBG: [%s] about to call vDevices[%d]->open()\n",__FUNCTION__,sensor_id);
243  vDevices[sensor_id]->open(m_width, m_height, m_fps);
244  showLog(vDevices[sensor_id]->getLog() + "\n");
245  showLog(mrpt::format(" Device [%d] ", sensor_id));
246  if(vDevices[sensor_id]->isOpen()){
247  showLog(" open successfully.\n");
248  }else{
249  showLog(" open failed.\n");
250  }
251  mrpt::system::sleep(1000); // Sleep
252 #else
253  MRPT_UNUSED_PARAM(sensor_id);
254  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
255 #endif // MRPT_HAS_OPENNI2
256 }
257 
258 unsigned int COpenNI2Generic::openDevicesBySerialNum(const std::set<unsigned>& serial_required)
259 {
260 #if MRPT_HAS_OPENNI2
261  showLog(mrpt::format("[%s]\n", __FUNCTION__));
262  unsigned num_open_dev = 0;
263  for(unsigned sensor_id=0; sensor_id < vDevices.size(); sensor_id++)
264  {
265  unsigned int serialNum;
266  if(vDevices[sensor_id]->getSerialNumber(serialNum) == false){
267  showLog(vDevices[sensor_id]->getLog());
268  continue;
269  }
270  if (m_verbose) printf("[COpenNI2Generic::openDevicesBySerialNum] checking device with serial '%d'\n",serialNum);
271 
272  if(serial_required.find(serialNum) == serial_required.end()){
273  vDevices[sensor_id]->close();
274  continue;
275  }
276  if(vDevices[sensor_id]->isOpen()){
277  num_open_dev++;
278  continue;
279  }
280  int width = m_width;
281  int height = m_height;
282  if (m_verbose) printf("[COpenNI2Generic] DBG: [%s] about to call vDevices[%d]->open(%d,%d,%d)\n",
283  __FUNCTION__,sensor_id,width,height,(int)m_fps);
284  if(vDevices[sensor_id]->open(width, height, m_fps) == false){
285  showLog(vDevices[sensor_id]->getLog());
286  continue;
287  }
288  num_open_dev++;
289  if (m_verbose) printf("[COpenNI2Generic] DBG: [%s] now has %d devices open\n", __FUNCTION__,num_open_dev);
290  }
291  return num_open_dev;
292 #else
293  MRPT_UNUSED_PARAM(serial_required);
294  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
295 #endif // MRPT_HAS_OPENNI2
296 }
297 
298 unsigned int COpenNI2Generic::openDeviceBySerial(const unsigned int SerialRequired){
299  std::set<unsigned> serial_required;
300  serial_required.insert(SerialRequired);
301  return openDevicesBySerialNum(serial_required);
302 }
303 
304 bool COpenNI2Generic::getDeviceIDFromSerialNum(const unsigned int SerialRequired, int& sensor_id) const{
305 #if MRPT_HAS_OPENNI2
306  for(size_t i = 0, i_end = vDevices.size();i < i_end;++i){
307  unsigned int sn;
308  if(vDevices[i]->getSerialNumber(sn) == false){
309  continue;
310  }
311  if(sn == SerialRequired){
312  sensor_id = (int)i;
313  return true;
314  }
315  }
316  return false;
317 #else
318  MRPT_UNUSED_PARAM(SerialRequired); MRPT_UNUSED_PARAM(sensor_id);
319  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
320 #endif // MRPT_HAS_OPENNI2
321 }
322 
323 void COpenNI2Generic::close(unsigned sensor_id)
324 {
325 #if MRPT_HAS_OPENNI2
326  // Sensor index validation.
327  if (!getNumDevices()){
328  THROW_EXCEPTION("No OpenNI2 devices found.")
329  }
330  if ((int)sensor_id >= getNumDevices()){
331  THROW_EXCEPTION("Sensor index is higher than the number of connected devices.")
332  }
333  vDevices[sensor_id]->close();
334 #else
335  MRPT_UNUSED_PARAM(sensor_id);
336  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
337 #endif // MRPT_HAS_OPENNI2
338 }
339 
340 /** The main data retrieving function, to be called after calling loadConfig() and initialize().
341 * \param out_obs The output retrieved observation (only if there_is_obs=true).
342 * \param timestamp The timestamp of the capture (only if there_is_obs=true).
343 * \param there_is_obs If set to false, there was no new observation.
344 * \param hardware_error True on hardware/comms error.
345 * \param sensor_id The index of the sensor accessed.
346 *
347 */
349  mrpt::utils::CImage &rgb_img,
350  uint64_t &timestamp,
351  bool &there_is_obs,
352  bool &hardware_error,
353  unsigned sensor_id )
354 {
355 #if MRPT_HAS_OPENNI2
356  // Sensor index validation.
357  if (!getNumDevices()){
358  THROW_EXCEPTION("No OpenNI2 devices found.")
359  }
360  if ((int)sensor_id >= getNumDevices()){
361  THROW_EXCEPTION("Sensor index is higher than the number of connected devices.")
362  }
363  if(vDevices[sensor_id]->getNextFrameRGB(rgb_img, timestamp, there_is_obs, hardware_error) == false){
364  showLog(mrpt::format("[%s]\n", __FUNCTION__ ));
365  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
366  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
367  }
368 #else
369  MRPT_UNUSED_PARAM(rgb_img); MRPT_UNUSED_PARAM(timestamp);
370  MRPT_UNUSED_PARAM(there_is_obs); MRPT_UNUSED_PARAM(hardware_error); MRPT_UNUSED_PARAM(sensor_id);
371  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
372 #endif // MRPT_HAS_OPENNI2
373 }
374 
375 /** The main data retrieving function, to be called after calling loadConfig() and initialize().
376 * \param depth_img The output retrieved depth image (only if there_is_obs=true).
377 * \param timestamp The timestamp of the capture (only if there_is_obs=true).
378 * \param there_is_obs If set to false, there was no new observation.
379 * \param hardware_error True on hardware/comms error.
380 * \param sensor_id The index of the sensor accessed.
381 *
382 */
384  mrpt::math::CMatrix &depth_img,
385  uint64_t &timestamp,
386  bool &there_is_obs,
387  bool &hardware_error,
388  unsigned sensor_id )
389 {
390 #if MRPT_HAS_OPENNI2
391  // Sensor index validation.
392  if (getNumDevices() == 0){
393  THROW_EXCEPTION("No OpenNI2 devices found.")
394  }
395  if ((int)sensor_id >= getNumDevices()){
396  THROW_EXCEPTION("Sensor index is higher than the number of connected devices.")
397  }
398  if(vDevices[sensor_id]->getNextFrameD(depth_img, timestamp, there_is_obs, hardware_error) == false){
399  showLog(mrpt::format("[%s]\n", __FUNCTION__));
400  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
401  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
402  }
403 #else
404  MRPT_UNUSED_PARAM(depth_img); MRPT_UNUSED_PARAM(timestamp);
405  MRPT_UNUSED_PARAM(there_is_obs); MRPT_UNUSED_PARAM(hardware_error); MRPT_UNUSED_PARAM(sensor_id);
406  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
407 #endif // MRPT_HAS_OPENNI2
408 }
409 
410 /** The main data retrieving function, to be called after calling loadConfig() and initialize().
411 * \param out_obs The output retrieved observation (only if there_is_obs=true).
412 * \param there_is_obs If set to false, there was no new observation.
413 * \param hardware_error True on hardware/comms error.
414 * \param sensor_id The index of the sensor accessed.
415 *
416 */
419  bool &there_is_obs,
420  bool &hardware_error,
421  unsigned sensor_id )
422 {
423 #if MRPT_HAS_OPENNI2
424  // Sensor index validation.
425  if (!getNumDevices()){
426  THROW_EXCEPTION("No OpenNI2 devices found.")
427  }
428  if ((int)sensor_id >= getNumDevices()){
429  THROW_EXCEPTION("Sensor index is higher than the number of connected devices.")
430  }
431  if(vDevices[sensor_id]->getNextFrameRGBD(out_obs, there_is_obs, hardware_error) == false){
432  showLog(mrpt::format("[%s]\n", __FUNCTION__));
433  showLog(mrpt::format(" Error [%d]th Sensor.\n", sensor_id));
434  showLog(std::string(" ") + vDevices[sensor_id]->getLog() + "\n");
435  }
436 #else
437  MRPT_UNUSED_PARAM(out_obs); MRPT_UNUSED_PARAM(there_is_obs); MRPT_UNUSED_PARAM(hardware_error);
438  MRPT_UNUSED_PARAM(sensor_id);
439  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
440 #endif // MRPT_HAS_OPENNI2
441 }
442 
444 #if MRPT_HAS_OPENNI2
445  if(isOpen(sensor_id) == false){
446  return false;
447  }
448  return vDevices[sensor_id]->getCameraParam(CDevice::COLOR_STREAM, param);
449 #else
451  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
452 #endif // MRPT_HAS_OPENNI2
453 }
454 
456 #if MRPT_HAS_OPENNI2
457  if(isOpen(sensor_id) == false){
458  return false;
459  }
460  return vDevices[sensor_id]->getCameraParam(CDevice::DEPTH_STREAM, param);
461 #else
463  THROW_EXCEPTION("MRPT was built without OpenNI2 support")
464 #endif // MRPT_HAS_OPENNI2
465 }
466 
467 
468 #if MRPT_HAS_OPENNI2
469 /*
470 void openni::VideoMode::setResolution()
471 Setter function for the resolution of this VideoMode. Application use of this function is not recommended.
472 Instead, use SensorInfo::getSupportedVideoModes() to obtain a list of valid video modes
473 
474 -- cited from OpenNI2 help. setResolution() is not recommended.
475 */
476 bool setONI2StreamMode(openni::VideoStream& stream, int w, int h, int fps, openni::PixelFormat format){
477  // std::cout << "[COpenNI2Generic] Ask mode: " << w << "x" << h << " " << fps << " fps. format " << format << std::endl;
478  bool found = false;
479  const openni::Array<openni::VideoMode>& modes = stream.getSensorInfo().getSupportedVideoModes();
480  for(int i = 0, i_end = modes.getSize();i < i_end;++i){
481  // if (m_verbose) std::cout << "[COpenNI2Generic] Mode: " << modes[i].getResolutionX() << "x" << modes[i].getResolutionY() << " " << modes[i].getFps() << " fps. format " << modes[i].getPixelFormat() << std::endl;
482  if(modes[i].getResolutionX() != w){
483  continue;
484  }
485  if(modes[i].getResolutionY() != h){
486  continue;
487  }
488  if(modes[i].getFps() != fps){
489  continue;
490  }
491  if(modes[i].getPixelFormat() != format){
492  continue;
493  }
494  openni::Status rc = stream.setVideoMode(modes[i]);
495  if(rc != openni::STATUS_OK){
496  return false;
497  }
498  return true;
499  }
500  return false;
501 }
502 
503 std::string oni2DevInfoStr(const openni::DeviceInfo& info, int tab){
504  std::stringstream sst;
505  std::string space;
506  for(int i = 0;i < tab;++i){
507  space += " ";
508  }
509  sst << space << "name=" << info.getName() << std::endl;
510  sst << space << "uri=" << info.getUri() << std::endl;
511  sst << space << "vendor=" << info.getVendor() << std::endl;
512  sst << space << "product=" << info.getUsbProductId();
513  return sst.str();
514 }
515 
516 bool cmpONI2Device(const openni::DeviceInfo& i1, const openni::DeviceInfo& i2){
517  return (strcmp(i1.getUri(), i2.getUri()) == 0);
518 }
519 //
520 COpenNI2Generic::CDevice::CDevice(const openni::DeviceInfo& info, openni::PixelFormat rgb, openni::PixelFormat depth,bool verbose)
521  :m_info(info), m_mirror(true), m_verbose(verbose)
522 {
523  m_streams[COLOR_STREAM] = CStream::create(m_device, openni::SENSOR_COLOR, rgb , m_log, m_verbose);
524  m_streams[IR_STREAM] = CStream::create(m_device, openni::SENSOR_IR, rgb , m_log, m_verbose);
525  m_streams[DEPTH_STREAM] = CStream::create(m_device, openni::SENSOR_DEPTH, depth, m_log, m_verbose);
526 }
527 
528 COpenNI2Generic::CDevice::~CDevice(){
529  close();
530 }
531 
532 bool COpenNI2Generic::CDevice::synchMirrorMode(){
533  m_mirror = false;
534  // Check whether both stream support mirroring.
535  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
536  if (!m_streams[i]) continue;
537  bool mirror_support;
538  try{
539  mirror_support = m_streams[i]->isMirrorSupported();
540  }catch(std::logic_error& e){
541  throw(e);
542  }
543  if(mirror_support == false){
544  m_log << "[" << __FUNCTION__ << "]" << std::endl;
545  m_log << " openni::STREAM_PROPERTY_MIRRORING is not supported on " << m_streams[i]->getName() << "." << std::endl;
546  m_log << " We assume this is MS Kinect and taken images are inverted to right and left." << std::endl;
547  // In this case, getMirroringEnabled() method always returns false. So we cannot confirm whether the images are inverted or not.
548  m_mirror = true;
549  break;
550  }
551  }
552  // Set both stream to same mirror mode.
553  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
554  if (!m_streams[i]) continue;
555  if(m_streams[i]->isMirrorSupported() == false){
556  break;
557  }
558  if(m_streams[i]->setMirror(m_mirror) == false){
559  return false;
560  }
561  }
562  return true;
563 }
564 
565 bool COpenNI2Generic::CDevice::startStreams(){
566  MRPT_START
567  int num_ok = 0;
568  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
569  if (!m_streams[i]) continue;
570  if (m_verbose) printf(" [%s] calling m_streams[%d]->start()\n",__FUNCTION__,i);
571  if(m_streams[i]->start() == false){
572  if (m_verbose) printf(" [%s] m_streams[%d]->start() returned FALSE!\n",__FUNCTION__,i);
573  }
574  else {
575  num_ok++;
576  }
577  if (m_verbose) printf(" [%s] m_streams[%d]->start() returned TRUE\n",__FUNCTION__,i);
578  }
579  if (m_verbose) printf(" [COpenNI2Generic::CDevice::startStreams()] %d streams were started.\n", num_ok);
580  return num_ok>0;
581  MRPT_END
582 }
583 
584 bool COpenNI2Generic::CDevice::isOpen()const{
585  return (m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid()) ||
586  (m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid());
587 }
588 
589 void COpenNI2Generic::CDevice::close(){
590  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
591  if (!m_streams[i]) continue;
592  m_streams[i]->destroy();
593  }
594  m_device.close();
595 }
596 
597 bool COpenNI2Generic::CDevice::open(int w, int h, int fps){
598  MRPT_START
599  if (m_verbose) printf(" [COpenNI2Generic::CDevice::open()] Called with w=%i h=%i fps=%i\n",w,h,fps);
600  clearLog();
601  close();
602  openni::Status rc = m_device.open(getInfo().getUri());
603  if(rc != openni::STATUS_OK){
604  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Failed to open device " << getInfo().getUri() << " " << openni::OpenNI::getExtendedError() << std::endl;
605  return false;
606  }
607  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
608  if(!m_streams[i]) continue;
609  if (m_verbose) printf(" [%s] calling m_streams[%d]->open()\n",__FUNCTION__,i);
610 
611  if(m_streams[i]->open(w, h, fps) == false)
612  {
613  if (m_verbose) printf(" [%s] m_streams[%d]->open() returned FALSE\n",__FUNCTION__,i);
614  return false;
615  }
616  if (m_verbose) printf(" [%s] m_streams[%d]->open() returned OK\n",__FUNCTION__,i);
617  }
618 
619  if(synchMirrorMode() == false){
620  close();
621  return false;
622  }
623 
624  if (m_streams[DEPTH_STREAM]) {
625  int CloseRange=0;
626  m_streams[DEPTH_STREAM]->setCloseRange(CloseRange);
627  m_log << " Close range: " << (CloseRange? "On" : "Off") << std::endl;
628  }
629 
630  if (m_verbose) printf(" DBG: checking if imageRegistrationMode is supported\n");
631  if(m_device.isImageRegistrationModeSupported(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) &&
632  m_streams[DEPTH_STREAM] && m_streams[DEPTH_STREAM]->isValid() &&
633  m_streams[COLOR_STREAM] && m_streams[COLOR_STREAM]->isValid() )
634  {
635 //SEB if(m_device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF) != openni::STATUS_OK){
636  if(m_device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR) != openni::STATUS_OK){
637  m_log << " setImageRegistrationMode() Failed:" << openni::OpenNI::getExtendedError() << endl;
638  }else{
639  m_log << " setImageRegistrationMode() Success" << endl;
640  }
641  }else{
642  m_log << " Device doesn't do image registration!" << endl;
643  }
644 
645  if (0) // hasColor())
646  { // printf("DBG: hasColor() returned TRUE\n");
647  m_streams[COLOR_STREAM]->disableAutoExposure();
648  printf("DBG: returned from disableAutoExposure()\n");
649  }
650 
651  if(startStreams() == false){
652  close();
653  return false;
654  }
655  return true;
656  MRPT_END
657 }
658 
659 bool COpenNI2Generic::CDevice::getNextFrameRGB(mrpt::utils::CImage &img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error){
660  MRPT_START
661  if(!hasColor()){
662  THROW_EXCEPTION("This OpenNI2 device does not support color imaging")
663  }
664  openni::VideoFrameRef frame;
665  if(m_streams[COLOR_STREAM]->getFrame(frame, timestamp, there_is_obs, hardware_error) == false){
666  return false;
667  }
668  copyFrame<openni::RGB888Pixel, mrpt::utils::CImage>(frame, img);
669 
670  return true;
671  MRPT_END
672 }
673 
674 bool COpenNI2Generic::CDevice::getNextFrameD(mrpt::math::CMatrix &img, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error){
675  MRPT_START
676  if(!hasDepth()){
677  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging")
678  }
679  openni::VideoFrameRef frame;
680  if(m_streams[DEPTH_STREAM]->getFrame(frame, timestamp, there_is_obs, hardware_error) == false){
681  return false;
682  }
683  copyFrame<openni::DepthPixel, mrpt::math::CMatrix>(frame, img);
684 
685  return true;
686  MRPT_END
687 }
688 
689 bool COpenNI2Generic::CDevice::getNextFrameRGBD(mrpt::obs::CObservation3DRangeScan &obs, bool &there_is_obs, bool &hardware_error){
690  MRPT_START
691  clearLog();
692  there_is_obs = false;
693  hardware_error = false;
694 
695  if(!hasColor()){
696  THROW_EXCEPTION("This OpenNI2 device does not support color imaging")
697  }
698  if(!hasDepth()){
699  THROW_EXCEPTION("This OpenNI2 device does not support depth imaging")
700  }
701  // Read a frame (depth + rgb)
703  openni::VideoFrameRef frame[STREAM_TYPE_SIZE];
704  for(int i = 0;i < STREAM_TYPE_SIZE;++i){
705  if (!m_streams[i] || !m_streams[i]->isValid()) continue;
706  if(m_streams[i]->getFrame(frame[i], tm, there_is_obs, hardware_error) == false){
707  return false;
708  }
709  if(there_is_obs == false || hardware_error == true){
710  return false;
711  }
712  }
713 
714  const int width = frame[COLOR_STREAM].getWidth();
715  const int height = frame[COLOR_STREAM].getHeight();
716  if((frame[DEPTH_STREAM].getWidth() != width) || (frame[DEPTH_STREAM].getHeight() != height)){
717  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Both frames don't have the same size." << std::endl;
718  return false;
719  }
720  there_is_obs = true;
721  obs.hasConfidenceImage = false;
722  obs.hasIntensityImage = true;
723  obs.hasRangeImage = true;
724  obs.range_is_depth = true;
725  obs.hasPoints3D = false;
727  resize(obs, width, height);
728 
729  const char* data[STREAM_TYPE_SIZE] =
730  {
731  (const char*)frame[COLOR_STREAM].getData(),
732  (const char*)frame[DEPTH_STREAM].getData()
733  };
734  const int step[STREAM_TYPE_SIZE] =
735  {
736  frame[COLOR_STREAM].getStrideInBytes(),
737  frame[DEPTH_STREAM].getStrideInBytes()
738  };
739 
740  for (int yc = 0; yc < height; ++yc){
741  const openni::RGB888Pixel* pRgb = (const openni::RGB888Pixel*)data[COLOR_STREAM];
742  const openni::DepthPixel * pDepth = (const openni::DepthPixel *)data[DEPTH_STREAM];
743  for (int xc = 0; xc < width; ++xc, ++pDepth, ++pRgb){
744  int x = xc;
745  if(isMirrorMode()){
746  x = width - x - 1;
747  }
748  setPixel(*pRgb , obs.intensityImage, x, yc);
749  setPixel(*pDepth, obs.rangeImage , x, yc);
750  }
751  data[COLOR_STREAM] += step[COLOR_STREAM];
752  data[DEPTH_STREAM] += step[DEPTH_STREAM];
753  }
754 
755  return true;
756  MRPT_END
757 }
758 
759 COpenNI2Generic::CDevice::Ptr COpenNI2Generic::CDevice::create(const openni::DeviceInfo& info, openni::PixelFormat rgb, openni::PixelFormat depth, bool verbose){
760  return Ptr(new CDevice(info, rgb, depth,verbose));
761 }
762 
763 bool COpenNI2Generic::CDevice::getSerialNumber(std::string& sn){
764  clearLog();
765  openni::Status rc;
766  bool isOpened = isOpen();
767  if(isOpened == false){
768  rc = m_device.open(getInfo().getUri());
769  if(rc != openni::STATUS_OK){
770  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Failed to open device " << getInfo().getUri() << " " << openni::OpenNI::getExtendedError() << std::endl;
771  return false;
772  }
773  }
774  char serialNumber[16];
775  rc = m_device.getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER, &serialNumber);
776  if(rc != openni::STATUS_OK){
777  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Failed to getProperty(ONI_DEVICE_PROPERTY_SERIAL_NUMBER) " << getInfo().getUri() << " " << openni::OpenNI::getExtendedError() << std::endl;
778  return false;
779  }
780  sn = std::string(serialNumber);
781  if(isOpened == false){
782  m_device.close();
783  }
784  return true;
785 }
786 
787 bool COpenNI2Generic::CDevice::getSerialNumber(unsigned int& sn){
788  std::string str;
789  if(getSerialNumber(str) == false){
790  return false;
791  }
792  std::stringstream sst;
793  sst.str(str);
794  sst >> sn;
795  return !sst.fail();
796 }
797 //
798 COpenNI2Generic::CDevice::CStream::CStream(openni::Device& device, openni::SensorType type, openni::PixelFormat format, std::ostream& log,bool verbose)
799  :m_log(log), m_device(device), m_strName("Unknown"), m_type(type), m_format(format), m_verbose(verbose)
800 {
801  if(m_type == openni::SENSOR_COLOR){
802  m_strName = "openni::SENSOR_COLOR";
803  }else if(m_type == openni::SENSOR_DEPTH){
804  m_strName = "openni::SENSOR_DEPTH";
805  }else if(m_type == openni::SENSOR_IR){
806  m_strName = "openni::SENSOR_IR";
807  }else{
808  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Unknown SensorType -> " << m_type << std::endl;
809  }
810 }
811 
812 COpenNI2Generic::CDevice::CStream::~CStream(){
813  destroy();
814 }
815 
816 bool COpenNI2Generic::CDevice::CStream::isMirrorSupported()const{
817  if(isValid() == false){
818  THROW_EXCEPTION(getName() + " is not opened.");
819  }
820  return m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING);
821 }
822 
823 bool COpenNI2Generic::CDevice::CStream::setMirror(bool flag){
824  if(isValid() == false){
825  m_log << "[" << __FUNCTION__ << "]" << std::endl << " " << getName() << " is not opened." << std::endl;
826  return false;
827  }
828  if(m_stream.isPropertySupported(openni::STREAM_PROPERTY_MIRRORING) == false){
829  return false;
830  }
831  if(m_stream.setMirroringEnabled(flag) != openni::STATUS_OK){
832  m_log << "[" << __FUNCTION__ << "]" << std::endl << " setMirroringEnabled() failed: " << openni::OpenNI::getExtendedError() << std::endl;
833  return false;
834  }
835  return true;
836 }
837 
838 bool COpenNI2Generic::CDevice::CStream::isValid()const{
839  return m_stream.isValid();
840 }
841 
842 void COpenNI2Generic::CDevice::CStream::destroy(){
843  m_stream.destroy();
844 }
845 
846 void COpenNI2Generic::CDevice::CStream::setCloseRange(int& value){
847  if (m_verbose) printf(" [CDevice::CStream::setCloseRange] entry with value=%d\n",value);
848  m_stream.setProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, value);
849  if (m_verbose) printf(" [CDevice::CStream::setCloseRange] returned from mstream.setProperty()\n");
850  m_stream.getProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, &value);
851  if (m_verbose) printf(" [CDevice::CStream::setCloseRange] returned from mstream.getProperty() ... value %d\n",value);
852 }
853 
854 bool COpenNI2Generic::CDevice::CStream::open(int w, int h, int fps){
855  destroy();
856  if(m_type != openni::SENSOR_COLOR && m_type != openni::SENSOR_DEPTH && m_type != openni::SENSOR_IR){ // SEB added IR
857  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Unknown SensorType -> " << m_type << std::endl;
858  return false;
859  }
860  if (m_verbose) printf(" [COpenNI2Generic::CDevice::CStream::open] opening sensor stream with m_type == %d\n",(int)m_type);
861  openni::Status rc = openni::STATUS_OK;
862 // if(m_type == openni::SENSOR_COLOR) {
863 // m_type = openni::SENSOR_IR;
864 // m_strName="openni::SENSOR_IR"; // SEB added
865 // if (m_verbose) printf("DBG: changing type to SENSOR_IR (%d)\n",(int)m_type);
866 // } // added whole if stmt
867  rc = m_stream.create(m_device, m_type);
868  if(rc != openni::STATUS_OK){
869  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Couldn't find sensor "
870  << m_strName << ":" << openni::OpenNI::getExtendedError() << std::endl;
871  if(m_type == openni::SENSOR_COLOR) {
872  m_type = openni::SENSOR_IR;
873  m_strName="openni::SENSOR_IR"; // SEB added
874  if (m_verbose) printf("DBG: changing type to SENSOR_IR (%d)\n",(int)m_type);
875  rc = m_stream.create(m_device, m_type);
876  } // SEB added whole if stmt
877  else
878  return false;
879  }
880  if (m_verbose) printf("returned OK from stream.create()\n");
881  openni::VideoMode options = m_stream.getVideoMode();
882  m_log << "[" << __FUNCTION__ << "]" << std::endl;
883  m_log << " " << m_strName << std::endl;
884  m_log << " " << mrpt::format("Initial resolution (%d, %d) FPS %d Format %d", options.getResolutionX(), options.getResolutionY(), options.getFps(), options.getPixelFormat()) << std::endl;
885  if (m_verbose) printf("DBG: calling setONI2StreamMode()\n");
886  if(setONI2StreamMode(m_stream, w, h, fps, m_format) == false){
887  m_log << " Can't find desired mode in the " << getName() << std::endl;
888  destroy();
889  return false;
890  }
891  if (m_verbose) printf("DBG: returned OK from setONI2StreamMode()\n");
892  if (m_verbose) printf("DBG: calling stream.getVideoMode()\n");
893  options = m_stream.getVideoMode();
894  m_log << " " << mrpt::format("-> (%d, %d) FPS %d Format %d", options.getResolutionX(), options.getResolutionY(), options.getFps(), options.getPixelFormat()) << std::endl;
895  if (m_verbose) printf(" [COpenNI2Generic::CDevice::CStream::open] returning TRUE\n");
896  return true;
897 }
898 
900  if(isValid() == false){
901  m_log << "[" << __FUNCTION__ << "]" << std::endl << " " << getName() << " is not opened." << std::endl;
902  return false;
903  }
904  if(m_stream.start() != openni::STATUS_OK){
905  m_log << "[" << __FUNCTION__ << "]" << std::endl << " Couldn't start " << getName() << " stream:" << openni::OpenNI::getExtendedError() << std::endl;
906  this->destroy();
907  return false;
908  }
909  return true;
910 }
911 
912 COpenNI2Generic::CDevice::CStream::Ptr COpenNI2Generic::CDevice::CStream::create(openni::Device& device, openni::SensorType type, openni::PixelFormat format, std::ostream& log, bool verbose){
913  return Ptr(new CStream(device, type, format, log,verbose));
914 }
915 
916 bool COpenNI2Generic::CDevice::CStream::getFrame(openni::VideoFrameRef& frame, uint64_t &timestamp, bool &there_is_obs, bool &hardware_error)
917 {
918  there_is_obs = false;
919  hardware_error = false;
920  if(isValid() == false){
921  return false;
922  }
923  openni::Status rc = m_stream.readFrame(&frame);
924  if(rc != openni::STATUS_OK){
925  hardware_error = true;
926  std::string message = mrpt::format("Failed to grab frame from %s", getName().c_str());
927  THROW_EXCEPTION(message);
928  }
929  there_is_obs = true;
930  timestamp = mrpt::system::getCurrentTime();
931  return true;
932 }
933 
934 #endif // MRPT_HAS_OPENNI2
double getHeight(const TPolygon3D &p, const TPoint3D &c)
bool isOpen(const unsigned sensor_id) const
Whether there is a working connection to the sensor.
void showLog(const std::string &message) const
void close(unsigned sensor_id=0)
Close the connection to the sensor (no need to call it manually unless desired for some reason,...
bool getDeviceIDFromSerialNum(const unsigned int SerialRequired, int &sensor_id) const
Get the ID of the device corresponding to 'SerialRequired'.
int getConnectedDevices()
Get a list of the connected OpenNI2 sensors.
bool getColorSensorParam(mrpt::utils::TCamera &param, unsigned sensor_id=0) const
class HWDRIVERS_IMPEXP CDevice
The list of available devices.
COpenNI2Generic()
Default ctor (width=640, height=480, fps=30)
unsigned int openDevicesBySerialNum(const std::set< unsigned > &vSerialRequired)
Open a set of RGBD devices specified by their serial number.
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().
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().
static std::vector< stlplus::smart_ptr< CDevice > > vDevices
bool start()
Open all sensor streams (normally called automatically at constructor, no need to call it manually).
void kill()
Kill the OpenNI2 driver.
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().
int m_width
The same options (width, height and fps) are set for all the sensors.
int getNumDevices() const
The number of available devices at initialization.
void open(unsigned sensor_id=0)
Try to open the camera (all the parameters [resolution,fps,...] must be set before calling this) - us...
unsigned int openDeviceBySerial(const unsigned int SerialRequired)
Open a RGBD device specified by its serial number.
bool getDepthSensorParam(mrpt::utils::TCamera &param, unsigned sensor_id=0) const
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:31
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
bool hasConfidenceImage
true means the field confidenceImage contains valid data
bool hasIntensityImage
true means the field intensityImage contains valid data
bool hasPoints3D
true means the field points3D contains valid data.
bool hasRangeImage
true means the field rangeImage contains valid data
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)
mrpt::utils::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage".
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based time...
A class for storing images as grayscale or RGB bitmaps.
Definition: CImage.h:102
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:32
const Scalar * const_iterator
Definition: eigen_plugins.h:24
GLuint start
Definition: glext.h:3512
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glext.h:3545
GLubyte GLubyte GLubyte GLubyte w
Definition: glext.h:3962
GLsizei GLsizei GLenum GLenum const GLvoid * data
Definition: glext.h:3520
GLfloat param
Definition: glext.h:3705
GLuint GLuint GLsizei GLenum type
Definition: glext.h:3512
GLenum GLsizei width
Definition: glext.h:3513
GLint GLvoid * img
Definition: glext.h:3645
GLenum GLint x
Definition: glext.h:3516
GLenum GLsizei GLsizei height
Definition: glext.h:3523
GLenum GLsizei GLenum format
Definition: glext.h:3513
GLsizei const GLfloat * value
Definition: glext.h:3929
GLsizei const GLchar ** string
Definition: glext.h:3919
void BASE_IMPEXP sleep(int time_ms) MRPT_NO_THROWS
An OS-independent method for sending the current thread to "sleep" for a given period of time.
Definition: threads.cpp:57
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
Definition: datetime.h:30
mrpt::system::TTimeStamp BASE_IMPEXP getCurrentTime()
Returns the current (UTC) system time.
Definition: datetime.cpp:71
backing_store_ptr info
Definition: jmemsys.h:170
#define MRPT_START
Definition: mrpt_macros.h:366
#define MRPT_END
Definition: mrpt_macros.h:370
#define THROW_EXCEPTION(msg)
Definition: mrpt_macros.h:154
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
Definition: mrpt_macros.h:307
Contains classes for various device interfaces.
This namespace contains representation of robot actions and observations.
This namespace provides multitask, synchronization utilities.
Definition: atomic_incr.h:30
This namespace provides a OS-independent interface to many useful functions: filenames manipulation,...
Definition: math_frwds.h:30
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:21
unsigned __int64 uint64_t
Definition: rptypes.h:52
Status
Definition: xmlParser.cpp:524



Page generated by Doxygen 1.9.1 for MRPT 1.5.5 Git: 832f416fc Sat Dec 2 06:28:34 2017 +0100 at mar 26 may 2026 13:01:45 CEST