YARP
Yet Another Robot Platform
RgbdSensor_nws_ros.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
7#include "rosPixelCode.h"
8
10#include <yarp/os/LogStream.h>
13
15#include <cstdio>
16#include <cstring>
17#include <sstream>
18
19using namespace RGBDImpl;
20using namespace yarp::sig;
21using namespace yarp::dev;
22using namespace yarp::os;
23
24YARP_LOG_COMPONENT(RGBDSENSORNWSROS, "yarp.devices.RgbdSensor_nws_ros")
25
26
29 m_node(nullptr),
30 nodeSeq(0),
32 sensor_p(nullptr),
33 fgCtrl(nullptr),
34 sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY),
35 verbose(4),
36 forceInfoSync(true),
37 isSubdeviceOwned(false),
38 subDeviceOwned(nullptr)
39{}
40
42{
43 close();
44 sensor_p = nullptr;
45 fgCtrl = nullptr;
46}
47
51{
52 if(verbose >= 5)
53 {
54 yCTrace(RGBDSENSORNWSROS) << "\nParameters are: \n" << config.toString();
55 }
56 if (!config.check("period", "refresh period of the broadcasted values in s"))
57 {
58 if (verbose >= 3) {
59 yCInfo(RGBDSENSORNWSROS) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
60 }
61 }
62 else
63 {
64 period = config.find("period").asFloat64();
65 }
66
67 //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value.
68
69 if (config.check("forceInfoSync"))
70 {
71 forceInfoSync = config.find("forceInfoSync").asBool();
72 }
73
74 if(config.check("subdevice")) {
75 isSubdeviceOwned=true;
76 } else {
77 isSubdeviceOwned=false;
78 }
79
80 if(!initialize_ROS(config))
81 {
82 return false;
83 }
84
85 // check if we need to create subdevice or if they are
86 // passed later on through attachAll()
87 if(isSubdeviceOwned)
88 {
89 if(! openAndAttachSubDevice(config))
90 {
91 yCError(RGBDSENSORNWSROS, "Error while opening subdevice");
92 return false;
93 }
94 }
95 else
96 {
97 if (!openDeferredAttach(config)) {
98 return false;
99 }
100 }
101
102 return true;
103}
104
105bool RgbdSensor_nws_ros::openDeferredAttach(Searchable& prop)
106{
107 // I dunno what to do here now...
108 isSubdeviceOwned = false;
109 return true;
110}
111
112bool RgbdSensor_nws_ros::openAndAttachSubDevice(Searchable& prop)
113{
114 Property p;
115 subDeviceOwned = new PolyDriver;
116 p.fromString(prop.toString());
117
118 p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
119 p.unput("device");
120 p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before
121
122 // if errors occurred during open, quit here.
123 yCDebug(RGBDSENSORNWSROS, "Opening IRGBDSensor subdevice");
124 subDeviceOwned->open(p);
125
126 if (!subDeviceOwned->isValid())
127 {
128 yCError(RGBDSENSORNWSROS, "Opening IRGBDSensor subdevice... FAILED");
129 return false;
130 }
131 isSubdeviceOwned = true;
132 if(!attach(subDeviceOwned)) {
133 return false;
134 }
135
136 return true;
137}
138
140{
141 yCTrace(RGBDSENSORNWSROS, "Close");
142 detach();
143
144 // close subdevice if it was created inside the open (--subdevice option)
145 if(isSubdeviceOwned)
146 {
147 if(subDeviceOwned)
148 {
149 delete subDeviceOwned;
150 subDeviceOwned=nullptr;
151 }
152 sensor_p = nullptr;
153 fgCtrl = nullptr;
154 isSubdeviceOwned = false;
155 }
156
157 if(m_node !=nullptr)
158 {
159 m_node->interrupt();
160 delete m_node;
161 m_node = nullptr;
162 }
163
164 return true;
165}
166
167/* Helper functions */
168
169bool RgbdSensor_nws_ros::initialize_ROS(yarp::os::Searchable &params)
170{
171 // depth topic base name check
172 if (!params.check("depth_topic_name")) {
173 yCError(RGBDSENSORNWSROS) << "missing depth_topic_name parameter";
174 return false;
175 }
176 std::string depth_topic_name = params.find("depth_topic_name").asString();
177 if(depth_topic_name[0] != '/'){
178 yCError(RGBDSENSORNWSROS) << "depth_topic_name must begin with an initial /";
179 return false;
180 }
181
182 // color topic base name check
183 if (!params.check("color_topic_name")) {
184 yCError(RGBDSENSORNWSROS) << "missing color_topic_name parameter";
185 return false;
186 }
187 std::string color_topic_name = params.find("color_topic_name").asString();
188 if(color_topic_name[0] != '/'){
189 yCError(RGBDSENSORNWSROS) << "color_topic_name must begin with an initial /";
190 return false;
191 }
192
193 // node_name check
194 if (!params.check("node_name")) {
195 yCError(RGBDSENSORNWSROS) << "missing node_name parameter";
196 return false;
197 }
198 std::string node_name = params.find("node_name").asString();
199 if(node_name[0] != '/'){
200 yCError(RGBDSENSORNWSROS) << "node_name must begin with an initial /";
201 return false;
202 }
203
204 // depth_frame_id check
205 if (!params.check("depth_frame_id")) {
206 yCError(RGBDSENSORNWSROS) << "missing depth_frame_id parameter";
207 return false;
208 }
209 m_depth_frame_id = params.find("depth_frame_id").asString();
210
211 // m_color_frame_id check
212 if (!params.check("color_frame_id")) {
213 yCError(RGBDSENSORNWSROS) << "missing color_frame_id parameter";
214 return false;
215 }
216 m_color_frame_id = params.find("color_frame_id").asString();
217
218 // open topics here if needed
219 m_node = new yarp::os::Node(nodeName);
220 nodeSeq = 0;
221
222 if (!publisherPort_color.topic(color_topic_name))
223 {
224 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << color_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
225 return false;
226 }
227
228 if (!publisherPort_depth.topic(depth_topic_name))
229 {
230 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
231 return false;
232 }
233 std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind('/')) + "/camera_info";
234 if (!publisherPort_colorCaminfo.topic(rgb_info_topic_name))
235 {
236 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << rgb_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
237 return false;
238 }
239
240 std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind('/')) + "/camera_info";
241 if (!publisherPort_depthCaminfo.topic(depth_info_topic_name))
242 {
243 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
244 return false;
245 }
246 return true;
247}
248
254{
257 }
258
259 //check if we already instantiated a subdevice previously
260 if (isSubdeviceOwned) {
261 return false;
262 }
263
264 sensor_p = nullptr;
265 return true;
266}
267
269{
270 if(poly)
271 {
272 poly->view(sensor_p);
273 poly->view(fgCtrl);
274 }
275
276 if(sensor_p == nullptr)
277 {
278 yCError(RGBDSENSORNWSROS) << "Attached device has no valid IRGBDSensor interface.";
279 return false;
280 }
281
282 if(fgCtrl == nullptr)
283 {
284 yCWarning(RGBDSENSORNWSROS) << "Attached device has no valid IFrameGrabberControls interface.";
285 }
286
287 PeriodicThread::setPeriod(period);
288 return PeriodicThread::start();
289}
290
291/* IRateThread interface */
292
294{
295 // Get interface from attached device if any.
296 return true;
297}
298
300{
301 // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
302}
303
304bool RgbdSensor_nws_ros::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
305{
306 double phyF = 0.0;
307 double fx = 0.0;
308 double fy = 0.0;
309 double cx = 0.0;
310 double cy = 0.0;
311 double k1 = 0.0;
312 double k2 = 0.0;
313 double t1 = 0.0;
314 double t2 = 0.0;
315 double k3 = 0.0;
316 double stamp = 0.0;
317
318 std::string distModel;
319 std::string currentSensor;
320 UInt i;
321 Property camData;
322 std::vector<param<double> > parVector;
323 param<double>* par;
324 bool ok;
325
326 currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
327 ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
328
329 if (!ok)
330 {
331 yCError(RGBDSENSORNWSROS) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
332 return false;
333 }
334
335 if(!camData.check("distortionModel"))
336 {
337 yCWarning(RGBDSENSORNWSROS) << "Missing distortion model";
338 return false;
339 }
340
341 distModel = camData.find("distortionModel").asString();
342 if (distModel != "plumb_bob")
343 {
344 yCError(RGBDSENSORNWSROS) << "Distortion model not supported";
345 return false;
346 }
347
348 //std::vector<param<std::string> > rosStringParam;
349 //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
350
351 parVector.emplace_back(phyF,"physFocalLength");
352 parVector.emplace_back(fx,"focalLengthX");
353 parVector.emplace_back(fy,"focalLengthY");
354 parVector.emplace_back(cx,"principalPointX");
355 parVector.emplace_back(cy,"principalPointY");
356 parVector.emplace_back(k1,"k1");
357 parVector.emplace_back(k2,"k2");
358 parVector.emplace_back(t1,"t1");
359 parVector.emplace_back(t2,"t2");
360 parVector.emplace_back(k3,"k3");
361 parVector.emplace_back(stamp,"stamp");
362 for(i = 0; i < parVector.size(); i++)
363 {
364 par = &parVector[i];
365
366 if(!camData.check(par->parname))
367 {
368 yCWarning(RGBDSENSORNWSROS) << "Driver has not the param:" << par->parname;
369 return false;
370 }
371 *par->var = camData.find(par->parname).asFloat64();
372 }
373
374 cameraInfo.header.frame_id = frame_id;
375 cameraInfo.header.seq = seq;
376 cameraInfo.header.stamp = stamp;
377 cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth();
378 cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight();
379 cameraInfo.distortion_model = distModel;
380
381 cameraInfo.D.resize(5);
382 cameraInfo.D[0] = k1;
383 cameraInfo.D[1] = k2;
384 cameraInfo.D[2] = t1;
385 cameraInfo.D[3] = t2;
386 cameraInfo.D[4] = k3;
387
388 cameraInfo.K.resize(9);
389 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
390 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
391 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
392
393 /*
394 * ROS documentation on cameraInfo message:
395 * "Rectification matrix (stereo cameras only)
396 * A rotation matrix aligning the camera coordinate system to the ideal
397 * stereo image plane so that epipolar lines in both stereo images are
398 * parallel."
399 * useless in our case, it will be an identity matrix
400 */
401
402 cameraInfo.R.assign(9, 0);
403 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
404
405 cameraInfo.P.resize(12);
406 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
407 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
408 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
409
410 cameraInfo.binning_x = cameraInfo.binning_y = 0;
411 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
412 cameraInfo.roi.do_rectify = false;
413 return true;
414}
415
416bool RgbdSensor_nws_ros::writeData()
417{
418 //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
419 // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
420
421 // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
422 // depthImage.resize(hDim, vDim);
423 if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
424 {
425 return false;
426 }
427
428 static Stamp oldColorStamp = Stamp(0, 0);
429 static Stamp oldDepthStamp = Stamp(0, 0);
430 bool rgb_data_ok = true;
431 bool depth_data_ok = true;
432
433 if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
434 {
435 rgb_data_ok=false;
436 //return true;
437 }
438 else { oldColorStamp = colorStamp; }
439
440 if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
441 {
442 depth_data_ok=false;
443 //return true;
444 }
445 else { oldDepthStamp = depthStamp; }
446
447 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
448 if (rgb_data_ok)
449 {
450 yarp::rosmsg::sensor_msgs::Image& rColorImage = publisherPort_color.prepare();
451 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = publisherPort_colorCaminfo.prepare();
452 yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime();
453 yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, m_color_frame_id, cRosStamp, nodeSeq);
454 publisherPort_color.setEnvelope(colorStamp);
455 publisherPort_color.write();
456 if (setCamInfo(camInfoC, m_color_frame_id, nodeSeq, COLOR_SENSOR))
457 {
458 if(forceInfoSync)
459 {camInfoC.header.stamp = rColorImage.header.stamp;}
460 publisherPort_colorCaminfo.setEnvelope(colorStamp);
461 publisherPort_colorCaminfo.write();
462 }
463 else
464 {
465 yCWarning(RGBDSENSORNWSROS, "Missing color camera parameters... camera info messages will be not sent");
466 }
467 }
468 if (depth_data_ok)
469 {
470 yarp::rosmsg::sensor_msgs::Image& rDepthImage = publisherPort_depth.prepare();
471 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = publisherPort_depthCaminfo.prepare();
472 yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime();
473 yarp::dev::RGBDRosConversionUtils::deepCopyImages(depthImage, rDepthImage, m_depth_frame_id, dRosStamp, nodeSeq);
474 publisherPort_depth.setEnvelope(depthStamp);
475 publisherPort_depth.write();
476 if (setCamInfo(camInfoD, m_depth_frame_id, nodeSeq, DEPTH_SENSOR))
477 {
478 if(forceInfoSync)
479 {camInfoD.header.stamp = rDepthImage.header.stamp;}
480 publisherPort_depthCaminfo.setEnvelope(depthStamp);
481 publisherPort_depthCaminfo.write();
482 }
483 else
484 {
485 yCWarning(RGBDSENSORNWSROS, "Missing depth camera parameters... camera info messages will be not sent");
486 }
487 }
488
489 nodeSeq++;
490
491 return true;
492}
493
495{
496 if (sensor_p!=nullptr)
497 {
498 static int i = 0;
499 sensorStatus = sensor_p->getSensorStatus();
500 switch (sensorStatus)
501 {
502 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
503 {
504 if (!writeData()) {
505 yCError(RGBDSENSORNWSROS, "Image not captured.. check hardware configuration");
506 }
507 i = 0;
508 }
509 break;
510 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
511 {
512 if(i < 1000) {
513 if((i % 30) == 0) {
514 yCInfo(RGBDSENSORNWSROS) << "Device not ready, waiting...";
515 }
516 } else {
517 yCWarning(RGBDSENSORNWSROS) << "Device is taking too long to start..";
518 }
519 i++;
520 }
521 break;
522 default:
523 {
524 if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
525 yCError(RGBDSENSORNWSROS, "%s: Sensor returned error", sensorId.c_str());
526 }
527 }
528 }
529 }
530 else
531 {
532 if(verbose >= 6) {
533 yCError(RGBDSENSORNWSROS, "%s: Sensor interface is not valid", sensorId.c_str());
534 }
535 }
536}
constexpr double DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RGBDSENSORNWSROS()
rgbdSensor_nws_ros: A Network grabber for kinect-like devices. This device will produce two streams o...
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
bool open(yarp::os::Searchable &params) override
Device driver interface.
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool detach() override
WrapperSingle interface.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:88
A generic interface for cameras that have both color camera as well as depth camera sensor,...
Definition: IRGBDSensor.h:39
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.
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.
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...
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.
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
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool asBool() const
Get boolean value.
Definition: Value.cpp:186
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
#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
yarp::rosmsg::sensor_msgs::Image Image
Definition: Image.h:21
yarp::rosmsg::sensor_msgs::CameraInfo CameraInfo
Definition: CameraInfo.h:21
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.
An interface to the operating system, including Port based communication.