YARP
Yet Another Robot Platform
RGBDSensorWrapper.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #include "RGBDSensorWrapper.h"
7 #include <sstream>
8 #include <cstdio>
9 #include <cstring>
10 #include <yarp/os/LogComponent.h>
11 #include <yarp/os/LogStream.h>
13 #include "rosPixelCode.h"
14 #include <RGBDRosConversionUtils.h>
16 
17 using namespace RGBDImpl;
18 using namespace yarp::sig;
19 using namespace yarp::dev;
20 using namespace yarp::os;
21 
22 
23 #define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
24 #define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
25 
26 YARP_LOG_COMPONENT(RGBDSENSORWRAPPER, "yarp.devices.RGBDSensorWrapper")
27 
28 
30  iRGBDSensor(nullptr)
31 {
32 }
33 
35 {
36  bool ret;
37  iRGBDSensor = interface;
38  ret = rgbParser.configure(interface);
39  ret &= depthParser.configure(interface);
40  return ret;
41 }
42 
43 bool RGBDSensorParser::configure(IRgbVisualParams *rgbInterface, IDepthVisualParams* depthInterface)
44 {
45  bool ret = rgbParser.configure(rgbInterface);
46  ret &= depthParser.configure(depthInterface);
47  return ret;
48 }
49 
51 {
52  return fgCtrlParsers.configure(_fgCtrl);
53 }
54 
55 bool RGBDSensorParser::respond(const Bottle& cmd, Bottle& response)
56 {
57  bool ret = false;
58  int interfaceType = cmd.get(0).asVocab32();
59 
60  response.clear();
61  switch(interfaceType)
62  {
64  {
65  // forwarding to the proper parser.
66  ret = rgbParser.respond(cmd, response);
67  }
68  break;
69 
71  {
72  // forwarding to the proper parser.
73  ret = depthParser.respond(cmd, response);
74  }
75  break;
76 
78  {
79  // forwarding to the proper parser.
80  ret = fgCtrlParsers.respond(cmd, response);
81  }
82  break;
83 
84  case VOCAB_RGBD_SENSOR:
85  {
86  switch (cmd.get(1).asVocab32())
87  {
88  case VOCAB_GET:
89  {
90  switch(cmd.get(2).asVocab32())
91  {
93  {
94  yarp::sig::Matrix params;
95  ret = iRGBDSensor->getExtrinsicParam(params);
96  if(ret)
97  {
98  yarp::os::Bottle params_b;
99  response.addVocab32(VOCAB_RGBD_SENSOR);
101  response.addVocab32(VOCAB_IS);
102  ret &= Property::copyPortable(params, params_b); // will it really work??
103  response.append(params_b);
104  } else {
105  response.addVocab32(VOCAB_FAILED);
106  }
107  }
108  break;
109 
110  case VOCAB_ERROR_MSG:
111  {
112  response.addVocab32(VOCAB_RGBD_SENSOR);
113  response.addVocab32(VOCAB_ERROR_MSG);
114  response.addVocab32(VOCAB_IS);
115  response.addString(iRGBDSensor->getLastErrorMsg());
116  ret = true;
117  }
118  break;
119 
121  {
122  response.addVocab32(VOCAB_RGBD_SENSOR);
124  response.addVocab32(VOCAB_IS);
127  }
128  break;
129 
130  case VOCAB_STATUS:
131  {
132  response.addVocab32(VOCAB_RGBD_SENSOR);
133  response.addVocab32(VOCAB_STATUS);
134  response.addVocab32(VOCAB_IS);
135  response.addInt32(iRGBDSensor->getSensorStatus());
136  }
137  break;
138 
139  default:
140  {
141  yCError(RGBDSENSORWRAPPER) << "Interface parser received an unknown GET command. Command is " << cmd.toString();
142  response.addVocab32(VOCAB_FAILED);
143  }
144  break;
145  }
146  }
147  break;
148 
149  case VOCAB_SET:
150  {
151  yCError(RGBDSENSORWRAPPER) << "Interface parser received an unknown SET command. Command is " << cmd.toString();
152  response.addVocab32(VOCAB_FAILED);
153  }
154  break;
155  }
156  }
157  break;
158 
159  default:
160  {
161  yCError(RGBDSENSORWRAPPER) << "Received a command for a wrong interface " << yarp::os::Vocab32::decode(interfaceType);
162  return DeviceResponder::respond(cmd,response);
163  }
164  break;
165  }
166  return ret;
167 }
168 
169 
172  rosNode(nullptr),
173  nodeSeq(0),
174  period(DEFAULT_THREAD_PERIOD),
175  sensor_p(nullptr),
176  fgCtrl(nullptr),
177  sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY),
178  verbose(4),
179  use_YARP(true),
180  use_ROS(false),
181  forceInfoSync(true),
182  isSubdeviceOwned(false),
183  subDeviceOwned(nullptr)
184 {}
185 
187 {
188  close();
189  sensor_p = nullptr;
190  fgCtrl = nullptr;
191 }
192 
196 {
197  yCWarning(RGBDSENSORWRAPPER) << "The 'RGBDSensorWrapper' device is deprecated in favour of 'rgbdSensor_nws_yarp'.";
198  yCWarning(RGBDSENSORWRAPPER) << "The old device is no longer supported, and it will be deprecated in YARP 3.6 and removed in YARP 4.";
199  yCWarning(RGBDSENSORWRAPPER) << "Please update your scripts.";
200 
201 // DeviceResponder::makeUsage();
202 // addUsage("[set] [bri] $fBrightness", "set brightness");
203 // addUsage("[set] [expo] $fExposure", "set exposure");
204 //
205  m_conf.fromString(config.toString());
206  if (verbose >= 5) {
207  yCTrace(RGBDSENSORWRAPPER) << "\nParameters are: \n"
208  << config.toString();
209  }
210 
211  if(!fromConfig(config))
212  {
213  yCError(RGBDSENSORWRAPPER) << "Failed to open, check previous log for error messages.";
214  return false;
215  }
216 
217  setId("RGBDSensorWrapper for " + depthFrame_StreamingPort_Name);
218 
219  if(use_YARP && !initialize_YARP(config))
220  {
221  yCError(RGBDSENSORWRAPPER) << sensorId << "Error initializing YARP ports";
222  return false;
223  }
224 
225  if(use_ROS && !initialize_ROS(config))
226  {
227  yCError(RGBDSENSORWRAPPER) << sensorId << "Error initializing ROS topic";
228  return false;
229  }
230 
231  // check if we need to create subdevice or if they are
232  // passed later on through attachAll()
233  if(isSubdeviceOwned)
234  {
235  if(! openAndAttachSubDevice(config))
236  {
237  yCError(RGBDSENSORWRAPPER, "Error while opening subdevice");
238  return false;
239  }
240  }
241  else
242  {
243  if (!openDeferredAttach(config)) {
244  return false;
245  }
246  }
247 
248  return true;
249 }
250 
252 {
253  if (!config.check("period", "refresh period of the broadcasted values in ms"))
254  {
255  if (verbose >= 3) {
256  yCInfo(RGBDSENSORWRAPPER) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
257  }
258  } else {
259  period = config.find("period").asInt32() / 1000.0;
260  }
261 
262  Bottle &rosGroup = config.findGroup("ROS");
263  if(rosGroup.isNull())
264  {
265  if (verbose >= 3) {
266  yCInfo(RGBDSENSORWRAPPER) << "ROS configuration parameters are not set, skipping ROS topic initialization.";
267  }
268  use_ROS = false;
269  use_YARP = true;
270  }
271  else
272  {
273  //if(verbose >= 2)
274  // yCWarning(RGBDSENSORWRAPPER) << "RGBDSensorWrapper: ROS topic support is not yet implemented";
275 
276  std::string confUseRos;
277 
278  if (!rosGroup.check("use_ROS"))
279  {
280  yCError(RGBDSENSORWRAPPER)<<"Missing use_ROS parameter";
281  return false;
282  }
283 
284  confUseRos = rosGroup.find("use_ROS").asString();
285 
286  if (confUseRos == "true" || confUseRos == "only")
287  {
288  use_ROS = true;
289  use_YARP = confUseRos == "true" ? true : false;
290  }
291  else
292  {
293  use_ROS = false;
294  if (verbose >= 3 && confUseRos != "false")
295  {
296  yCInfo(RGBDSENSORWRAPPER, "'use_ROS' value not understood.. skipping ROS topic initialization");
297  }
298  }
299  }
300 
301  if (use_ROS)
302  {
303  //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value.
304  unsigned int i;
305  std::vector<param<std::string> > rosStringParam;
306  param<std::string>* prm;
307 
308  rosStringParam.emplace_back(nodeName, nodeName_param );
309  rosStringParam.emplace_back(rosFrameId, frameId_param );
310  rosStringParam.emplace_back(colorTopicName, colorTopicName_param );
311  rosStringParam.emplace_back(depthTopicName, depthTopicName_param );
312  rosStringParam.emplace_back(cInfoTopicName, colorInfoTopicName_param);
313  rosStringParam.emplace_back(dInfoTopicName, depthInfoTopicName_param);
314 
315  for (i = 0; i < rosStringParam.size(); i++)
316  {
317  prm = &rosStringParam[i];
318  if (!rosGroup.check(prm->parname))
319  {
320  if(verbose >= 3)
321  {
322  yCError(RGBDSENSORWRAPPER) << "Missing " << prm->parname << "check your configuration file, not using ROS";
323  }
324  use_ROS = false;
325  return false;
326  }
327  *(prm->var) = rosGroup.find(prm->parname).asString();
328  }
329 
330  if (rosGroup.check("forceInfoSync"))
331  {
332  forceInfoSync = rosGroup.find("forceInfoSync").asBool();
333  }
334  }
335 
336  if(use_YARP)
337  {
338  std::string rootName;
339  rootName = config.check("name",Value("/"), "starting '/' if needed.").asString();
340 
341  if (!config.check("name", "Prefix name of the ports opened by the RGBD wrapper.")) {
342  yCError(RGBDSENSORWRAPPER) << "Missing 'name' parameter. Check you configuration file; it must be like:";
343  yCError(RGBDSENSORWRAPPER) << " name: Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD";
344  return false;
345  }
346 
347  rootName = config.find("name").asString();
348  rpcPort_Name = rootName + "/rpc:i";
349  colorFrame_StreamingPort_Name = rootName + "/rgbImage:o";
350  depthFrame_StreamingPort_Name = rootName + "/depthImage:o";
351  }
352 
353  if(config.check("subdevice")) {
354  isSubdeviceOwned=true;
355  } else {
356  isSubdeviceOwned=false;
357  }
358 
359  return true;
360 }
361 
362 bool RGBDSensorWrapper::openDeferredAttach(Searchable& prop)
363 {
364  // I dunno what to do here now...
365  isSubdeviceOwned = false;
366  return true;
367 }
368 
369 bool RGBDSensorWrapper::openAndAttachSubDevice(Searchable& prop)
370 {
371  Property p;
372  subDeviceOwned = new PolyDriver;
373  p.fromString(prop.toString());
374 
375  p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
376  p.unput("device");
377  p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before
378 
379  // if errors occurred during open, quit here.
380  yCDebug(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice");
381  subDeviceOwned->open(p);
382 
383  if (!subDeviceOwned->isValid())
384  {
385  yCError(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice... FAILED");
386  return false;
387  }
388  isSubdeviceOwned = true;
389  if(!attach(subDeviceOwned)) {
390  return false;
391  }
392 
393  return true;
394 }
395 
397 {
398  yCTrace(RGBDSENSORWRAPPER, "Close");
399  detachAll();
400 
401  // close subdevice if it was created inside the open (--subdevice option)
402  if(isSubdeviceOwned)
403  {
404  if(subDeviceOwned)
405  {
406  delete subDeviceOwned;
407  subDeviceOwned=nullptr;
408  }
409  sensor_p = nullptr;
410  fgCtrl = nullptr;
411  isSubdeviceOwned = false;
412  }
413 
414  // Closing port
415  if(use_YARP)
416  {
417  rpcPort.interrupt();
418  colorFrame_StreamingPort.interrupt();
419  depthFrame_StreamingPort.interrupt();
420 
421  rpcPort.close();
422  colorFrame_StreamingPort.close();
423  depthFrame_StreamingPort.close();
424  }
425 
426  if(rosNode!=nullptr)
427  {
428  rosNode->interrupt();
429  delete rosNode;
430  rosNode = nullptr;
431  }
432 
433  // Closing ROS topic
434  if(use_ROS)
435  {
436  // bla bla bla
437  }
438  //
439  return true;
440 }
441 
442 /* Helper functions */
443 
444 bool RGBDSensorWrapper::initialize_YARP(yarp::os::Searchable &params)
445 {
446  // Open ports
447  bool bRet;
448  bRet = true;
449  if(!rpcPort.open(rpcPort_Name))
450  {
451  yCError(RGBDSENSORWRAPPER) << "Unable to open rpc Port" << rpcPort_Name.c_str();
452  bRet = false;
453  }
454  rpcPort.setReader(rgbdParser);
455 
456  if(!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name))
457  {
458  yCError(RGBDSENSORWRAPPER) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str();
459  bRet = false;
460  }
461  if(!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name))
462  {
463  yCError(RGBDSENSORWRAPPER) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str();
464  bRet = false;
465  }
466 
467  return bRet;
468 }
469 
470 bool RGBDSensorWrapper::initialize_ROS(yarp::os::Searchable &params)
471 {
472  // open topics here if needed
473  rosNode = new yarp::os::Node(nodeName);
474  nodeSeq = 0;
475  if (!rosPublisherPort_color.topic(colorTopicName))
476  {
477  yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << colorTopicName.c_str() << " topic, check your yarp-ROS network configuration";
478  return false;
479  }
480  if (!rosPublisherPort_depth.topic(depthTopicName))
481  {
482  yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << depthTopicName.c_str() << " topic, check your yarp-ROS network configuration";
483  return false;
484  }
485  if (!rosPublisherPort_colorCaminfo.topic(cInfoTopicName))
486  {
487  yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << cInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration";
488  return false;
489  }
490  if (!rosPublisherPort_depthCaminfo.topic(dInfoTopicName))
491  {
492  yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << dInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration";
493  return false;
494  }
495  return true;
496 }
497 
498 void RGBDSensorWrapper::setId(const std::string &id)
499 {
500  sensorId=id;
501 }
502 
504 {
505  return sensorId;
506 }
507 
512 {
513  // First implementation only accepts devices with both the interfaces Framegrabber and IDepthSensor,
514  // on a second version maybe two different devices could be accepted, one for each interface.
515  // Yet to be defined which and how parameters shall be used in this case ... using the name of the
516  // interface to view could be a good initial guess.
517  if (device2attach.size() != 1)
518  {
519  yCError(RGBDSENSORWRAPPER, "Cannot attach more than one device");
520  return false;
521  }
522 
523  yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly;
524  if(device2attach[0]->key == "IRGBDSensor")
525  {
526  yCInfo(RGBDSENSORWRAPPER) << "Good name!";
527  }
528  else
529  {
530  yCInfo(RGBDSENSORWRAPPER) << "Bad name!";
531  }
532 
533  if (!Idevice2attach->isValid())
534  {
535  yCError(RGBDSENSORWRAPPER) << "Device " << device2attach[0]->key << " to attach to is not valid ... cannot proceed";
536  return false;
537  }
538 
539  Idevice2attach->view(sensor_p);
540  Idevice2attach->view(fgCtrl);
541  if (!attach(sensor_p)) {
542  return false;
543  }
544 
545  PeriodicThread::setPeriod(period);
546  return PeriodicThread::start();
547 }
548 
550 {
553  }
554 
555  //check if we already instantiated a subdevice previously
556  if (isSubdeviceOwned) {
557  return false;
558  }
559 
560  sensor_p = nullptr;
561  return true;
562 }
563 
565 {
566  if(s == nullptr)
567  {
568  yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface.";
569  return false;
570  }
571  sensor_p = s;
572  if(!rgbdParser.configure(sensor_p))
573  {
574  yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers";
575  return false;
576  }
577  if (fgCtrl)
578  {
579  if(!rgbdParser.configure(fgCtrl))
580  {
581  yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers";
582  return false;
583  }
584  }
585 
586  PeriodicThread::setPeriod(period);
587  return PeriodicThread::start();
588 }
589 
591 {
592  if(poly)
593  {
594  poly->view(sensor_p);
595  poly->view(fgCtrl);
596  }
597 
598  if(sensor_p == nullptr)
599  {
600  yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface.";
601  return false;
602  }
603 
604  if(!rgbdParser.configure(sensor_p))
605  {
606  yCError(RGBDSENSORWRAPPER) << "Error configuring IRGBD interface";
607  return false;
608  }
609 
610  if (!rgbdParser.configure(fgCtrl))
611  {
612  yCWarning(RGBDSENSORWRAPPER) <<"Interface IFrameGrabberControl not implemented by the device";
613  }
614 
615  PeriodicThread::setPeriod(period);
616  return PeriodicThread::start();
617 }
618 
620 {
621  sensor_p = nullptr;
622  return true;
623 }
624 
625 /* IRateThread interface */
626 
628 {
629  // Get interface from attached device if any.
630  return true;
631 }
632 
634 {
635  // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
636 }
637 
638 bool RGBDSensorWrapper::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
639 {
640  double phyF = 0.0;
641  double fx = 0.0;
642  double fy = 0.0;
643  double cx = 0.0;
644  double cy = 0.0;
645  double k1 = 0.0;
646  double k2 = 0.0;
647  double t1 = 0.0;
648  double t2 = 0.0;
649  double k3 = 0.0;
650  double stamp = 0.0;
651 
652  std::string distModel;
653  std::string currentSensor;
654  UInt i;
655  Property camData;
656  std::vector<param<double> > parVector;
657  param<double>* par;
658  bool ok;
659 
660  currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
661  ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
662 
663  if (!ok)
664  {
665  yCError(RGBDSENSORWRAPPER) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
666  return false;
667  }
668 
669  if(!camData.check("distortionModel"))
670  {
671  yCWarning(RGBDSENSORWRAPPER) << "Missing distortion model";
672  return false;
673  }
674 
675  distModel = camData.find("distortionModel").asString();
676  if (distModel != "plumb_bob")
677  {
678  yCError(RGBDSENSORWRAPPER) << "Distortion model not supported";
679  return false;
680  }
681 
682  //std::vector<param<std::string> > rosStringParam;
683  //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
684 
685  parVector.emplace_back(phyF,"physFocalLength");
686  parVector.emplace_back(fx,"focalLengthX");
687  parVector.emplace_back(fy,"focalLengthY");
688  parVector.emplace_back(cx,"principalPointX");
689  parVector.emplace_back(cy,"principalPointY");
690  parVector.emplace_back(k1,"k1");
691  parVector.emplace_back(k2,"k2");
692  parVector.emplace_back(t1,"t1");
693  parVector.emplace_back(t2,"t2");
694  parVector.emplace_back(k3,"k3");
695  parVector.emplace_back(stamp,"stamp");
696  for(i = 0; i < parVector.size(); i++)
697  {
698  par = &parVector[i];
699 
700  if(!camData.check(par->parname))
701  {
702  yCWarning(RGBDSENSORWRAPPER) << "Driver has not the param:" << par->parname;
703  return false;
704  }
705  *par->var = camData.find(par->parname).asFloat64();
706  }
707 
708  cameraInfo.header.frame_id = frame_id;
709  cameraInfo.header.seq = seq;
710  cameraInfo.header.stamp = stamp;
711  cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth();
712  cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight();
713  cameraInfo.distortion_model = distModel;
714 
715  cameraInfo.D.resize(5);
716  cameraInfo.D[0] = k1;
717  cameraInfo.D[1] = k2;
718  cameraInfo.D[2] = t1;
719  cameraInfo.D[3] = t2;
720  cameraInfo.D[4] = k3;
721 
722  cameraInfo.K.resize(9);
723  cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
724  cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
725  cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
726 
727  /*
728  * ROS documentation on cameraInfo message:
729  * "Rectification matrix (stereo cameras only)
730  * A rotation matrix aligning the camera coordinate system to the ideal
731  * stereo image plane so that epipolar lines in both stereo images are
732  * parallel."
733  * useless in our case, it will be an identity matrix
734  */
735 
736  cameraInfo.R.assign(9, 0);
737  cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
738 
739  cameraInfo.P.resize(12);
740  cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
741  cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
742  cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
743 
744  cameraInfo.binning_x = cameraInfo.binning_y = 0;
745  cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
746  cameraInfo.roi.do_rectify = false;
747  return true;
748 }
749 
750 bool RGBDSensorWrapper::writeData()
751 {
752  //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
753  // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
754 
755  // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
756  // depthImage.resize(hDim, vDim);
757  if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
758  {
759  return false;
760  }
761 
762  static Stamp oldColorStamp = Stamp(0, 0);
763  static Stamp oldDepthStamp = Stamp(0, 0);
764  bool rgb_data_ok = true;
765  bool depth_data_ok = true;
766 
767  if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
768  {
769  rgb_data_ok=false;
770  //return true;
771  }
772  else { oldColorStamp = colorStamp; }
773 
774  if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
775  {
776  depth_data_ok=false;
777  //return true;
778  }
779  else { oldDepthStamp = depthStamp; }
780 
781 
782  if (use_YARP)
783  {
784  // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
785  if (rgb_data_ok)
786  {
787  FlexImage& yColorImage = colorFrame_StreamingPort.prepare();
789  colorFrame_StreamingPort.setEnvelope(colorStamp);
790  colorFrame_StreamingPort.write();
791  }
792  if (depth_data_ok)
793  {
794  ImageOf<PixelFloat>& yDepthImage = depthFrame_StreamingPort.prepare();
796  depthFrame_StreamingPort.setEnvelope(depthStamp);
797  depthFrame_StreamingPort.write();
798  }
799  }
800  if (use_ROS)
801  {
802  // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
803  if (rgb_data_ok)
804  {
805  yarp::rosmsg::sensor_msgs::Image& rColorImage = rosPublisherPort_color.prepare();
806  yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = rosPublisherPort_colorCaminfo.prepare();
807  yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime();
808  yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, rosFrameId, cRosStamp, nodeSeq);
809  rosPublisherPort_color.setEnvelope(colorStamp);
810  rosPublisherPort_color.write();
811  if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR))
812  {
813  if(forceInfoSync)
814  {camInfoC.header.stamp = rColorImage.header.stamp;}
815  rosPublisherPort_colorCaminfo.setEnvelope(colorStamp);
816  rosPublisherPort_colorCaminfo.write();
817  }
818  else
819  {
820  yCWarning(RGBDSENSORWRAPPER, "Missing color camera parameters... camera info messages will be not sent");
821  }
822  }
823  if (depth_data_ok)
824  {
825  yarp::rosmsg::sensor_msgs::Image& rDepthImage = rosPublisherPort_depth.prepare();
826  yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = rosPublisherPort_depthCaminfo.prepare();
827  yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime();
828  yarp::dev::RGBDRosConversionUtils::deepCopyImages(depthImage, rDepthImage, rosFrameId, dRosStamp, nodeSeq);
829  rosPublisherPort_depth.setEnvelope(depthStamp);
830  rosPublisherPort_depth.write();
831  if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR))
832  {
833  if(forceInfoSync)
834  {camInfoD.header.stamp = rDepthImage.header.stamp;}
835  rosPublisherPort_depthCaminfo.setEnvelope(depthStamp);
836  rosPublisherPort_depthCaminfo.write();
837  }
838  else
839  {
840  yCWarning(RGBDSENSORWRAPPER, "Missing depth camera parameters... camera info messages will be not sent");
841  }
842  }
843 
844  nodeSeq++;
845  }
846  return true;
847 }
848 
850 {
851  if (sensor_p!=nullptr)
852  {
853  static int i = 0;
854  sensorStatus = sensor_p->getSensorStatus();
855  switch (sensorStatus)
856  {
857  case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
858  {
859  if (!writeData()) {
860  yCError(RGBDSENSORWRAPPER, "Image not captured.. check hardware configuration");
861  }
862  i = 0;
863  }
864  break;
865  case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
866  {
867  if(i < 1000) {
868  if((i % 30) == 0) {
869  yCInfo(RGBDSENSORWRAPPER) << "Device not ready, waiting...";
870  }
871  } else {
872  yCWarning(RGBDSENSORWRAPPER) << "Device is taking too long to start..";
873  }
874  i++;
875  }
876  break;
877  default:
878  {
879  if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
880  yCError(RGBDSENSORWRAPPER, "%s: Sensor returned error", sensorId.c_str());
881  }
882  }
883  }
884  }
885  else
886  {
887  if(verbose >= 6) {
888  yCError(RGBDSENSORWRAPPER, "%s: Sensor interface is not valid", sensorId.c_str());
889  }
890  }
891 }
constexpr yarp::conf::vocab32_t VOCAB_DEPTH_VISUAL_PARAMS
Definition: CameraVocabs.h:19
constexpr yarp::conf::vocab32_t VOCAB_RGBD_SENSOR
Definition: CameraVocabs.h:20
constexpr yarp::conf::vocab32_t VOCAB_RGB_VISUAL_PARAMS
Definition: CameraVocabs.h:18
constexpr yarp::conf::vocab32_t VOCAB_EXTRINSIC_PARAM
Definition: CameraVocabs.h:114
constexpr yarp::conf::vocab32_t VOCAB_RGBD_PROTOCOL_VERSION
Definition: CameraVocabs.h:21
constexpr yarp::conf::vocab32_t VOCAB_STATUS
Definition: CameraVocabs.h:119
constexpr yarp::conf::vocab32_t VOCAB_FRAMEGRABBER_CONTROL
Definition: CameraVocabs.h:39
constexpr yarp::conf::vocab32_t VOCAB_ERROR_MSG
Definition: CameraVocabs.h:115
constexpr yarp::conf::vocab32_t VOCAB_IS
Definition: GenericVocabs.h:14
constexpr yarp::conf::vocab32_t VOCAB_GET
Definition: GenericVocabs.h:13
constexpr yarp::conf::vocab32_t VOCAB_FAILED
Definition: GenericVocabs.h:16
constexpr yarp::conf::vocab32_t VOCAB_SET
Definition: GenericVocabs.h:12
bool ret
const yarp::os::LogComponent & RGBDSENSORWRAPPER()
#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR
#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR
constexpr double DEFAULT_THREAD_PERIOD
bool configure(yarp::dev::IRGBDSensor *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool detach() override
Detach the object (you must have first called attach).
bool attachAll(const yarp::dev::PolyDriverList &p) override
Specify which sensor this thread has to read from.
bool close() override
Close the DeviceDriver.
bool fromConfig(yarp::os::Searchable &params)
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool open(yarp::os::Searchable &params) override
Device driver interface.
void setId(const std::string &id)
void threadRelease() override
Release method.
bool detachAll() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:74
An interface for retrieving intrinsic parameter from a depth camera.
Control interface for frame grabber devices.
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:40
int getRgbWidth() override=0
Return the width of each frame.
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
int getDepthWidth() override=0
Return the height of each frame.
int getRgbHeight() override=0
Return the height of each frame.
virtual bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0
Get the both the color and depth frame in a single call.
virtual RGBDSensor_status getSensorStatus()=0
Get the surrent status of the sensor, using enum type.
int getDepthHeight() override=0
Return the height of each frame.
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the depth camera.
An interface for retrieving intrinsic parameter from a rgb camera.
A container for a device driver.
Definition: PolyDriver.h:24
bool isValid() const
Check if device is valid.
Definition: PolyDriver.cpp:196
bool open(const std::string &txt)
Construct and configure a device by its common name.
Definition: PolyDriver.cpp:140
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
Definition: Bottle.cpp:164
void append(const Bottle &alt)
Append the content of the given bottle to the current list.
Definition: Bottle.cpp:380
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:246
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
void clear()
Empties the bottle of any objects it contains.
Definition: Bottle.cpp:121
void addInt32(std::int32_t x)
Places a 32-bit integer in the bottle, at the end of the list.
Definition: Bottle.cpp:140
bool isNull() const override
Checks if the object is invalid.
Definition: Bottle.cpp:370
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:211
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:287
void close() override
Stop port activity.
bool setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
void interrupt() override
Interrupt any current reads or writes attached to the port.
void write(bool forceStrict=false)
Write the current object being returned by BufferedPort::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::BufferedPort::write.
The Node class.
Definition: Node.h:24
void interrupt()
interrupt delegates the call to the Node port interrupt.
Definition: Node.cpp:597
An abstraction for a periodic thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
void setReader(PortReader &reader) override
Set an external reader for port data.
Definition: Port.cpp:502
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:374
void close() override
Stop port activity.
Definition: Port.cpp:354
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
Definition: Port.cpp:79
A class for storing options and configuration information.
Definition: Property.h:34
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Property.cpp:1051
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Property.cpp:1041
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1046
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:64
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:124
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
A base class for nested structures that can be searched.
Definition: Searchable.h:66
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.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
A single value (typically within a Bottle).
Definition: Value.h:45
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition: Value.cpp:228
virtual bool asBool() const
Get boolean value.
Definition: Value.cpp:186
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:204
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
std::vector< yarp::conf::float64_t > R
Definition: CameraInfo.h:167
std::vector< yarp::conf::float64_t > K
Definition: CameraInfo.h:166
yarp::rosmsg::sensor_msgs::RegionOfInterest roi
Definition: CameraInfo.h:171
std::vector< yarp::conf::float64_t > P
Definition: CameraInfo.h:168
yarp::rosmsg::std_msgs::Header header
Definition: CameraInfo.h:161
std::vector< yarp::conf::float64_t > D
Definition: CameraInfo.h:165
yarp::rosmsg::std_msgs::Header header
Definition: Image.h:56
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
Image class with user control of representation details.
Definition: Image.h:414
A class for a Matrix.
Definition: Matrix.h:43
yarp::os::Node * rosNode
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
const std::string depthInfoTopicName_param
const std::string depthTopicName_param
const std::string colorTopicName_param
const std::string nodeName_param
const std::string frameId_param
const std::string colorInfoTopicName_param
void shallowCopyImages(const yarp::sig::FlexImage &src, yarp::sig::FlexImage &dest)
void deepCopyImages(const yarp::sig::FlexImage &src, yarp::rosmsg::sensor_msgs::Image &dest, const std::string &frame_id, const yarp::rosmsg::TickTime &timeStamp, const unsigned int &seq)
An interface for the device drivers.
std::string decode(NetInt32 code)
Convert a vocabulary identifier into a string.
Definition: Vocab.cpp:33
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:22