YARP
Yet Another Robot Platform
depthCameraDriver.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #include "depthCameraDriver.h"
20 
21 #include <yarp/os/LogComponent.h>
22 #include <yarp/os/LogStream.h>
23 #include <yarp/os/Value.h>
24 
25 #include <algorithm>
26 #include <cmath>
27 #include <mutex>
28 
29 using namespace yarp::dev;
30 using namespace yarp::sig;
31 using namespace yarp::os;
32 using namespace openni;
33 using namespace std;
34 
35 #ifndef RETURN_FALSE_STATUS_NOT_OK
36 #define RETURN_FALSE_STATUS_NOT_OK(s) if(s != STATUS_OK) { yCError(DEPTHCAMERA) << OpenNI::getExtendedError(); return false; }
37 #endif
38 
39 namespace {
40 YARP_LOG_COMPONENT(DEPTHCAMERA, "yarp.device.depthCamera")
41 constexpr char accuracy [] = "accuracy";
42 constexpr char clipPlanes [] = "clipPlanes";
43 constexpr char depth_Fov [] = "depth_Fov";
44 constexpr char depthRes [] = "depthResolution";
45 constexpr char rgb_Fov [] = "rgb_Fov";
46 constexpr char rgbRes [] = "rgbResolution";
47 constexpr char rgbMirroring [] = "rgbMirroring";
48 constexpr char depthMirroring [] = "depthMirroring";
49 }
50 
51 static std::map<std::string, RGBDSensorParamParser::RGBDParam> params_map =
52 {
55  {depth_Fov, RGBDSensorParamParser::RGBDParam(depth_Fov, 2)},
57  {rgb_Fov, RGBDSensorParamParser::RGBDParam(rgb_Fov, 2)},
59  {rgbMirroring, RGBDSensorParamParser::RGBDParam(rgbMirroring, 1)},
60  {depthMirroring, RGBDSensorParamParser::RGBDParam(depthMirroring, 1)}
61 };
62 
63 class streamFrameListener : public openni::VideoStream::NewFrameListener
64 {
65 public:
66 
67  //Properties
68  std::mutex mutex;
71  openni::PixelFormat pixF{openni::PixelFormat::PIXEL_FORMAT_DEPTH_1_MM};
72  int w{0};
73  int h{0};
74  size_t dataSize{0};
75  bool isReady{false};
76 
77  //Method
79  bool isValid(){return frameRef.isValid() & isReady;}
80  void destroy(){frameRef.release();}
81  bool getImage(FlexImage& inputImage)
82  {
83  std::lock_guard<std::mutex> guard(mutex);
84  return inputImage.copy(image);
85  }
86 
88  {
89  std::lock_guard<std::mutex> guard(mutex);
90  return stamp;
91  }
92 
93 private:
94  void onNewFrame(openni::VideoStream& stream) override;
95  openni::VideoFrameRef frameRef;
96 };
97 
99 {
100  image.setPixelCode(VOCAB_PIXEL_RGB);
101 }
102 
103 void streamFrameListener::onNewFrame(openni::VideoStream& stream)
104 {
105  std::lock_guard<std::mutex> guard(mutex);
106  stream.readFrame(&frameRef);
107 
108  if (!frameRef.isValid() || !frameRef.getData())
109  {
110  yCInfo(DEPTHCAMERA) << "Frame lost";
111  return;
112  }
113 
114  int pixC;
115 
116  pixF = stream.getVideoMode().getPixelFormat();
118  w = frameRef.getWidth();
119  h = frameRef.getHeight();
120  dataSize = frameRef.getDataSize();
121 
122  if (isReady == false)
123  {
124  isReady = true;
125  }
126 
127  if (pixC == VOCAB_PIXEL_INVALID)
128  {
129  yCError(DEPTHCAMERA) << "Pixel Format not recognized";
130  return;
131  }
132 
133  image.setPixelCode(pixC);
134  image.resize(w, h);
135 
136  if (image.getRawImageSize() != (size_t) frameRef.getDataSize())
137  {
138  yCError(DEPTHCAMERA) << "Device and local copy data size doesn't match";
139  return;
140  }
141 
142  memcpy((void*)image.getRawImage(), (void*)frameRef.getData(), frameRef.getDataSize());
143  stamp.update();
144  return;
145 }
146 
147 
148 depthCameraDriver::depthCameraDriver() : m_depthFrame(nullptr), m_imageFrame(nullptr), m_paramParser(nullptr)
149 {
150 
151  m_depthRegistration = true;
152  m_depthFrame = new streamFrameListener();
153  m_imageFrame = new streamFrameListener();
154  m_paramParser = new RGBDSensorParamParser();
155 
156  m_supportedFeatures.push_back(YARP_FEATURE_EXPOSURE);
157  m_supportedFeatures.push_back(YARP_FEATURE_WHITE_BALANCE);
158  m_supportedFeatures.push_back(YARP_FEATURE_GAIN);
159  m_supportedFeatures.push_back(YARP_FEATURE_FRAME_RATE);
160  m_supportedFeatures.push_back(YARP_FEATURE_MIRROR);
161 }
162 
164 {
165  close();
166  if (m_depthFrame)
167  delete m_depthFrame;
168  if (m_imageFrame)
169  delete m_imageFrame;
170  if (m_paramParser)
171  delete m_paramParser;
172 }
173 
174 bool depthCameraDriver::initializeOpeNIDevice()
175 {
176  Status rc;
177 
178  rc = OpenNI::initialize();
179  if (rc != STATUS_OK)
180  {
181  yCError(DEPTHCAMERA) << "Initialize failed," << OpenNI::getExtendedError();
182  return false;
183  }
184 
185  rc = m_device.open(ANY_DEVICE);
186  if (rc != STATUS_OK)
187  {
188  yCError(DEPTHCAMERA) << "Couldn't open device," << OpenNI::getExtendedError();
189  return false;
190  }
191 
192  if (m_device.getSensorInfo(SENSOR_COLOR) != nullptr)
193  {
194  rc = m_imageStream.create(m_device, SENSOR_COLOR);
195  if (rc != STATUS_OK)
196  {
197  yCError(DEPTHCAMERA) << "Couldn't create color stream," << OpenNI::getExtendedError();
198  return false;
199  }
200  }
201 
202  rc = m_imageStream.start();
203  if (rc != STATUS_OK)
204  {
205  yCError(DEPTHCAMERA) << "Couldn't start the color stream," << OpenNI::getExtendedError();
206  return false;
207  }
208 
209  if (m_device.getSensorInfo(SENSOR_DEPTH) != nullptr)
210  {
211  rc = m_depthStream.create(m_device, SENSOR_DEPTH);
212  if (rc != STATUS_OK)
213  {
214  yCError(DEPTHCAMERA) << "Couldn't create depth stream," << OpenNI::getExtendedError();
215  return false;
216  }
217  }
218 
219  if (m_depthRegistration)
220  {
221  if (m_device.isImageRegistrationModeSupported(IMAGE_REGISTRATION_DEPTH_TO_COLOR))
222  {
223  if (m_device.setImageRegistrationMode(IMAGE_REGISTRATION_DEPTH_TO_COLOR) == STATUS_OK)
224  {
225  yCInfo(DEPTHCAMERA) << "Depth successfully registered on rgb sensor";
226  }
227  else
228  {
229  yCWarning(DEPTHCAMERA) << "Depth registration failed.. sending unregistered images";
230  }
231  }
232  else
233  {
234  yCWarning(DEPTHCAMERA) << "Depth image registration not supported by this device";
235  }
236  }
237 
238  rc = m_depthStream.start();
239  if (rc != STATUS_OK)
240  {
241  yCError(DEPTHCAMERA) << "Couldn't start the depth stream," << OpenNI::getExtendedError();
242  return false;
243  }
244 
245  m_imageStream.addNewFrameListener(m_imageFrame);
246  m_depthStream.addNewFrameListener(m_depthFrame);
247 
248  return true;
249 }
250 
251 
252 void depthCameraDriver::settingErrorMsg(const string& error, bool& ret)
253 {
254  yCError(DEPTHCAMERA) << error;
255  ret = false;
256 }
257 
258 bool depthCameraDriver::setParams()
259 {
260  bool ret;
261  ret = true;
262 
263  // Do all required settings
264 
265  //ACCURACY
266  if (params_map[accuracy].isSetting && ret)
267  {
268  if (!params_map[accuracy].val[0].isFloat64() )
269  settingErrorMsg("Param " + params_map[accuracy].name + " is not a double as it should be.", ret);
270 
271  if (! setDepthAccuracy(params_map[accuracy].val[0].asFloat64() ) )
272  settingErrorMsg("Setting param " + params_map[accuracy].name + " failed... quitting.", ret);
273  }
274 
275  //CLIP_PLANES
276  if (params_map[clipPlanes].isSetting && ret)
277  {
278  if (!params_map[clipPlanes].val[0].isFloat64() )
279  settingErrorMsg("Param " + params_map[clipPlanes].name + " is not a double as it should be.", ret);
280 
281  if (!params_map[clipPlanes].val[1].isFloat64() )
282  settingErrorMsg("Param " + params_map[clipPlanes].name + " is not a double as it should be.", ret);
283 
284  if (! setDepthClipPlanes(params_map[clipPlanes].val[0].asFloat64(), params_map[clipPlanes].val[1].asFloat64() ) )
285  settingErrorMsg("Setting param " + params_map[clipPlanes].name + " failed... quitting.", ret);
286  }
287 
288  //DEPTH_FOV
289  if (params_map[depth_Fov].isSetting && ret)
290  {
291  Value p1, p2;
292  p1 = params_map[depth_Fov].val[0];
293  p2 = params_map[depth_Fov].val[1];
294 
295  if (!p1.isFloat64() || !p2.isFloat64() )
296  settingErrorMsg("Param " + params_map[depth_Fov].name + " is not a double as it should be.", ret);
297 
298  if (! setDepthFOV(p1.asFloat64(), p2.asFloat64() ) )
299  settingErrorMsg("Setting param " + params_map[depth_Fov].name + " failed... quitting.", ret);
300  }
301 
302 
303 
304  //RGB_FOV
305  if (params_map[rgb_Fov].isSetting && ret)
306  {
307  Value p1, p2;
308  p1 = params_map[rgb_Fov].val[0];
309  p2 = params_map[rgb_Fov].val[1];
310 
311  if (!p1.isFloat64() || !p2.isFloat64() )
312  {
313  settingErrorMsg("Param " + params_map[rgb_Fov].name + " is not a double as it should be.", ret);
314  }
315 
316  if (! setRgbFOV(p1.asFloat64(), p2.asFloat64() ) )
317  {
318  settingErrorMsg("Setting param " + params_map[rgb_Fov].name + " failed... quitting.", ret);
319  }
320  }
321 
322  //DEPTH_RES
323  if (params_map[depthRes].isSetting && ret)
324  {
325  Value p1, p2;
326  p1 = params_map[depthRes].val[0];
327  p2 = params_map[depthRes].val[1];
328 
329  if (!p1.isInt32() || !p2.isInt32() )
330  {
331  settingErrorMsg("Param " + params_map[depthRes].name + " is not a int as it should be.", ret);
332  }
333 
334  if (! setDepthResolution(p1.asInt32(), p2.asInt32()))
335  {
336  settingErrorMsg("Setting param " + params_map[depthRes].name + " failed... quitting.", ret);
337  }
338  }
339 
340  //RGB_RES
341  if (params_map[rgbRes].isSetting && ret)
342  {
343  Value p1, p2;
344  p1 = params_map[rgbRes].val[0];
345  p2 = params_map[rgbRes].val[1];
346 
347  if (!p1.isInt32() || !p2.isInt32() )
348  {
349  settingErrorMsg("Param " + params_map[rgbRes].name + " is not a int as it should be.", ret);
350  }
351 
352  if (! setRgbResolution(p1.asInt32(), p2.asInt32()))
353  {
354  settingErrorMsg("Setting param " + params_map[rgbRes].name + " failed... quitting.", ret);
355  }
356  }
357 
358  // rgb MIRRORING
359  if (params_map[rgbMirroring].isSetting && ret)
360  {
361  //the device usually fail to set the mirror properties at the start.
362  //so we will try to set it for 5 times with a little delay before returning false
363  bool mirrorOk;
364  Value& v = params_map[rgbMirroring].val[0];
365  mirrorOk = false;
366 
367  if (!v.isBool())
368  {
369  settingErrorMsg("Param " + params_map[rgbMirroring].name + " is not a bool as it should be.", ret);
370  return false;
371  }
372 
373  for (int t = 0; t < 5; t++)
374  {
375  yCInfo(DEPTHCAMERA) << "Trying to set rgb mirroring parameter for the" << t+1 << "time/s";
377  if (setRgbMirroring(v.asBool()))
378  {
379  yCInfo(DEPTHCAMERA) << "Rgb mirroring parameter set successfully";
380  mirrorOk = true;
381  break;
382  }
383  }
384  if (!mirrorOk)
385  {
386  settingErrorMsg("Setting param " + params_map[rgbMirroring].name + " failed... quitting.", ret);
387  }
388  }
389  // depth MIRRORING
390  if (params_map[depthMirroring].isSetting && ret)
391  {
392  //the device usually fail to set the mirror properties at the start.
393  //so we will try to set it for 5 times with a little delay before returning false
394  bool mirrorOk;
395  Value& v = params_map[depthMirroring].val[0];
396  mirrorOk = false;
397 
398  if (!v.isBool() )
399  {
400  settingErrorMsg("Param " + params_map[depthMirroring].name + " is not a bool as it should be.", ret);
401  }
402 
403  for (int t = 0; t < 5; t++)
404  {
405  yCInfo(DEPTHCAMERA) << "Trying to set depth mirroring parameter for the" << t+1 << "time/s";
407  if (setDepthMirroring(v.asBool()))
408  {
409  yCInfo(DEPTHCAMERA) << "Depth mirroring parameter set successfully";
410  mirrorOk = true;
411  break;
412  }
413  }
414  if (!mirrorOk)
415  {
416  settingErrorMsg("Setting param " + params_map[depthMirroring].name + " failed... quitting.", ret);
417  }
418  }
419  return ret;
420 }
421 
422 
424 {
425  std::vector<RGBDSensorParamParser::RGBDParam*> params;
426  for (auto& p:params_map)
427  {
428  params.push_back(&(p.second));
429  }
430 
431  if (!m_paramParser->parseParam(config, params))
432  {
433  yCError(DEPTHCAMERA) << "Failed to parse the parameters";
434  return false;
435  }
436 
437  //"registered" is a hidden parameter for debugging pourpose
438  m_depthRegistration = !(config.check("registered") && config.find("registered").isBool() && config.find("registered").asBool() == false);
439 
440  if (!initializeOpeNIDevice())
441  {
442  return false;
443  }
444 
445  // setting Parameters
446  if (!setParams())
447  {
448  return false;
449  }
450 
451  return true;
452 }
453 
455 {
456  m_imageStream.stop();
457  m_imageStream.destroy();
458  m_depthStream.stop();
459  m_depthStream.destroy();
460  m_device.close();
461  OpenNI::shutdown();
462  return true;
463 }
464 
466 {
467  if (params_map[rgbRes].isDescription)
468  {
469  return params_map[rgbRes].val.at(1).asInt32();
470  }
471 
472  return m_imageStream.getVideoMode().getResolutionY();
473 }
474 
476 {
477  if (params_map[rgbRes].isDescription)
478  {
479  return params_map[rgbRes].val.at(0).asInt32();
480  }
481 
482  return m_imageStream.getVideoMode().getResolutionX();
483 }
484 
486 {
487  yCWarning(DEPTHCAMERA) << "getRgbSupportedConfigurations not implemented yet";
488  return false;
489 }
490 
491 bool depthCameraDriver::getRgbResolution(int &width, int &height)
492 {
493  if (params_map[rgbRes].isDescription)
494  {
495  return params_map[rgbRes].val.at(0).asInt32();
496  }
497  else{
498  width = m_imageStream.getVideoMode().getResolutionX();
499  height = m_imageStream.getVideoMode().getResolutionY();
500  }
501  return true;
502 }
503 
504 bool depthCameraDriver::setDepthResolution(int width, int height)
505 {
506  if (params_map[depthRes].isDescription)
507  {
508  yCError(DEPTHCAMERA) << "Cannot set. Depth resolution is a description!";
509  return false;
510  }
511 
512  return setResolution(width, height, m_depthStream);
513 }
514 
515 bool depthCameraDriver::setResolution(int width, int height, VideoStream& stream)
516 {
517  VideoMode vm;
518  bool bRet;
519 
520  vm = stream.getVideoMode();
521  vm.setResolution(width, height);
522  stream.stop();
523  bRet = (stream.setVideoMode(vm) == STATUS_OK);
524  RETURN_FALSE_STATUS_NOT_OK(stream.start());
525 
526  if (!bRet)
527  {
528  yCError(DEPTHCAMERA) << OpenNI::getExtendedError();
529  }
530 
531  return bRet;
532 }
533 
534 bool depthCameraDriver::setRgbResolution(int width, int height)
535 {
536  if (params_map[rgbRes].isDescription)
537  {
538  return false;
539  }
540 
541  return setResolution(width, height, m_imageStream);
542 }
543 
544 bool depthCameraDriver::setFOV(double horizontalFov, double verticalFov, VideoStream& stream)
545 {
546  RETURN_FALSE_STATUS_NOT_OK(stream.setProperty(STREAM_PROPERTY_VERTICAL_FOV, verticalFov * DEG2RAD));
547  RETURN_FALSE_STATUS_NOT_OK(stream.setProperty(STREAM_PROPERTY_HORIZONTAL_FOV, horizontalFov * DEG2RAD));
548  return true;
549 }
550 
551 bool depthCameraDriver::setRgbFOV(double horizontalFov, double verticalFov)
552 {
553  if (params_map[rgb_Fov].isDescription)
554  {
555  return false;
556  }
557  return setFOV(horizontalFov, verticalFov, m_depthStream);
558 }
559 
560 bool depthCameraDriver::setDepthFOV(double horizontalFov, double verticalFov)
561 {
562  if (params_map[depth_Fov].isDescription)
563  {
564  return false;
565  }
566  return setFOV(horizontalFov, verticalFov, m_depthStream);
567 }
568 
570 {
571  if (params_map[accuracy].isDescription)
572  {
573  return false;
574  }
575  bool a1, a2;
576  a1 = fabs(_accuracy - 0.001) < 0.00001;
577  a2 = fabs(_accuracy - 0.0001) < 0.00001;
578  if (!a1 && !a2)
579  {
580  yCError(DEPTHCAMERA) << "Supporting accuracy of 1mm (0.001) or 100um (0.0001) only at the moment";
581  return false;
582  }
583 
584  PixelFormat pf;
585  VideoMode vm;
586  bool ret;
587 
588  vm = m_imageStream.getVideoMode();
589  pf = fabs(_accuracy - 0.001) < 0.00001 ? PIXEL_FORMAT_DEPTH_1_MM : PIXEL_FORMAT_DEPTH_100_UM;
590 
591  vm.setPixelFormat(pf);
592  m_depthStream.stop();
593  ret = m_depthStream.setVideoMode(vm) == STATUS_OK;
594  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.start());
595 
596  if (!ret)
597  {
598  yCError(DEPTHCAMERA) << OpenNI::getExtendedError();
599  }
600  return ret;
601 }
602 
603 bool depthCameraDriver::getRgbFOV(double &horizontalFov, double &verticalFov)
604 {
605  if (params_map[rgb_Fov].isDescription)
606  {
607  horizontalFov = params_map[rgb_Fov].val[0].asFloat64();
608  verticalFov = params_map[rgb_Fov].val[1].asFloat64();
609  return true;
610  }
611  horizontalFov = m_imageStream.getHorizontalFieldOfView() * RAD2DEG;
612  verticalFov = m_imageStream.getVerticalFieldOfView() * RAD2DEG;
613  return true;
614 }
615 
617 {
618  if (params_map[rgbMirroring].isDescription)
619  {
620  mirror = params_map[rgbMirroring].val[0].asBool();
621  return true;
622  }
623 
624  mirror = m_imageStream.getMirroringEnabled();
625  return true;
626 }
627 
629 {
630  if (params_map[rgbMirroring].isDescription)
631  {
632  return false;
633  }
634 
635  if (m_imageStream.setMirroringEnabled(mirror) != STATUS_OK)
636  {
637  return false;
638  }
639 
640  bool ret;
642  return (ret == mirror);
643 }
644 
645 bool depthCameraDriver::setIntrinsic(Property& intrinsic, const yarp::sig::IntrinsicParams& values)
646 {
647  values.toProperty(intrinsic);
648  return true;
649 }
650 
652 {
653  return setIntrinsic(intrinsic, m_paramParser->rgbIntrinsic);
654 }
655 
657 {
658  if (params_map[depthRes].isDescription)
659  {
660  return params_map[depthRes].val[1].asFloat64();
661  }
662  return m_depthStream.getVideoMode().getResolutionY();
663 }
664 
666 {
667  if (params_map[depthRes].isDescription)
668  {
669  return params_map[depthRes].val[0].asFloat64();
670  }
671  return m_depthStream.getVideoMode().getResolutionX();
672 }
673 
674 bool depthCameraDriver::getDepthFOV(double& horizontalFov, double& verticalFov)
675 {
676  if (params_map[depth_Fov].isDescription)
677  {
678  horizontalFov = params_map[depth_Fov].val[0].asFloat64();
679  verticalFov = params_map[depth_Fov].val[1].asFloat64();
680  return true;
681  }
682  horizontalFov = m_depthStream.getHorizontalFieldOfView() * RAD2DEG;
683  verticalFov = m_depthStream.getVerticalFieldOfView() * RAD2DEG;
684  return true;
685 }
686 
688 {
689  return setIntrinsic(intrinsic, m_paramParser->rgbIntrinsic);
690 }
691 
693 {
694  if (params_map[accuracy].isDescription)
695  {
696  return params_map[accuracy].val[0].asFloat64();
697  }
698  return m_depthStream.getVideoMode().getPixelFormat() == PIXEL_FORMAT_DEPTH_1_MM ? 0.001 : 0.0001;
699 }
700 
701 bool depthCameraDriver::getDepthClipPlanes(double& nearPlane, double& farPlane)
702 {
703  if (params_map[clipPlanes].isDescription)
704  {
705  nearPlane = params_map[clipPlanes].val[0].asFloat64();
706  farPlane = params_map[clipPlanes].val[1].asFloat64();
707  return true;
708  }
709  double factor;
710  factor = getDepthAccuracy();
711  nearPlane = m_depthStream.getMinPixelValue() * factor;
712  farPlane = m_depthStream.getMaxPixelValue() * factor;
713  return true;
714 }
715 
716 bool depthCameraDriver::setDepthClipPlanes(double nearPlane, double farPlane)
717 {
718  if (params_map[clipPlanes].isDescription)
719  {
720  return false;
721  }
722  double factor;
723  factor = getDepthAccuracy();
724  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.setProperty(STREAM_PROPERTY_MAX_VALUE, int(farPlane / factor)));
725  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.setProperty(STREAM_PROPERTY_MIN_VALUE, int(nearPlane / factor)));
726  return true;
727 }
728 
730 {
731  if (params_map[depthMirroring].isDescription)
732  {
733  return params_map[depthMirroring].val[0].asBool();
734  }
735  mirror = m_depthStream.getMirroringEnabled();
736  return true;
737 }
738 
740 {
741  if (params_map[depthMirroring].isDescription)
742  {
743  return false;
744  }
745  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.setMirroringEnabled(mirror));
746 
747  bool ret;
749  return (ret == mirror);
750 }
751 
753 {
754  extrinsic = m_paramParser->transformationMatrix;
755  return true;
756 }
757 
758 bool depthCameraDriver::getRgbImage(FlexImage& rgbImage, Stamp* timeStamp)
759 {
760  return getImage(rgbImage, timeStamp, m_imageFrame);
761 }
762 
764 {
765  return getImage(depthImage, timeStamp, m_depthFrame);
766 }
767 
769 {
770  //pixel size interpretation based on openni2_camera/src/openni2_frame_listener.cpp:
771  /*switch (video_mode.getPixelFormat())
772  {
773  case openni::PIXEL_FORMAT_DEPTH_1_MM:
774  image->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
775  image->step = sizeof(unsigned char) * 2 * image->width;
776  break;
777  case openni::PIXEL_FORMAT_DEPTH_100_UM:
778  image->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
779  image->step = sizeof(unsigned char) * 2 * image->width;
780  break;
781  case openni::PIXEL_FORMAT_SHIFT_9_2:
782  image->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
783  image->step = sizeof(unsigned char) * 2 * image->width;
784  break;
785  case openni::PIXEL_FORMAT_SHIFT_9_3:
786  image->encoding = sensor_msgs::image_encodings::TYPE_16UC1;
787  image->step = sizeof(unsigned char) * 2 * image->width;
788  break;
789  */
790  switch(p)
791  {
792  case (PIXEL_FORMAT_RGB888):
793  return VOCAB_PIXEL_RGB;
794 
795  case (PIXEL_FORMAT_DEPTH_1_MM):
796  return VOCAB_PIXEL_MONO16;
797 
798  case (PIXEL_FORMAT_DEPTH_100_UM):
799  return VOCAB_PIXEL_MONO16;
800 
801  case (PIXEL_FORMAT_SHIFT_9_2):
802  return VOCAB_PIXEL_INVALID;
803 
804  case (PIXEL_FORMAT_SHIFT_9_3):
805  return VOCAB_PIXEL_INVALID;
806 
807  case (PIXEL_FORMAT_GRAY8):
808  return VOCAB_PIXEL_MONO;
809 
810  case (PIXEL_FORMAT_GRAY16):
811  return VOCAB_PIXEL_MONO16;
812 
813  default:
814  return VOCAB_PIXEL_INVALID;
815  }
816  return VOCAB_PIXEL_INVALID;
817 }
818 
819 bool depthCameraDriver::getImage(FlexImage& Frame, Stamp* Stamp, streamFrameListener* sourceFrame)
820 {
821  bool ret = sourceFrame->getImage(Frame);
822  *Stamp = sourceFrame->getStamp();
823  return ret;
824 }
825 
826 bool depthCameraDriver::getImage(ImageOf<PixelFloat>& Frame, Stamp* Stamp, streamFrameListener* sourceFrame)
827 {
828  std::lock_guard<std::mutex> guard(sourceFrame->mutex);
829  if (!sourceFrame->isReady)
830  {
831  yCError(DEPTHCAMERA) << "Device not ready";
832  return false;
833  }
834  int w, h, i;
835  w = sourceFrame->w;
836  h = sourceFrame->h;
837 
838  if (sourceFrame->dataSize != size_t(h * w * sizeof(short)) ||
839  (sourceFrame->pixF != PIXEL_FORMAT_DEPTH_100_UM && sourceFrame->pixF != PIXEL_FORMAT_DEPTH_1_MM))
840  {
841  yCError(DEPTHCAMERA) << "getImage: image format error";
842  return false;
843  }
844 
845  float factor;
846  float* rawImage;
847  short* srcRawImage;
848 
849  srcRawImage = reinterpret_cast<short*> (sourceFrame->image.getRawImage());
850  factor = sourceFrame->pixF == PIXEL_FORMAT_DEPTH_1_MM ? 0.001 : 0.0001;
851 
852  Frame.resize(w, h);
853  rawImage = reinterpret_cast<float*> (Frame.getRawImage());
854 
855  //TODO: optimize short-to-float cast and multiplication using SSE/SIMD instruction
856  for(i = 0; i < w * h; i++)
857  {
858  rawImage[i] = srcRawImage[i] * factor;
859  }
860  *Stamp = sourceFrame->stamp;
861  return true;
862 }
863 
864 bool depthCameraDriver::getImages(FlexImage& colorFrame, ImageOf<PixelFloat>& depthFrame, Stamp* colorStamp, Stamp* depthStamp)
865 {
866  return getImage(colorFrame, colorStamp, m_imageFrame) & getImage(depthFrame, depthStamp, m_depthFrame);
867 }
868 
870 {
871  openni::DeviceState status;
872  status = DEVICE_STATE_NOT_READY;
873  if (m_device.isValid() &&
874  m_imageStream.isValid() &&
875  m_depthStream.isValid() &&
876  m_imageFrame->isValid() &&
877  m_depthFrame->isValid())
878  {
879  status = DEVICE_STATE_OK;
880  }
881  switch(status)
882  {
883  case DEVICE_STATE_OK:
884  return RGBD_SENSOR_OK_IN_USE;
885 
886  case DEVICE_STATE_NOT_READY:
887  return RGBD_SENSOR_NOT_READY;
888 
889  default:
891  }
892 
894 }
895 
897 {
898  return OpenNI::getExtendedError();
899 }
900 
902 {
903  camera->deviceDescription = m_device.getDeviceInfo().getName();
904  camera->busType = BUS_USB;
905  return true;
906 }
907 
908 bool depthCameraDriver::hasFeature(int feature, bool* hasFeature)
909 {
911  f = static_cast<cameraFeature_id_t>(feature);
912  if (f < YARP_FEATURE_BRIGHTNESS || f > YARP_FEATURE_NUMBER_OF-1)
913  {
914  return false;
915  }
916 
917  if (std::find(m_supportedFeatures.begin(), m_supportedFeatures.end(), f) != m_supportedFeatures.end())
918  {
919  *hasFeature = true;
920  }
921  else
922  {
923  *hasFeature = false;
924  }
925 
926  return true;
927 }
928 
929 bool depthCameraDriver::setFeature(int feature, double value)
930 {
931  bool b;
932  if (!hasFeature(feature, &b) || !b)
933  {
934  yCError(DEPTHCAMERA) << "Feature not supported!";
935  return false;
936  }
937 
938  auto f = static_cast<cameraFeature_id_t>(feature);
939  switch(f)
940  {
942  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.getCameraSettings()->setExposure(int(value * 100)+1));
943  break;
944  case YARP_FEATURE_GAIN:
945  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.getCameraSettings()->setGain(int(value * 100)+1));
946  break;
948  {
949  VideoMode vm;
950 
951  vm = m_imageStream.getVideoMode();
952  vm.setFps(int(value));
953  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.setVideoMode(vm));
954 
955  m_depthStream.getVideoMode();
956  vm.setFps(int(value));
957  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.setVideoMode(vm));
958  break;
959  }
961  yCError(DEPTHCAMERA) << "No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode instead of wasting my time";
962  return false;
963  default:
964  yCError(DEPTHCAMERA) << "Feature not supported!";
965  return false;
966  }
967  return true;
968 }
969 
970 bool depthCameraDriver::getFeature(int feature, double *value)
971 {
972  bool b;
973  if (!hasFeature(feature, &b) || !b)
974  {
975  yCError(DEPTHCAMERA) << "Feature not supported!";
976  return false;
977  }
978 
979  auto f = static_cast<cameraFeature_id_t>(feature);
980  switch(f)
981  {
983  *value = m_imageStream.getCameraSettings()->getExposure();
984  break;
985  case YARP_FEATURE_GAIN:
986  *value = m_imageStream.getCameraSettings()->getGain();
987  break;
989  *value = (m_imageStream.getVideoMode().getFps());
990  break;
992  yCError(DEPTHCAMERA) << "No manual mode for white_balance. call hasManual() to know if a specific feature support Manual mode";
993  return false;
994  default:
995  return false;
996  }
997  return true;
998 }
999 
1000 bool depthCameraDriver::setFeature(int feature, double value1, double value2)
1001 {
1002  yCError(DEPTHCAMERA) << "No 2-valued feature are supported";
1003  return false;
1004 }
1005 
1006 bool depthCameraDriver::getFeature(int feature, double *value1, double *value2)
1007 {
1008  yCError(DEPTHCAMERA) << "No 2-valued feature are supported";
1009  return false;
1010 }
1011 
1012 bool depthCameraDriver::hasOnOff( int feature, bool *HasOnOff)
1013 {
1014  bool b;
1015  if (!hasFeature(feature, &b) || !b)
1016  {
1017  yCError(DEPTHCAMERA) << "Feature not supported!";
1018  return false;
1019  }
1020 
1021  auto f = static_cast<cameraFeature_id_t>(feature);
1023  {
1024  *HasOnOff = true;
1025  return true;
1026  }
1027  *HasOnOff = false;
1028  return true;
1029 }
1030 
1031 bool depthCameraDriver::setActive( int feature, bool onoff)
1032 {
1033  bool b;
1034  if (!hasFeature(feature, &b) || !b)
1035  {
1036  yCError(DEPTHCAMERA) << "Feature not supported!";
1037  return false;
1038  }
1039 
1040  if (!hasOnOff(feature, &b) || !b)
1041  {
1042  yCError(DEPTHCAMERA) << "Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1043  return false;
1044  }
1045 
1046  switch(feature)
1047  {
1048  case YARP_FEATURE_MIRROR:
1049  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.setProperty(STREAM_PROPERTY_MIRRORING, onoff));
1050  RETURN_FALSE_STATUS_NOT_OK(m_depthStream.setProperty(STREAM_PROPERTY_MIRRORING, onoff));
1051  break;
1053  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.getCameraSettings()->setAutoWhiteBalanceEnabled(onoff));
1054  break;
1055  default:
1056  return false;
1057  }
1058 
1059 
1060  return true;
1061 }
1062 
1063 bool depthCameraDriver::getActive( int feature, bool *isActive)
1064 {
1065  bool b;
1066  if (!hasFeature(feature, &b) || !b)
1067  {
1068  yCError(DEPTHCAMERA) << "Feature not supported!";
1069  return false;
1070  }
1071 
1072  if (!hasOnOff(feature, &b) || !b)
1073  {
1074  yCError(DEPTHCAMERA) << "Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1075  return false;
1076  }
1077 
1078  *isActive = m_imageStream.getCameraSettings()->getAutoWhiteBalanceEnabled();
1079  return true;
1080 }
1081 
1082 bool depthCameraDriver::hasAuto(int feature, bool *hasAuto)
1083 {
1084  bool b;
1085  if (!hasFeature(feature, &b) || !b)
1086  {
1087  yCError(DEPTHCAMERA) << "Feature not supported!";
1088  return false;
1089  }
1090 
1091  auto f = static_cast<cameraFeature_id_t>(feature);
1093  {
1094  *hasAuto = true;
1095  return true;
1096  }
1097  *hasAuto = false;
1098  return true;
1099 }
1100 
1101 bool depthCameraDriver::hasManual( int feature, bool* hasManual)
1102 {
1103  bool b;
1104  if (!hasFeature(feature, &b) || !b)
1105  {
1106  yCError(DEPTHCAMERA) << "Feature not supported!";
1107  return false;
1108  }
1109 
1110  auto f = static_cast<cameraFeature_id_t>(feature);
1112  {
1113  *hasManual = true;
1114  return true;
1115  }
1116  *hasManual = false;
1117  return true;
1118 }
1119 
1120 bool depthCameraDriver::hasOnePush(int feature, bool* hasOnePush)
1121 {
1122  bool b;
1123  if (!hasFeature(feature, &b) || !b)
1124  {
1125  yCError(DEPTHCAMERA) << "Feature not supported!";
1126  return false;
1127  }
1128 
1129  return hasAuto(feature, hasOnePush);
1130 }
1131 
1133 {
1134  bool b;
1135  if (!hasFeature(feature, &b) || !b)
1136  {
1137  yCError(DEPTHCAMERA) << "Feature not supported!";
1138  return false;
1139  }
1140 
1141  auto f = static_cast<cameraFeature_id_t>(feature);
1142  if (f == YARP_FEATURE_EXPOSURE)
1143  {
1144  switch(mode)
1145  {
1146  case MODE_AUTO:
1147  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.getCameraSettings()->setAutoExposureEnabled(true));
1148  break;
1149  case MODE_MANUAL:
1150  RETURN_FALSE_STATUS_NOT_OK(m_imageStream.getCameraSettings()->setAutoExposureEnabled(false));
1151  break;
1152  case MODE_UNKNOWN:
1153  return false;
1154  default:
1155  return false;
1156  }
1157  return true;
1158  }
1159 
1160  yCError(DEPTHCAMERA) << "Feature does not have both auto and manual mode";
1161  return false;
1162 }
1163 
1164 bool depthCameraDriver::getMode(int feature, FeatureMode* mode)
1165 {
1166  bool b;
1167  if (!hasFeature(feature, &b) || !b)
1168  {
1169  yCError(DEPTHCAMERA) << "Feature not supported!";
1170  return false;
1171  }
1172 
1173  auto f = static_cast<cameraFeature_id_t>(feature);
1174  if (f == YARP_FEATURE_EXPOSURE)
1175  {
1176  *mode = m_imageStream.getCameraSettings()->getAutoExposureEnabled() ? MODE_AUTO : MODE_MANUAL;
1177  return true;
1178  }
1179 
1180  yCError(DEPTHCAMERA) << "Feature does not have both auto and manual mode";
1181  return false;
1182 }
1183 
1185 {
1186  bool b;
1187  if (!hasFeature(feature, &b) || !b)
1188  {
1189  yCError(DEPTHCAMERA) << "Feature not supported!";
1190  return false;
1191  }
1192 
1193  if (!hasOnePush(feature, &b) || !b)
1194  {
1195  yCError(DEPTHCAMERA) << "Feature doesn't have OnePush";
1196  return false;
1197  }
1198 
1199  setMode(feature, MODE_AUTO);
1200  setMode(feature, MODE_MANUAL);
1201 
1202  return true;
1203 }
float t
cameraFeature_id_t
@ YARP_FEATURE_NUMBER_OF
@ YARP_FEATURE_FRAME_RATE
@ YARP_FEATURE_WHITE_BALANCE
@ YARP_FEATURE_EXPOSURE
@ YARP_FEATURE_MIRROR
@ YARP_FEATURE_GAIN
@ MODE_UNKNOWN
bool ret
#define DEG2RAD
#define RAD2DEG
Definition: MapGrid2D.cpp:34
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
int getDepthHeight() override
Return the height of each frame.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
int getRgbHeight() override
Return the height of each frame.
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool close() override
Close the DeviceDriver.
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=NULL) override
Get the rgb frame from the device.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
int getRgbWidth() override
Return the width of each frame.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
int getDepthWidth() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=NULL) override
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
static int pixFormatToCode(openni::PixelFormat p)
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
bool getImage(FlexImage &inputImage)
yarp::sig::FlexImage image
openni::PixelFormat pixF
yarp::os::Stamp getStamp()
The RGBDSensorParamParser class.
bool parseParam(const yarp::os::Searchable &config, std::vector< RGBDParam * > &params)
parseParam, parse the params stored in a Searchable.
yarp::sig::IntrinsicParams rgbIntrinsic
A class for storing options and configuration information.
Definition: Property.h:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
static void delaySystem(double seconds)
Definition: SystemClock.cpp:32
A single value (typically within a Bottle).
Definition: Value.h:47
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
virtual bool isBool() const
Checks if value is a boolean.
Definition: Value.cpp:117
virtual bool asBool() const
Get boolean value.
Definition: Value.cpp:189
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:153
virtual bool isInt32() const
Checks if value is a 32-bit integer.
Definition: Value.cpp:135
Image class with user control of representation details.
Definition: Image.h:403
Typed image class.
Definition: Image.h:647
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition: Image.cpp:535
bool copy(const Image &alt)
Copy operator.
Definition: Image.cpp:847
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
Definition: Image.cpp:467
A class for a Matrix.
Definition: Matrix.h:46
Provides:
Definition: Vector.h:122
#define RETURN_FALSE_STATUS_NOT_OK(s)
static std::map< std::string, RGBDSensorParamParser::RGBDParam > params_map
#define yCInfo(component,...)
Definition: LogComponent.h:135
#define yCError(component,...)
Definition: LogComponent.h:157
#define yCWarning(component,...)
Definition: LogComponent.h:146
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
@ VOCAB_PIXEL_MONO16
Definition: Image.h:49
@ VOCAB_PIXEL_INVALID
Definition: Image.h:47
@ VOCAB_PIXEL_MONO
Definition: Image.h:48
@ VOCAB_PIXEL_RGB
Definition: Image.h:50
An interface for the device drivers.
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:25
constexpr char clipPlanes[]
constexpr char rgbRes[]
constexpr char depthRes[]
constexpr char accuracy[]
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).
void toProperty(yarp::os::Property &intrinsic) const
toProperty, convert the struct to a Property.