YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RgbdSensor_nws_ros.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 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>
12#include <yarp/rosmsg/impl/yarpRosHelper.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{}
38
40{
41 close();
42 sensor_p = nullptr;
43 fgCtrl = nullptr;
44}
45
49{
50 if(verbose >= 5)
51 {
52 yCTrace(RGBDSENSORNWSROS) << "\nParameters are: \n" << config.toString();
53 }
54 if (!config.check("period", "refresh period of the broadcasted values in s"))
55 {
56 if (verbose >= 3) {
57 yCInfo(RGBDSENSORNWSROS) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
58 }
59 }
60 else
61 {
62 period = config.find("period").asFloat64();
63 }
64
65 //check if param exist and assign it to corresponding variable.. if it doesn't, initialize the variable with default value.
66
67 if (config.check("forceInfoSync"))
68 {
69 forceInfoSync = config.find("forceInfoSync").asBool();
70 }
71
72 if(!initialize_ROS(config))
73 {
74 return false;
75 }
76
77 return true;
78}
79
81{
82 yCTrace(RGBDSENSORNWSROS, "Close");
83 detach();
84
85 if(m_node !=nullptr)
86 {
87 m_node->interrupt();
88 delete m_node;
89 m_node = nullptr;
90 }
91
92 return true;
93}
94
95/* Helper functions */
96
97bool RgbdSensor_nws_ros::initialize_ROS(yarp::os::Searchable &params)
98{
99 // depth topic base name check
100 if (!params.check("depth_topic_name")) {
101 yCError(RGBDSENSORNWSROS) << "missing depth_topic_name parameter";
102 return false;
103 }
104 std::string depth_topic_name = params.find("depth_topic_name").asString();
105 if(depth_topic_name[0] != '/'){
106 yCError(RGBDSENSORNWSROS) << "depth_topic_name must begin with an initial /";
107 return false;
108 }
109
110 // color topic base name check
111 if (!params.check("color_topic_name")) {
112 yCError(RGBDSENSORNWSROS) << "missing color_topic_name parameter";
113 return false;
114 }
115 std::string color_topic_name = params.find("color_topic_name").asString();
116 if(color_topic_name[0] != '/'){
117 yCError(RGBDSENSORNWSROS) << "color_topic_name must begin with an initial /";
118 return false;
119 }
120
121 // node_name check
122 if (!params.check("node_name")) {
123 yCError(RGBDSENSORNWSROS) << "missing node_name parameter";
124 return false;
125 }
126 std::string node_name = params.find("node_name").asString();
127 if(node_name[0] != '/'){
128 yCError(RGBDSENSORNWSROS) << "node_name must begin with an initial /";
129 return false;
130 }
131
132 // depth_frame_id check
133 if (!params.check("depth_frame_id")) {
134 yCError(RGBDSENSORNWSROS) << "missing depth_frame_id parameter";
135 return false;
136 }
137 m_depth_frame_id = params.find("depth_frame_id").asString();
138
139 // m_color_frame_id check
140 if (!params.check("color_frame_id")) {
141 yCError(RGBDSENSORNWSROS) << "missing color_frame_id parameter";
142 return false;
143 }
144 m_color_frame_id = params.find("color_frame_id").asString();
145
146 // open topics here if needed
147 m_node = new yarp::os::Node(nodeName);
148 nodeSeq = 0;
149
150 if (!publisherPort_color.topic(color_topic_name))
151 {
152 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << color_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
153 return false;
154 }
155
156 if (!publisherPort_depth.topic(depth_topic_name))
157 {
158 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
159 return false;
160 }
161 std::string rgb_info_topic_name = color_topic_name.substr(0,color_topic_name.rfind('/')) + "/camera_info";
162 if (!publisherPort_colorCaminfo.topic(rgb_info_topic_name))
163 {
164 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << rgb_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
165 return false;
166 }
167
168 std::string depth_info_topic_name = depth_topic_name.substr(0,depth_topic_name.rfind('/')) + "/camera_info";
169 if (!publisherPort_depthCaminfo.topic(depth_info_topic_name))
170 {
171 yCError(RGBDSENSORNWSROS) << "Unable to publish data on " << depth_info_topic_name.c_str() << " topic, check your yarp-ROS network configuration";
172 return false;
173 }
174 return true;
175}
176
182{
185 }
186
187 sensor_p = nullptr;
188 return true;
189}
190
192{
193 if(poly)
194 {
195 poly->view(sensor_p);
196 poly->view(fgCtrl);
197 }
198
199 if(sensor_p == nullptr)
200 {
201 yCError(RGBDSENSORNWSROS) << "Attached device has no valid IRGBDSensor interface.";
202 return false;
203 }
204
205 if(fgCtrl == nullptr)
206 {
207 yCWarning(RGBDSENSORNWSROS) << "Attached device has no valid IFrameGrabberControls interface.";
208 }
209
211 return PeriodicThread::start();
212}
213
214/* IRateThread interface */
215
217{
218 // Get interface from attached device if any.
219 return true;
220}
221
223{
224 // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
225}
226
227bool RgbdSensor_nws_ros::setCamInfo(yarp::rosmsg::sensor_msgs::CameraInfo& cameraInfo, const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
228{
229 double phyF = 0.0;
230 double fx = 0.0;
231 double fy = 0.0;
232 double cx = 0.0;
233 double cy = 0.0;
234 double k1 = 0.0;
235 double k2 = 0.0;
236 double t1 = 0.0;
237 double t2 = 0.0;
238 double k3 = 0.0;
239 double stamp = 0.0;
240
241 std::string distModel;
242 std::string currentSensor;
243 UInt i;
245 std::vector<param<double> > parVector;
247 bool ok;
248
249 currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
250 ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
251
252 if (!ok)
253 {
254 yCError(RGBDSENSORNWSROS) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
255 return false;
256 }
257
258 if(!camData.check("distortionModel"))
259 {
260 yCWarning(RGBDSENSORNWSROS) << "Missing distortion model";
261 return false;
262 }
263
264 distModel = camData.find("distortionModel").asString();
265 if (distModel != "plumb_bob")
266 {
267 yCError(RGBDSENSORNWSROS) << "Distortion model not supported";
268 return false;
269 }
270
271 //std::vector<param<std::string> > rosStringParam;
272 //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
273
274 parVector.emplace_back(phyF,"physFocalLength");
275 parVector.emplace_back(fx,"focalLengthX");
276 parVector.emplace_back(fy,"focalLengthY");
277 parVector.emplace_back(cx,"principalPointX");
278 parVector.emplace_back(cy,"principalPointY");
279 parVector.emplace_back(k1,"k1");
280 parVector.emplace_back(k2,"k2");
281 parVector.emplace_back(t1,"t1");
282 parVector.emplace_back(t2,"t2");
283 parVector.emplace_back(k3,"k3");
284 parVector.emplace_back(stamp,"stamp");
285 for(i = 0; i < parVector.size(); i++)
286 {
287 par = &parVector[i];
288
289 if(!camData.check(par->parname))
290 {
291 yCWarning(RGBDSENSORNWSROS) << "Driver has not the param:" << par->parname;
292 return false;
293 }
294 *par->var = camData.find(par->parname).asFloat64();
295 }
296
297 cameraInfo.header.frame_id = frame_id;
298 cameraInfo.header.seq = seq;
299 cameraInfo.header.stamp = stamp;
300 cameraInfo.width = sensorType == COLOR_SENSOR ? sensor_p->getRgbWidth() : sensor_p->getDepthWidth();
301 cameraInfo.height = sensorType == COLOR_SENSOR ? sensor_p->getRgbHeight() : sensor_p->getDepthHeight();
302 cameraInfo.distortion_model = distModel;
303
304 cameraInfo.D.resize(5);
305 cameraInfo.D[0] = k1;
306 cameraInfo.D[1] = k2;
307 cameraInfo.D[2] = t1;
308 cameraInfo.D[3] = t2;
309 cameraInfo.D[4] = k3;
310
311 cameraInfo.K.resize(9);
312 cameraInfo.K[0] = fx; cameraInfo.K[1] = 0; cameraInfo.K[2] = cx;
313 cameraInfo.K[3] = 0; cameraInfo.K[4] = fy; cameraInfo.K[5] = cy;
314 cameraInfo.K[6] = 0; cameraInfo.K[7] = 0; cameraInfo.K[8] = 1;
315
316 /*
317 * ROS documentation on cameraInfo message:
318 * "Rectification matrix (stereo cameras only)
319 * A rotation matrix aligning the camera coordinate system to the ideal
320 * stereo image plane so that epipolar lines in both stereo images are
321 * parallel."
322 * useless in our case, it will be an identity matrix
323 */
324
325 cameraInfo.R.assign(9, 0);
326 cameraInfo.R.at(0) = cameraInfo.R.at(4) = cameraInfo.R.at(8) = 1;
327
328 cameraInfo.P.resize(12);
329 cameraInfo.P[0] = fx; cameraInfo.P[1] = 0; cameraInfo.P[2] = cx; cameraInfo.P[3] = 0;
330 cameraInfo.P[4] = 0; cameraInfo.P[5] = fy; cameraInfo.P[6] = cy; cameraInfo.P[7] = 0;
331 cameraInfo.P[8] = 0; cameraInfo.P[9] = 0; cameraInfo.P[10] = 1; cameraInfo.P[11] = 0;
332
333 cameraInfo.binning_x = cameraInfo.binning_y = 0;
334 cameraInfo.roi.height = cameraInfo.roi.width = cameraInfo.roi.x_offset = cameraInfo.roi.y_offset = 0;
335 cameraInfo.roi.do_rectify = false;
336 return true;
337}
338
339bool RgbdSensor_nws_ros::writeData()
340{
341 //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
342 // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
343
344 // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
345 // depthImage.resize(hDim, vDim);
346 if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
347 {
348 return false;
349 }
350
351 static Stamp oldColorStamp = Stamp(0, 0);
352 static Stamp oldDepthStamp = Stamp(0, 0);
353 bool rgb_data_ok = true;
354 bool depth_data_ok = true;
355
356 if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
357 {
358 rgb_data_ok=false;
359 //return true;
360 }
361 else { oldColorStamp = colorStamp; }
362
363 if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
364 {
365 depth_data_ok=false;
366 //return true;
367 }
368 else { oldDepthStamp = depthStamp; }
369
370 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
371 if (rgb_data_ok)
372 {
373 yarp::rosmsg::sensor_msgs::Image& rColorImage = publisherPort_color.prepare();
374 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoC = publisherPort_colorCaminfo.prepare();
375 yarp::rosmsg::TickTime cRosStamp = colorStamp.getTime();
376 yarp::dev::RGBDRosConversionUtils::deepCopyImages(colorImage, rColorImage, m_color_frame_id, cRosStamp, nodeSeq);
377 publisherPort_color.setEnvelope(colorStamp);
378 publisherPort_color.write();
379 if (setCamInfo(camInfoC, m_color_frame_id, nodeSeq, COLOR_SENSOR))
380 {
381 if(forceInfoSync)
382 {camInfoC.header.stamp = rColorImage.header.stamp;}
383 publisherPort_colorCaminfo.setEnvelope(colorStamp);
384 publisherPort_colorCaminfo.write();
385 }
386 else
387 {
388 yCWarning(RGBDSENSORNWSROS, "Missing color camera parameters... camera info messages will be not sent");
389 }
390 }
391 if (depth_data_ok)
392 {
393 yarp::rosmsg::sensor_msgs::Image& rDepthImage = publisherPort_depth.prepare();
394 yarp::rosmsg::sensor_msgs::CameraInfo& camInfoD = publisherPort_depthCaminfo.prepare();
395 yarp::rosmsg::TickTime dRosStamp = depthStamp.getTime();
397 publisherPort_depth.setEnvelope(depthStamp);
398 publisherPort_depth.write();
399 if (setCamInfo(camInfoD, m_depth_frame_id, nodeSeq, DEPTH_SENSOR))
400 {
401 if(forceInfoSync)
402 {camInfoD.header.stamp = rDepthImage.header.stamp;}
403 publisherPort_depthCaminfo.setEnvelope(depthStamp);
404 publisherPort_depthCaminfo.write();
405 }
406 else
407 {
408 yCWarning(RGBDSENSORNWSROS, "Missing depth camera parameters... camera info messages will be not sent");
409 }
410 }
411
412 nodeSeq++;
413
414 return true;
415}
416
418{
419 if (sensor_p!=nullptr)
420 {
421 static int i = 0;
422 sensorStatus = sensor_p->getSensorStatus();
423 switch (sensorStatus)
424 {
426 {
427 if (!writeData()) {
428 yCError(RGBDSENSORNWSROS, "Image not captured.. check hardware configuration");
429 }
430 i = 0;
431 }
432 break;
434 {
435 if(i < 1000) {
436 if((i % 30) == 0) {
437 yCInfo(RGBDSENSORNWSROS) << "Device not ready, waiting...";
438 }
439 } else {
440 yCWarning(RGBDSENSORNWSROS) << "Device is taking too long to start..";
441 }
442 i++;
443 }
444 break;
445 default:
446 {
447 if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
448 yCError(RGBDSENSORNWSROS, "%s: Sensor returned error", sensorId.c_str());
449 }
450 }
451 }
452 }
453 else
454 {
455 if(verbose >= 6) {
456 yCError(RGBDSENSORNWSROS, "%s: Sensor interface is not valid", sensorId.c_str());
457 }
458 }
459}
#define DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RGBDSENSORNWSROS()
#define DEFAULT_THREAD_PERIOD
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.
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 setEnvelope(PortWriter &envelope) override
Set an envelope (e.g., a timestamp) to the next message which will be sent.
A mini-server for performing network communication in the background.
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 setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
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
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:31
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
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
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.
Definition jointData.cpp:13
An interface to the operating system, including Port based communication.