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