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>
11#include <yarp/os/LogStream.h>
13#include "rosPixelCode.h"
16
17using namespace RGBDImpl;
18using namespace yarp::sig;
19using namespace yarp::dev;
20using namespace yarp::os;
21
22
23#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
24#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
25
26YARP_LOG_COMPONENT(RGBDSENSORWRAPPER, "yarp.devices.RGBDSensorWrapper")
27
28
30 iRGBDSensor(nullptr)
31{
32}
33
34bool RGBDSensorParser::configure(IRGBDSensor *interface)
35{
36 bool ret;
37 iRGBDSensor = interface;
38 ret = rgbParser.configure(interface);
39 ret &= depthParser.configure(interface);
40 return ret;
41}
42
43bool 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
55bool 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
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;
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 {
113 response.addVocab32(VOCAB_ERROR_MSG);
114 response.addVocab32(VOCAB_IS);
115 response.addString(iRGBDSensor->getLastErrorMsg());
116 ret = true;
117 }
118 break;
119
121 {
124 response.addVocab32(VOCAB_IS);
127 }
128 break;
129
130 case VOCAB_STATUS:
131 {
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.7 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 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
246 return true;
247}
248
250{
251 if (!config.check("period", "refresh period of the broadcasted values in ms"))
252 {
253 if (verbose >= 3) {
254 yCInfo(RGBDSENSORWRAPPER) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
255 }
256 } else {
257 period = config.find("period").asInt32() / 1000.0;
258 }
259
260 Bottle &rosGroup = config.findGroup("ROS");
261 if(rosGroup.isNull())
262 {
263 if (verbose >= 3) {
264 yCInfo(RGBDSENSORWRAPPER) << "ROS configuration parameters are not set, skipping ROS topic initialization.";
265 }
266 use_ROS = false;
267 use_YARP = true;
268 }
269 else
270 {
271 //if(verbose >= 2)
272 // yCWarning(RGBDSENSORWRAPPER) << "RGBDSensorWrapper: ROS topic support is not yet implemented";
273
274 std::string confUseRos;
275
276 if (!rosGroup.check("use_ROS"))
277 {
278 yCError(RGBDSENSORWRAPPER)<<"Missing use_ROS parameter";
279 return false;
280 }
281
282 confUseRos = rosGroup.find("use_ROS").asString();
283
284 if (confUseRos == "true" || confUseRos == "only")
285 {
286 use_ROS = true;
287 use_YARP = confUseRos == "true" ? true : false;
288 }
289 else
290 {
291 use_ROS = false;
292 if (verbose >= 3 && confUseRos != "false")
293 {
294 yCInfo(RGBDSENSORWRAPPER, "'use_ROS' value not understood.. skipping ROS topic initialization");
295 }
296 }
297 }
298
299 if (use_ROS)
300 {
301 //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value.
302 unsigned int i;
303 std::vector<param<std::string> > rosStringParam;
304 param<std::string>* prm;
305
306 rosStringParam.emplace_back(nodeName, nodeName_param );
307 rosStringParam.emplace_back(rosFrameId, frameId_param );
308 rosStringParam.emplace_back(colorTopicName, colorTopicName_param );
309 rosStringParam.emplace_back(depthTopicName, depthTopicName_param );
310 rosStringParam.emplace_back(cInfoTopicName, colorInfoTopicName_param);
311 rosStringParam.emplace_back(dInfoTopicName, depthInfoTopicName_param);
312
313 for (i = 0; i < rosStringParam.size(); i++)
314 {
315 prm = &rosStringParam[i];
316 if (!rosGroup.check(prm->parname))
317 {
318 if(verbose >= 3)
319 {
320 yCError(RGBDSENSORWRAPPER) << "Missing " << prm->parname << "check your configuration file, not using ROS";
321 }
322 use_ROS = false;
323 return false;
324 }
325 *(prm->var) = rosGroup.find(prm->parname).asString();
326 }
327
328 if (rosGroup.check("forceInfoSync"))
329 {
330 forceInfoSync = rosGroup.find("forceInfoSync").asBool();
331 }
332 }
333
334 if(use_YARP)
335 {
336 std::string rootName;
337 rootName = config.check("name",Value("/"), "starting '/' if needed.").asString();
338
339 if (!config.check("name", "Prefix name of the ports opened by the RGBD wrapper.")) {
340 yCError(RGBDSENSORWRAPPER) << "Missing 'name' parameter. Check you configuration file; it must be like:";
341 yCError(RGBDSENSORWRAPPER) << " name: Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD";
342 return false;
343 }
344
345 rootName = config.find("name").asString();
346 rpcPort_Name = rootName + "/rpc:i";
347 colorFrame_StreamingPort_Name = rootName + "/rgbImage:o";
348 depthFrame_StreamingPort_Name = rootName + "/depthImage:o";
349 }
350
351 if(config.check("subdevice")) {
352 isSubdeviceOwned=true;
353 } else {
354 isSubdeviceOwned=false;
355 }
356
357 return true;
358}
359
360bool RGBDSensorWrapper::openDeferredAttach(Searchable& prop)
361{
362 // I dunno what to do here now...
363 isSubdeviceOwned = false;
364 return true;
365}
366
367bool RGBDSensorWrapper::openAndAttachSubDevice(Searchable& prop)
368{
369 Property p;
370 subDeviceOwned = new PolyDriver;
371 p.fromString(prop.toString());
372
373 p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
374 p.unput("device");
375 p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before
376
377 // if errors occurred during open, quit here.
378 yCDebug(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice");
379 subDeviceOwned->open(p);
380
381 if (!subDeviceOwned->isValid())
382 {
383 yCError(RGBDSENSORWRAPPER, "Opening IRGBDSensor subdevice... FAILED");
384 return false;
385 }
386 isSubdeviceOwned = true;
387 if(!attach(subDeviceOwned)) {
388 return false;
389 }
390
391 return true;
392}
393
395{
396 yCTrace(RGBDSENSORWRAPPER, "Close");
397 detachAll();
398
399 // close subdevice if it was created inside the open (--subdevice option)
400 if(isSubdeviceOwned)
401 {
402 if(subDeviceOwned)
403 {
404 delete subDeviceOwned;
405 subDeviceOwned=nullptr;
406 }
407 sensor_p = nullptr;
408 fgCtrl = nullptr;
409 isSubdeviceOwned = false;
410 }
411
412 // Closing port
413 if(use_YARP)
414 {
415 rpcPort.interrupt();
416 colorFrame_StreamingPort.interrupt();
417 depthFrame_StreamingPort.interrupt();
418
419 rpcPort.close();
420 colorFrame_StreamingPort.close();
421 depthFrame_StreamingPort.close();
422 }
423
424 if(rosNode!=nullptr)
425 {
426 rosNode->interrupt();
427 delete rosNode;
428 rosNode = nullptr;
429 }
430
431 // Closing ROS topic
432 if(use_ROS)
433 {
434 // bla bla bla
435 }
436 //
437 return true;
438}
439
440/* Helper functions */
441
442bool RGBDSensorWrapper::initialize_YARP(yarp::os::Searchable &params)
443{
444 // Open ports
445 bool bRet;
446 bRet = true;
447 if(!rpcPort.open(rpcPort_Name))
448 {
449 yCError(RGBDSENSORWRAPPER) << "Unable to open rpc Port" << rpcPort_Name.c_str();
450 bRet = false;
451 }
452 rpcPort.setReader(rgbdParser);
453
454 if(!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name))
455 {
456 yCError(RGBDSENSORWRAPPER) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str();
457 bRet = false;
458 }
459 if(!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name))
460 {
461 yCError(RGBDSENSORWRAPPER) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str();
462 bRet = false;
463 }
464
465 return bRet;
466}
467
468bool RGBDSensorWrapper::initialize_ROS(yarp::os::Searchable &params)
469{
470 // open topics here if needed
471 rosNode = new yarp::os::Node(nodeName);
472 nodeSeq = 0;
473 if (!rosPublisherPort_color.topic(colorTopicName))
474 {
475 yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << colorTopicName.c_str() << " topic, check your yarp-ROS network configuration";
476 return false;
477 }
478 if (!rosPublisherPort_depth.topic(depthTopicName))
479 {
480 yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << depthTopicName.c_str() << " topic, check your yarp-ROS network configuration";
481 return false;
482 }
483 if (!rosPublisherPort_colorCaminfo.topic(cInfoTopicName))
484 {
485 yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << cInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration";
486 return false;
487 }
488 if (!rosPublisherPort_depthCaminfo.topic(dInfoTopicName))
489 {
490 yCError(RGBDSENSORWRAPPER) << "Unable to publish data on " << dInfoTopicName.c_str() << " topic, check your yarp-ROS network configuration";
491 return false;
492 }
493 return true;
494}
495
500{
501 // First implementation only accepts devices with both the interfaces Framegrabber and IDepthSensor,
502 // on a second version maybe two different devices could be accepted, one for each interface.
503 // Yet to be defined which and how parameters shall be used in this case ... using the name of the
504 // interface to view could be a good initial guess.
505 if (device2attach.size() != 1)
506 {
507 yCError(RGBDSENSORWRAPPER, "Cannot attach more than one device");
508 return false;
509 }
510
511 yarp::dev::PolyDriver * Idevice2attach = device2attach[0]->poly;
512 if(device2attach[0]->key == "IRGBDSensor")
513 {
514 yCInfo(RGBDSENSORWRAPPER) << "Good name!";
515 }
516 else
517 {
518 yCInfo(RGBDSENSORWRAPPER) << "Bad name!";
519 }
520
521 if (!Idevice2attach->isValid())
522 {
523 yCError(RGBDSENSORWRAPPER) << "Device " << device2attach[0]->key << " to attach to is not valid ... cannot proceed";
524 return false;
525 }
526
527 Idevice2attach->view(sensor_p);
528 Idevice2attach->view(fgCtrl);
529 if (!attach(sensor_p)) {
530 return false;
531 }
532
533 PeriodicThread::setPeriod(period);
534 return PeriodicThread::start();
535}
536
538{
541 }
542
543 //check if we already instantiated a subdevice previously
544 if (isSubdeviceOwned) {
545 return false;
546 }
547
548 sensor_p = nullptr;
549 return true;
550}
551
553{
554 if(s == nullptr)
555 {
556 yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface.";
557 return false;
558 }
559 sensor_p = s;
560 if(!rgbdParser.configure(sensor_p))
561 {
562 yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers";
563 return false;
564 }
565 if (fgCtrl)
566 {
567 if(!rgbdParser.configure(fgCtrl))
568 {
569 yCError(RGBDSENSORWRAPPER) << "Error configuring interfaces for parsers";
570 return false;
571 }
572 }
573
574 PeriodicThread::setPeriod(period);
575 return PeriodicThread::start();
576}
577
579{
580 if(poly)
581 {
582 poly->view(sensor_p);
583 poly->view(fgCtrl);
584 }
585
586 if(sensor_p == nullptr)
587 {
588 yCError(RGBDSENSORWRAPPER) << "Attached device has no valid IRGBDSensor interface.";
589 return false;
590 }
591
592 if(!rgbdParser.configure(sensor_p))
593 {
594 yCError(RGBDSENSORWRAPPER) << "Error configuring IRGBD interface";
595 return false;
596 }
597
598 if (!rgbdParser.configure(fgCtrl))
599 {
600 yCWarning(RGBDSENSORWRAPPER) <<"Interface IFrameGrabberControl not implemented by the device";
601 }
602
603 PeriodicThread::setPeriod(period);
604 return PeriodicThread::start();
605}
606
608{
609 sensor_p = nullptr;
610 return true;
611}
612
613/* IRateThread interface */
614
616{
617 // Get interface from attached device if any.
618 return true;
619}
620
622{
623 // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
624}
625
626bool RGBDSensorWrapper::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
627{
628 double phyF = 0.0;
629 double fx = 0.0;
630 double fy = 0.0;
631 double cx = 0.0;
632 double cy = 0.0;
633 double k1 = 0.0;
634 double k2 = 0.0;
635 double t1 = 0.0;
636 double t2 = 0.0;
637 double k3 = 0.0;
638 double stamp = 0.0;
639
640 std::string distModel;
641 std::string currentSensor;
642 UInt i;
643 Property camData;
644 std::vector<param<double> > parVector;
645 param<double>* par;
646 bool ok;
647
648 currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
649 ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
650
651 if (!ok)
652 {
653 yCError(RGBDSENSORWRAPPER) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
654 return false;
655 }
656
657 if(!camData.check("distortionModel"))
658 {
659 yCWarning(RGBDSENSORWRAPPER) << "Missing distortion model";
660 return false;
661 }
662
663 distModel = camData.find("distortionModel").asString();
664 if (distModel != "plumb_bob")
665 {
666 yCError(RGBDSENSORWRAPPER) << "Distortion model not supported";
667 return false;
668 }
669
670 //std::vector<param<std::string> > rosStringParam;
671 //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
672
673 parVector.emplace_back(phyF,"physFocalLength");
674 parVector.emplace_back(fx,"focalLengthX");
675 parVector.emplace_back(fy,"focalLengthY");
676 parVector.emplace_back(cx,"principalPointX");
677 parVector.emplace_back(cy,"principalPointY");
678 parVector.emplace_back(k1,"k1");
679 parVector.emplace_back(k2,"k2");
680 parVector.emplace_back(t1,"t1");
681 parVector.emplace_back(t2,"t2");
682 parVector.emplace_back(k3,"k3");
683 parVector.emplace_back(stamp,"stamp");
684 for(i = 0; i < parVector.size(); i++)
685 {
686 par = &parVector[i];
687
688 if(!camData.check(par->parname))
689 {
690 yCWarning(RGBDSENSORWRAPPER) << "Driver has not the param:" << par->parname;
691 return false;
692 }
693 *par->var = camData.find(par->parname).asFloat64();
694 }
695
696 cameraInfo.header.frame_id = frame_id;
697 cameraInfo.header.seq = seq;
698 cameraInfo.header.stamp = stamp;
699 cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth();
700 cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight();
701 cameraInfo.distortion_model = distModel;
702
703 cameraInfo.D.resize(5);
704 cameraInfo.D[0] = k1;
705 cameraInfo.D[1] = k2;
706 cameraInfo.D[2] = t1;
707 cameraInfo.D[3] = t2;
708 cameraInfo.D[4] = k3;
709
710 cameraInfo.K.resize(9);
711 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
712 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
713 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
714
715 /*
716 * ROS documentation on cameraInfo message:
717 * "Rectification matrix (stereo cameras only)
718 * A rotation matrix aligning the camera coordinate system to the ideal
719 * stereo image plane so that epipolar lines in both stereo images are
720 * parallel."
721 * useless in our case, it will be an identity matrix
722 */
723
724 cameraInfo.R.assign(9, 0);
725 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
726
727 cameraInfo.P.resize(12);
728 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
729 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
730 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
731
732 cameraInfo.binning_x = cameraInfo.binning_y = 0;
733 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
734 cameraInfo.roi.do_rectify = false;
735 return true;
736}
737
738bool RGBDSensorWrapper::writeData()
739{
740 //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
741 // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
742
743 // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
744 // depthImage.resize(hDim, vDim);
745 if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
746 {
747 return false;
748 }
749
750 static Stamp oldColorStamp = Stamp(0, 0);
751 static Stamp oldDepthStamp = Stamp(0, 0);
752 bool rgb_data_ok = true;
753 bool depth_data_ok = true;
754
755 if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
756 {
757 rgb_data_ok=false;
758 //return true;
759 }
760 else { oldColorStamp = colorStamp; }
761
762 if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
763 {
764 depth_data_ok=false;
765 //return true;
766 }
767 else { oldDepthStamp = depthStamp; }
768
769
770 if (use_YARP)
771 {
772 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
773 if (rgb_data_ok)
774 {
775 FlexImage& yColorImage = colorFrame_StreamingPort.prepare();
777 colorFrame_StreamingPort.setEnvelope(colorStamp);
778 colorFrame_StreamingPort.write();
779 }
780 if (depth_data_ok)
781 {
782 ImageOf<PixelFloat>& yDepthImage = depthFrame_StreamingPort.prepare();
784 depthFrame_StreamingPort.setEnvelope(depthStamp);
785 depthFrame_StreamingPort.write();
786 }
787 }
788 if (use_ROS)
789 {
790 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
791 if (rgb_data_ok)
792 {
793 yarp::rosmsg::sensor_msgs::Image& rColorImage = rosPublisherPort_color.prepare();
794 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = rosPublisherPort_colorCaminfo.prepare();
795 yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime();
796 yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, rosFrameId, cRosStamp, nodeSeq);
797 rosPublisherPort_color.setEnvelope(colorStamp);
798 rosPublisherPort_color.write();
799 if (setCamInfo(camInfoC, rosFrameId, nodeSeq, COLOR_SENSOR))
800 {
801 if(forceInfoSync)
802 {camInfoC.header.stamp = rColorImage.header.stamp;}
803 rosPublisherPort_colorCaminfo.setEnvelope(colorStamp);
804 rosPublisherPort_colorCaminfo.write();
805 }
806 else
807 {
808 yCWarning(RGBDSENSORWRAPPER, "Missing color camera parameters... camera info messages will be not sent");
809 }
810 }
811 if (depth_data_ok)
812 {
813 yarp::rosmsg::sensor_msgs::Image& rDepthImage = rosPublisherPort_depth.prepare();
814 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = rosPublisherPort_depthCaminfo.prepare();
815 yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime();
816 yarp::dev::RGBDRosConversionUtils::deepCopyImages(depthImage, rDepthImage, rosFrameId, dRosStamp, nodeSeq);
817 rosPublisherPort_depth.setEnvelope(depthStamp);
818 rosPublisherPort_depth.write();
819 if (setCamInfo(camInfoD, rosFrameId, nodeSeq, DEPTH_SENSOR))
820 {
821 if(forceInfoSync)
822 {camInfoD.header.stamp = rDepthImage.header.stamp;}
823 rosPublisherPort_depthCaminfo.setEnvelope(depthStamp);
824 rosPublisherPort_depthCaminfo.write();
825 }
826 else
827 {
828 yCWarning(RGBDSENSORWRAPPER, "Missing depth camera parameters... camera info messages will be not sent");
829 }
830 }
831
832 nodeSeq++;
833 }
834 return true;
835}
836
838{
839 if (sensor_p!=nullptr)
840 {
841 static int i = 0;
842 sensorStatus = sensor_p->getSensorStatus();
843 switch (sensorStatus)
844 {
845 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
846 {
847 if (!writeData()) {
848 yCError(RGBDSENSORWRAPPER, "Image not captured.. check hardware configuration");
849 }
850 i = 0;
851 }
852 break;
853 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
854 {
855 if(i < 1000) {
856 if((i % 30) == 0) {
857 yCInfo(RGBDSENSORWRAPPER) << "Device not ready, waiting...";
858 }
859 } else {
860 yCWarning(RGBDSENSORWRAPPER) << "Device is taking too long to start..";
861 }
862 i++;
863 }
864 break;
865 default:
866 {
867 if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
868 yCError(RGBDSENSORWRAPPER, "%s: Sensor returned error", sensorId.c_str());
869 }
870 }
871 }
872 }
873 else
874 {
875 if(verbose >= 6) {
876 yCError(RGBDSENSORWRAPPER, "%s: Sensor interface is not valid", sensorId.c_str());
877 }
878 }
879}
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 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:88
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:39
virtual std::string getLastErrorMsg(yarp::os::Stamp *timeStamp=nullptr)=0
Return an error message in case of error.
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.
virtual bool getExtrinsicParam(yarp::sig::Matrix &extrinsic)=0
Get the extrinsic parameters from the device.
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:23
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:64
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:23
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:511
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:383
void close() override
Stop port activity.
Definition: Port.cpp:363
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:33
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:63
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:148
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:123
A base class for nested structures that can be searched.
Definition: Searchable.h:63
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 Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
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:21
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
A single value (typically within a Bottle).
Definition: Value.h:43
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
bool configure(yarp::dev::IDepthVisualParams *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool configure(yarp::dev::IFrameGrabberControls *interface)
bool configure(yarp::dev::IRgbVisualParams *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
Image class with user control of representation details.
Definition: Image.h:411
A class for a Matrix.
Definition: Matrix.h:39
yarp::os::Node * rosNode
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCTrace(component,...)
Definition: LogComponent.h:84
#define yCWarning(component,...)
Definition: LogComponent.h:192
#define yCDebug(component,...)
Definition: LogComponent.h:128
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
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
yarp::rosmsg::sensor_msgs::Image Image
Definition: Image.h:21
yarp::rosmsg::sensor_msgs::CameraInfo CameraInfo
Definition: CameraInfo.h:21
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)
For streams capable of holding different kinds of content, check what they actually have.
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.