YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RgbdSensor_nws_yarp.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
9#include <yarp/os/LogStream.h>
10
12
13#include <cstdio>
14#include <cstring>
15#include <sstream>
16
17using namespace RGBDImpl;
18using namespace yarp::sig;
19using namespace yarp::dev;
20using namespace yarp::os;
21
22YARP_LOG_COMPONENT(RGBDSENSORNWSYARP, "yarp.devices.RgbdSensor_nws_yarp")
23
24#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR 1
25#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR 0
26
27
29 iRGBDSensor(nullptr)
30{
31}
32
34{
35 bool ret;
36 iRGBDSensor = interface;
37 ret = rgbParser.configure(interface);
38 ret &= depthParser.configure(interface);
39 return ret;
40}
41
48
53
54bool RGBDSensorParser::respond(const Bottle& cmd, Bottle& response)
55{
56 bool ret = false;
57 int interfaceType = cmd.get(0).asVocab32();
58
59 response.clear();
60 switch(interfaceType)
61 {
63 {
64 // forwarding to the proper parser.
65 ret = rgbParser.respond(cmd, response);
66 }
67 break;
68
70 {
71 // forwarding to the proper parser.
72 ret = depthParser.respond(cmd, response);
73 }
74 break;
75
77 {
78 // forwarding to the proper parser.
79 ret = fgCtrlParsers.respond(cmd, response);
80 }
81 break;
82
84 {
85 switch (cmd.get(1).asVocab32())
86 {
87 case VOCAB_GET:
88 {
89 switch(cmd.get(2).asVocab32())
90 {
92 {
93 yarp::sig::Matrix params;
94 ret = iRGBDSensor->getExtrinsicParam(params);
95 if(ret)
96 {
100 response.addVocab32(VOCAB_IS);
101 ret &= Property::copyPortable(params, params_b); // will it really work??
102 response.append(params_b);
103 } else {
104 response.addVocab32(VOCAB_FAILED);
105 }
106 }
107 break;
108
109 case VOCAB_ERROR_MSG:
110 {
112 response.addVocab32(VOCAB_ERROR_MSG);
113 response.addVocab32(VOCAB_IS);
114 response.addString(iRGBDSensor->getLastErrorMsg());
115 ret = true;
116 }
117 break;
118
120 {
123 response.addVocab32(VOCAB_IS);
126 }
127 break;
128
129 case VOCAB_STATUS:
130 {
132 response.addVocab32(VOCAB_STATUS);
133 response.addVocab32(VOCAB_IS);
134 response.addInt32(iRGBDSensor->getSensorStatus());
135 }
136 break;
137
138 default:
139 {
140 yCError(RGBDSENSORNWSYARP) << "Interface parser received an unknown GET command. Command is " << cmd.toString();
141 response.addVocab32(VOCAB_FAILED);
142 }
143 break;
144 }
145 }
146 break;
147
148 case VOCAB_SET:
149 {
150 yCError(RGBDSENSORNWSYARP) << "Interface parser received an unknown SET command. Command is " << cmd.toString();
151 response.addVocab32(VOCAB_FAILED);
152 }
153 break;
154 }
155 }
156 break;
157
158 default:
159 {
160 yCError(RGBDSENSORNWSYARP) << "Received a command for a wrong interface " << yarp::os::Vocab32::decode(interfaceType);
161 return DeviceResponder::respond(cmd,response);
162 }
163 break;
164 }
165 return ret;
166}
167
168
171 sensor_p(nullptr),
172 fgCtrl(nullptr),
173 sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY),
174 verbose(4)
175{}
176
178{
179 close();
180 sensor_p = nullptr;
181 fgCtrl = nullptr;
182}
183
187{
188 if (!parseParams(config)) { return false; }
189
190 //port names
191 std::string rootName = m_name;
192 std::string rpcPort_Name = rootName + "/rpc:i";
193 colorFrame_StreamingPort_Name = rootName + "/rgbImage:o";
194 depthFrame_StreamingPort_Name = rootName + "/depthImage:o";
195
196 // Open ports
197 bool bRet;
198 bRet = true;
199 if (!rpcPort.open(rpcPort_Name))
200 {
201 yCError(RGBDSENSORNWSYARP) << "Unable to open rpc Port" << rpcPort_Name.c_str();
202 bRet = false;
203 }
204 rpcPort.setReader(rgbdParser);
205
206 if (!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name))
207 {
208 yCError(RGBDSENSORNWSYARP) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str();
209 bRet = false;
210 }
211 if (!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name))
212 {
213 yCError(RGBDSENSORNWSYARP) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str();
214 bRet = false;
215 }
216
217 return true;
218}
219
221{
222 yCTrace(RGBDSENSORNWSYARP, "Close");
223 detach();
224
225 // Closing port
226 rpcPort.interrupt();
227 colorFrame_StreamingPort.interrupt();
228 depthFrame_StreamingPort.interrupt();
229
230 rpcPort.close();
231 colorFrame_StreamingPort.close();
232 depthFrame_StreamingPort.close();
233
234 return true;
235}
236
242{
245 }
246
247 sensor_p = nullptr;
248 fgCtrl = nullptr;
249 return true;
250}
251
253{
254 if(poly)
255 {
256 poly->view(sensor_p);
257 poly->view(fgCtrl);
258 }
259
260 if(sensor_p == nullptr)
261 {
262 yCError(RGBDSENSORNWSYARP) << "Attached device has no valid IRGBDSensor interface.";
263 return false;
264 }
265
266 if(!rgbdParser.configure(sensor_p))
267 {
268 yCError(RGBDSENSORNWSYARP) << "Error configuring IRGBD interface";
269 return false;
270 }
271
272 if(fgCtrl != nullptr)
273 {
274 if (!rgbdParser.configure(fgCtrl)) {
275 yCError(RGBDSENSORNWSYARP) << "Error configuring interfaces for parsers";
276 return false;
277 }
278 }
279 else
280 {
281 yCWarning(RGBDSENSORNWSYARP) << "Attached device has no valid IFrameGrabberControls interface.";
282 }
283
285 return PeriodicThread::start();
286}
287
288/* IRateThread interface */
289
291{
292 // Get interface from attached device if any.
293 return true;
294}
295
297{
298 // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
299}
300
301bool RgbdSensor_nws_yarp::setCamInfo(const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
302{
303 double phyF = 0.0;
304 double fx = 0.0;
305 double fy = 0.0;
306 double cx = 0.0;
307 double cy = 0.0;
308 double k1 = 0.0;
309 double k2 = 0.0;
310 double t1 = 0.0;
311 double t2 = 0.0;
312 double k3 = 0.0;
313 double stamp = 0.0;
314
315 std::string distModel, currentSensor;
316 UInt i;
318 std::vector<param<double> > parVector;
320 bool ok;
321
322 currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
323 ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
324
325 if (!ok)
326 {
327 yCError(RGBDSENSORNWSYARP) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
328 return false;
329 }
330
331 if(!camData.check("distortionModel"))
332 {
333 yCWarning(RGBDSENSORNWSYARP) << "Missing distortion model";
334 return false;
335 }
336
337 distModel = camData.find("distortionModel").asString();
338 if (distModel != "plumb_bob")
339 {
340 yCError(RGBDSENSORNWSYARP) << "Distortion model not supported";
341 return false;
342 }
343
344 //std::vector<param<std::string> > rosStringParam;
345 //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
346
347 parVector.emplace_back(phyF,"physFocalLength");
348 parVector.emplace_back(fx,"focalLengthX");
349 parVector.emplace_back(fy,"focalLengthY");
350 parVector.emplace_back(cx,"principalPointX");
351 parVector.emplace_back(cy,"principalPointY");
352 parVector.emplace_back(k1,"k1");
353 parVector.emplace_back(k2,"k2");
354 parVector.emplace_back(t1,"t1");
355 parVector.emplace_back(t2,"t2");
356 parVector.emplace_back(k3,"k3");
357 parVector.emplace_back(stamp,"stamp");
358 for(i = 0; i < parVector.size(); i++)
359 {
360 par = &parVector[i];
361
362 if(!camData.check(par->parname))
363 {
364 yCWarning(RGBDSENSORNWSYARP) << "Driver has not the param:" << par->parname;
365 return false;
366 }
367 *par->var = camData.find(par->parname).asFloat64();
368 }
369
370 return true;
371}
372
373bool RgbdSensor_nws_yarp::writeData()
374{
375 //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
376 // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
377
378 // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
379 // depthImage.resize(hDim, vDim);
380 if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
381 {
382 return false;
383 }
384
385 static Stamp oldColorStamp = Stamp(0, 0);
386 static Stamp oldDepthStamp = Stamp(0, 0);
387 bool rgb_data_ok = true;
388 bool depth_data_ok = true;
389
390 if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
391 {
392 rgb_data_ok=false;
393 //return true;
394 }
395 else { oldColorStamp = colorStamp; }
396
397 if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
398 {
399 depth_data_ok=false;
400 //return true;
401 }
402 else { oldDepthStamp = depthStamp; }
403
404 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
405 if (rgb_data_ok && colorFrame_StreamingPort.getOutputCount() > 0)
406 {
407 FlexImage& yColorImage = colorFrame_StreamingPort.prepare();
408 yColorImage.setPixelCode(colorImage.getPixelCode());
409 yColorImage.setQuantum(colorImage.getQuantum());
410 yColorImage.setExternal(colorImage.getRawImage(), colorImage.width(), colorImage.height());
411 colorFrame_StreamingPort.setEnvelope(colorStamp);
412 colorFrame_StreamingPort.write();
413 }
414 if (depth_data_ok && depthFrame_StreamingPort.getOutputCount() > 0)
415 {
416 ImageOf<PixelFloat>& yDepthImage = depthFrame_StreamingPort.prepare();
417 yDepthImage.setQuantum(depthImage.getQuantum());
419 depthFrame_StreamingPort.setEnvelope(depthStamp);
420 depthFrame_StreamingPort.write();
421 }
422
423 return true;
424}
425
427{
428 if (sensor_p!=nullptr)
429 {
430 static int i = 0;
431 sensorStatus = sensor_p->getSensorStatus();
432 switch (sensorStatus)
433 {
435 {
436 if (!writeData()) {
437 yCError(RGBDSENSORNWSYARP, "Image not captured.. check hardware configuration");
438 }
439 i = 0;
440 }
441 break;
443 {
444 if(i < 1000) {
445 if((i % 30) == 0) {
446 yCInfo(RGBDSENSORNWSYARP) << "Device not ready, waiting...";
447 }
448 } else {
449 yCWarning(RGBDSENSORNWSYARP) << "Device is taking too long to start..";
450 }
451 i++;
452 }
453 break;
454 default:
455 {
456 if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
457 yCError(RGBDSENSORNWSYARP, "%s: Sensor returned error", m_name.c_str());
458 }
459 }
460 }
461 }
462 else
463 {
464 if(verbose >= 6) {
465 yCError(RGBDSENSORNWSYARP, "%s: Sensor interface is not valid", m_name.c_str());
466 }
467 }
468}
constexpr yarp::conf::vocab32_t VOCAB_DEPTH_VISUAL_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_RGBD_SENSOR
constexpr yarp::conf::vocab32_t VOCAB_RGB_VISUAL_PARAMS
constexpr yarp::conf::vocab32_t VOCAB_EXTRINSIC_PARAM
constexpr yarp::conf::vocab32_t VOCAB_RGBD_PROTOCOL_VERSION
constexpr yarp::conf::vocab32_t VOCAB_STATUS
constexpr yarp::conf::vocab32_t VOCAB_FRAMEGRABBER_CONTROL
constexpr yarp::conf::vocab32_t VOCAB_ERROR_MSG
#define DEFAULT_THREAD_PERIOD
constexpr yarp::conf::vocab32_t VOCAB_IS
constexpr yarp::conf::vocab32_t VOCAB_GET
constexpr yarp::conf::vocab32_t VOCAB_FAILED
constexpr yarp::conf::vocab32_t VOCAB_SET
bool ret
#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR
const yarp::os::LogComponent & RGBDSENSORNWSYARP()
#define RGBD_INTERFACE_PROTOCOL_VERSION_MAJOR
bool configure(yarp::dev::IRGBDSensor *interface)
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool detach() override
WrapperSingle interface.
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &params) override
Device driver interface.
void threadRelease() override
Release method.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
bool view(T *&x)
Get an interface to the device driver.
virtual bool respond(const yarp::os::Bottle &command, yarp::os::Bottle &reply)
Respond to a message.
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.
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
virtual bool getExtrinsicParam(yarp::sig::Matrix &extrinsic)=0
Get the extrinsic parameters from the device.
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.
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
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:353
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition Bottle.cpp:246
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
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
A mini-server for performing network communication in the background.
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.
int getOutputCount() override
Determine how many output connections this port has.
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.
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...
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
A base class for nested structures that can be searched.
Definition Searchable.h:31
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::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
Definition Value.cpp:228
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:363
size_t width() const
Gets width of image in pixels.
Definition Image.h:171
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition Image.cpp:479
size_t getQuantum() const
The size of a row is constrained to be a multiple of the "quantum".
Definition Image.h:204
size_t height() const
Gets height of image in pixels.
Definition Image.h:177
virtual int getPixelCode() const
Gets pixel type identifier.
Definition Image.cpp:390
A class for a Matrix.
Definition Matrix.h:39
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
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.