YARP
Yet Another Robot Platform
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 
6 #include "RgbdSensor_nws_yarp.h"
7 
8 #include <yarp/os/LogComponent.h>
9 #include <yarp/os/LogStream.h>
10 
12 
13 #include <cstdio>
14 #include <cstring>
15 #include <sstream>
16 
17 using namespace RGBDImpl;
18 using namespace yarp::sig;
19 using namespace yarp::dev;
20 using namespace yarp::os;
21 
22 YARP_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 
43 {
44  bool ret = rgbParser.configure(rgbInterface);
45  ret &= depthParser.configure(depthInterface);
46  return ret;
47 }
48 
50 {
51  return fgCtrlParsers.configure(_fgCtrl);
52 }
53 
54 bool 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 
83  case VOCAB_RGBD_SENSOR:
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  {
97  yarp::os::Bottle params_b;
98  response.addVocab32(VOCAB_RGBD_SENSOR);
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  {
111  response.addVocab32(VOCAB_RGBD_SENSOR);
112  response.addVocab32(VOCAB_ERROR_MSG);
113  response.addVocab32(VOCAB_IS);
114  response.addString(iRGBDSensor->getLastErrorMsg());
115  ret = true;
116  }
117  break;
118 
120  {
121  response.addVocab32(VOCAB_RGBD_SENSOR);
123  response.addVocab32(VOCAB_IS);
126  }
127  break;
128 
129  case VOCAB_STATUS:
130  {
131  response.addVocab32(VOCAB_RGBD_SENSOR);
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  period(DEFAULT_THREAD_PERIOD),
172  sensor_p(nullptr),
173  fgCtrl(nullptr),
174  sensorStatus(IRGBDSensor::RGBD_SENSOR_NOT_READY),
175  verbose(4),
176  isSubdeviceOwned(false),
177  subDeviceOwned(nullptr)
178 {}
179 
181 {
182  close();
183  sensor_p = nullptr;
184  fgCtrl = nullptr;
185 }
186 
190 {
191 // DeviceResponder::makeUsage();
192 // addUsage("[set] [bri] $fBrightness", "set brightness");
193 // addUsage("[set] [expo] $fExposure", "set exposure");
194 //
195  m_conf.fromString(config.toString());
196  if (verbose >= 5) {
197  yCTrace(RGBDSENSORNWSYARP) << "\nParameters are: \n"
198  << config.toString();
199  }
200 
201  if(!fromConfig(config))
202  {
203  yCError(RGBDSENSORNWSYARP) << "Failed to open, check previous log for error messages.";
204  return false;
205  }
206 
207  setId("RGBDSensorWrapper for " + depthFrame_StreamingPort_Name);
208 
209  if(!initialize_YARP(config))
210  {
211  yCError(RGBDSENSORNWSYARP) << sensorId << "Error initializing YARP ports";
212  return false;
213  }
214 
215  // check if we need to create subdevice or if they are
216  // passed later on through attachAll()
217  if(isSubdeviceOwned)
218  {
219  if(! openAndAttachSubDevice(config))
220  {
221  yCError(RGBDSENSORNWSYARP, "Error while opening subdevice");
222  return false;
223  }
224  }
225  else
226  {
227  if (!openDeferredAttach(config)) {
228  return false;
229  }
230  }
231 
232  return true;
233 }
234 
236 {
237  if (!config.check("period", "refresh period of the broadcasted values in s"))
238  {
239  if (verbose >= 3) {
240  yCInfo(RGBDSENSORNWSYARP) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
241  }
242  } else {
243  period = config.find("period").asFloat64();
244  }
245 
246  std::string rootName;
247  rootName = config.check("name",Value("/"), "starting '/' if needed.").asString();
248 
249  if (!config.check("name", "Prefix name of the ports opened by the RGBD wrapper.")) {
250  yCError(RGBDSENSORNWSYARP) << "Missing 'name' parameter. Check you configuration file; it must be like:";
251  yCError(RGBDSENSORNWSYARP) << " name: Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD";
252  return false;
253  }
254 
255  rootName = config.find("name").asString();
256  rpcPort_Name = rootName + "/rpc:i";
257  colorFrame_StreamingPort_Name = rootName + "/rgbImage:o";
258  depthFrame_StreamingPort_Name = rootName + "/depthImage:o";
259 
260  if(config.check("subdevice")) {
261  isSubdeviceOwned=true;
262  } else {
263  isSubdeviceOwned=false;
264  }
265 
266  return true;
267 }
268 
269 bool RgbdSensor_nws_yarp::openDeferredAttach(Searchable& prop)
270 {
271  // I dunno what to do here now...
272  isSubdeviceOwned = false;
273  return true;
274 }
275 
276 bool RgbdSensor_nws_yarp::openAndAttachSubDevice(Searchable& prop)
277 {
278  Property p;
279  subDeviceOwned = new PolyDriver;
280  p.fromString(prop.toString());
281 
282  p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
283  p.unput("device");
284  p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before
285 
286  // if errors occurred during open, quit here.
287  yCDebug(RGBDSENSORNWSYARP, "Opening IRGBDSensor subdevice");
288  subDeviceOwned->open(p);
289 
290  if (!subDeviceOwned->isValid())
291  {
292  yCError(RGBDSENSORNWSYARP, "Opening IRGBDSensor subdevice... FAILED");
293  return false;
294  }
295  isSubdeviceOwned = true;
296  if(!attach(subDeviceOwned)) {
297  return false;
298  }
299 
300  return true;
301 }
302 
304 {
305  yCTrace(RGBDSENSORNWSYARP, "Close");
306  detach();
307 
308  // close subdevice if it was created inside the open (--subdevice option)
309  if(isSubdeviceOwned)
310  {
311  if(subDeviceOwned)
312  {
313  delete subDeviceOwned;
314  subDeviceOwned=nullptr;
315  }
316  sensor_p = nullptr;
317  fgCtrl = nullptr;
318  isSubdeviceOwned = false;
319  }
320 
321  // Closing port
322 
323  rpcPort.interrupt();
324  colorFrame_StreamingPort.interrupt();
325  depthFrame_StreamingPort.interrupt();
326 
327  rpcPort.close();
328  colorFrame_StreamingPort.close();
329  depthFrame_StreamingPort.close();
330 
331  return true;
332 }
333 
334 /* Helper functions */
335 
336 bool RgbdSensor_nws_yarp::initialize_YARP(yarp::os::Searchable &params)
337 {
338  // Open ports
339  bool bRet;
340  bRet = true;
341  if(!rpcPort.open(rpcPort_Name))
342  {
343  yCError(RGBDSENSORNWSYARP) << "Unable to open rpc Port" << rpcPort_Name.c_str();
344  bRet = false;
345  }
346  rpcPort.setReader(rgbdParser);
347 
348  if(!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name))
349  {
350  yCError(RGBDSENSORNWSYARP) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str();
351  bRet = false;
352  }
353  if(!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name))
354  {
355  yCError(RGBDSENSORNWSYARP) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str();
356  bRet = false;
357  }
358 
359  return bRet;
360 }
361 
362 void RgbdSensor_nws_yarp::setId(const std::string &id)
363 {
364  sensorId=id;
365 }
366 
368 {
369  return sensorId;
370 }
371 
377 {
380  }
381 
382  //check if we already instantiated a subdevice previously
383  if (isSubdeviceOwned) {
384  return false;
385  }
386 
387  sensor_p = nullptr;
388  return true;
389 }
390 
392 {
393  if(poly)
394  {
395  poly->view(sensor_p);
396  poly->view(fgCtrl);
397  }
398 
399  if(sensor_p == nullptr)
400  {
401  yCError(RGBDSENSORNWSYARP) << "Attached device has no valid IRGBDSensor interface.";
402  return false;
403  }
404 
405  if(!rgbdParser.configure(sensor_p))
406  {
407  yCError(RGBDSENSORNWSYARP) << "Error configuring IRGBD interface";
408  return false;
409  }
410 
411  if(fgCtrl != nullptr)
412  {
413  if (!rgbdParser.configure(fgCtrl)) {
414  yCError(RGBDSENSORNWSYARP) << "Error configuring interfaces for parsers";
415  return false;
416  }
417  }
418  else
419  {
420  yCWarning(RGBDSENSORNWSYARP) << "Attached device has no valid IFrameGrabberControls interface.";
421  }
422 
423  PeriodicThread::setPeriod(period);
424  return PeriodicThread::start();
425 }
426 
427 /* IRateThread interface */
428 
430 {
431  // Get interface from attached device if any.
432  return true;
433 }
434 
436 {
437  // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
438 }
439 
440 bool RgbdSensor_nws_yarp::setCamInfo(const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
441 {
442  double phyF = 0.0;
443  double fx = 0.0;
444  double fy = 0.0;
445  double cx = 0.0;
446  double cy = 0.0;
447  double k1 = 0.0;
448  double k2 = 0.0;
449  double t1 = 0.0;
450  double t2 = 0.0;
451  double k3 = 0.0;
452  double stamp = 0.0;
453 
454  std::string distModel, currentSensor;
455  UInt i;
456  Property camData;
457  std::vector<param<double> > parVector;
458  param<double>* par;
459  bool ok;
460 
461  currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
462  ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
463 
464  if (!ok)
465  {
466  yCError(RGBDSENSORNWSYARP) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
467  return false;
468  }
469 
470  if(!camData.check("distortionModel"))
471  {
472  yCWarning(RGBDSENSORNWSYARP) << "Missing distortion model";
473  return false;
474  }
475 
476  distModel = camData.find("distortionModel").asString();
477  if (distModel != "plumb_bob")
478  {
479  yCError(RGBDSENSORNWSYARP) << "Distortion model not supported";
480  return false;
481  }
482 
483  //std::vector<param<std::string> > rosStringParam;
484  //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
485 
486  parVector.emplace_back(phyF,"physFocalLength");
487  parVector.emplace_back(fx,"focalLengthX");
488  parVector.emplace_back(fy,"focalLengthY");
489  parVector.emplace_back(cx,"principalPointX");
490  parVector.emplace_back(cy,"principalPointY");
491  parVector.emplace_back(k1,"k1");
492  parVector.emplace_back(k2,"k2");
493  parVector.emplace_back(t1,"t1");
494  parVector.emplace_back(t2,"t2");
495  parVector.emplace_back(k3,"k3");
496  parVector.emplace_back(stamp,"stamp");
497  for(i = 0; i < parVector.size(); i++)
498  {
499  par = &parVector[i];
500 
501  if(!camData.check(par->parname))
502  {
503  yCWarning(RGBDSENSORNWSYARP) << "Driver has not the param:" << par->parname;
504  return false;
505  }
506  *par->var = camData.find(par->parname).asFloat64();
507  }
508 
509  return true;
510 }
511 
512 bool RgbdSensor_nws_yarp::writeData()
513 {
514  //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
515  // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
516 
517  // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
518  // depthImage.resize(hDim, vDim);
519  if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
520  {
521  return false;
522  }
523 
524  static Stamp oldColorStamp = Stamp(0, 0);
525  static Stamp oldDepthStamp = Stamp(0, 0);
526  bool rgb_data_ok = true;
527  bool depth_data_ok = true;
528 
529  if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
530  {
531  rgb_data_ok=false;
532  //return true;
533  }
534  else { oldColorStamp = colorStamp; }
535 
536  if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
537  {
538  depth_data_ok=false;
539  //return true;
540  }
541  else { oldDepthStamp = depthStamp; }
542 
543  // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
544  if (rgb_data_ok)
545  {
546  FlexImage& yColorImage = colorFrame_StreamingPort.prepare();
547  yColorImage.setPixelCode(colorImage.getPixelCode());
548  yColorImage.setQuantum(colorImage.getQuantum());
549  yColorImage.setExternal(colorImage.getRawImage(), colorImage.width(), colorImage.height());
550  colorFrame_StreamingPort.setEnvelope(colorStamp);
551  colorFrame_StreamingPort.write();
552  }
553  if (depth_data_ok)
554  {
555  ImageOf<PixelFloat>& yDepthImage = depthFrame_StreamingPort.prepare();
556  yDepthImage.setQuantum(depthImage.getQuantum());
558  depthFrame_StreamingPort.setEnvelope(depthStamp);
559  depthFrame_StreamingPort.write();
560  }
561 
562  return true;
563 }
564 
566 {
567  if (sensor_p!=nullptr)
568  {
569  static int i = 0;
570  sensorStatus = sensor_p->getSensorStatus();
571  switch (sensorStatus)
572  {
573  case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
574  {
575  if (!writeData()) {
576  yCError(RGBDSENSORNWSYARP, "Image not captured.. check hardware configuration");
577  }
578  i = 0;
579  }
580  break;
581  case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
582  {
583  if(i < 1000) {
584  if((i % 30) == 0) {
585  yCInfo(RGBDSENSORNWSYARP) << "Device not ready, waiting...";
586  }
587  } else {
588  yCWarning(RGBDSENSORNWSYARP) << "Device is taking too long to start..";
589  }
590  i++;
591  }
592  break;
593  default:
594  {
595  if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
596  yCError(RGBDSENSORNWSYARP, "%s: Sensor returned error", sensorId.c_str());
597  }
598  }
599  }
600  }
601  else
602  {
603  if(verbose >= 6) {
604  yCError(RGBDSENSORNWSYARP, "%s: Sensor interface is not valid", sensorId.c_str());
605  }
606  }
607 }
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
constexpr double DEFAULT_THREAD_PERIOD
const yarp::os::LogComponent & RGBDSENSORNWSYARP()
#define RGBD_INTERFACE_PROTOCOL_VERSION_MINOR
#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.
void setId(const std::string &id)
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool detach() override
WrapperSingle interface.
bool fromConfig(yarp::os::Searchable &params)
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.
Definition: DeviceDriver.h:74
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:40
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:24
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
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
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
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
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.
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:502
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Port.cpp:374
void close() override
Stop port activity.
Definition: Port.cpp:354
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:34
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
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
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.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
A single value (typically within a Bottle).
Definition: Value.h:45
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 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:414
void setQuantum(size_t imgQuantum)
Definition: Image.h:429
void setPixelCode(int imgPixelCode)
Definition: Image.h:417
void setQuantum(size_t imgQuantum)
Definition: Image.cpp:501
size_t width() const
Gets width of image in pixels.
Definition: Image.h:166
void setExternal(const void *data, size_t imgWidth, size_t imgHeight)
Use this to wrap an external image.
Definition: Image.cpp:903
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition: Image.cpp:541
size_t getQuantum() const
The size of a row is constrained to be a multiple of the "quantum".
Definition: Image.h:199
size_t height() const
Gets height of image in pixels.
Definition: Image.h:172
virtual int getPixelCode() const
Gets pixel type identifier.
Definition: Image.cpp:440
A class for a Matrix.
Definition: Matrix.h:43
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
An interface for the device drivers.
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.
Signal processing.
Definition: Image.h:22