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
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
28RGBDSensorParser::RGBDSensorParser() :
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
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 {
97 yarp::os::Bottle params_b;
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 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 if(!initialize_YARP(config))
208 {
209 yCError(RGBDSENSORNWSYARP) << sensorId << "Error initializing YARP ports";
210 return false;
211 }
212
213 // check if we need to create subdevice or if they are
214 // passed later on through attachAll()
215 if(isSubdeviceOwned)
216 {
217 if(! openAndAttachSubDevice(config))
218 {
219 yCError(RGBDSENSORNWSYARP, "Error while opening subdevice");
220 return false;
221 }
222 }
223 else
224 {
225 if (!openDeferredAttach(config)) {
226 return false;
227 }
228 }
229
230 return true;
231}
232
234{
235 if (!config.check("period", "refresh period of the broadcasted values in s"))
236 {
237 if (verbose >= 3) {
238 yCInfo(RGBDSENSORNWSYARP) << "Using default 'period' parameter of " << DEFAULT_THREAD_PERIOD << "s";
239 }
240 } else {
241 period = config.find("period").asFloat64();
242 }
243
244 std::string rootName;
245 rootName = config.check("name",Value("/"), "starting '/' if needed.").asString();
246
247 if (!config.check("name", "Prefix name of the ports opened by the RGBD wrapper.")) {
248 yCError(RGBDSENSORNWSYARP) << "Missing 'name' parameter. Check you configuration file; it must be like:";
249 yCError(RGBDSENSORNWSYARP) << " name: Prefix name of the ports opened by the RGBD wrapper, e.g. /robotName/RGBD";
250 return false;
251 }
252
253 rootName = config.find("name").asString();
254 rpcPort_Name = rootName + "/rpc:i";
255 colorFrame_StreamingPort_Name = rootName + "/rgbImage:o";
256 depthFrame_StreamingPort_Name = rootName + "/depthImage:o";
257
258 if(config.check("subdevice")) {
259 isSubdeviceOwned=true;
260 } else {
261 isSubdeviceOwned=false;
262 }
263
264 return true;
265}
266
267bool RgbdSensor_nws_yarp::openDeferredAttach(Searchable& prop)
268{
269 // I dunno what to do here now...
270 isSubdeviceOwned = false;
271 return true;
272}
273
274bool RgbdSensor_nws_yarp::openAndAttachSubDevice(Searchable& prop)
275{
276 Property p;
277 subDeviceOwned = new PolyDriver;
278 p.fromString(prop.toString());
279
280 p.setMonitor(prop.getMonitor(), "subdevice"); // pass on any monitoring
281 p.unput("device");
282 p.put("device",prop.find("subdevice").asString()); // subdevice was already checked before
283
284 // if errors occurred during open, quit here.
285 yCDebug(RGBDSENSORNWSYARP, "Opening IRGBDSensor subdevice");
286 subDeviceOwned->open(p);
287
288 if (!subDeviceOwned->isValid())
289 {
290 yCError(RGBDSENSORNWSYARP, "Opening IRGBDSensor subdevice... FAILED");
291 return false;
292 }
293 isSubdeviceOwned = true;
294 if(!attach(subDeviceOwned)) {
295 return false;
296 }
297
298 return true;
299}
300
302{
303 yCTrace(RGBDSENSORNWSYARP, "Close");
304 detach();
305
306 // close subdevice if it was created inside the open (--subdevice option)
307 if(isSubdeviceOwned)
308 {
309 if(subDeviceOwned)
310 {
311 delete subDeviceOwned;
312 subDeviceOwned=nullptr;
313 }
314 sensor_p = nullptr;
315 fgCtrl = nullptr;
316 isSubdeviceOwned = false;
317 }
318
319 // Closing port
320
321 rpcPort.interrupt();
322 colorFrame_StreamingPort.interrupt();
323 depthFrame_StreamingPort.interrupt();
324
325 rpcPort.close();
326 colorFrame_StreamingPort.close();
327 depthFrame_StreamingPort.close();
328
329 return true;
330}
331
332/* Helper functions */
333
334bool RgbdSensor_nws_yarp::initialize_YARP(yarp::os::Searchable &params)
335{
336 // Open ports
337 bool bRet;
338 bRet = true;
339 if(!rpcPort.open(rpcPort_Name))
340 {
341 yCError(RGBDSENSORNWSYARP) << "Unable to open rpc Port" << rpcPort_Name.c_str();
342 bRet = false;
343 }
344 rpcPort.setReader(rgbdParser);
345
346 if(!colorFrame_StreamingPort.open(colorFrame_StreamingPort_Name))
347 {
348 yCError(RGBDSENSORNWSYARP) << "Unable to open color streaming Port" << colorFrame_StreamingPort_Name.c_str();
349 bRet = false;
350 }
351 if(!depthFrame_StreamingPort.open(depthFrame_StreamingPort_Name))
352 {
353 yCError(RGBDSENSORNWSYARP) << "Unable to open depth streaming Port" << depthFrame_StreamingPort_Name.c_str();
354 bRet = false;
355 }
356
357 return bRet;
358}
359
365{
368 }
369
370 //check if we already instantiated a subdevice previously
371 if (isSubdeviceOwned) {
372 return false;
373 }
374
375 sensor_p = nullptr;
376 return true;
377}
378
380{
381 if(poly)
382 {
383 poly->view(sensor_p);
384 poly->view(fgCtrl);
385 }
386
387 if(sensor_p == nullptr)
388 {
389 yCError(RGBDSENSORNWSYARP) << "Attached device has no valid IRGBDSensor interface.";
390 return false;
391 }
392
393 if(!rgbdParser.configure(sensor_p))
394 {
395 yCError(RGBDSENSORNWSYARP) << "Error configuring IRGBD interface";
396 return false;
397 }
398
399 if(fgCtrl != nullptr)
400 {
401 if (!rgbdParser.configure(fgCtrl)) {
402 yCError(RGBDSENSORNWSYARP) << "Error configuring interfaces for parsers";
403 return false;
404 }
405 }
406 else
407 {
408 yCWarning(RGBDSENSORNWSYARP) << "Attached device has no valid IFrameGrabberControls interface.";
409 }
410
411 PeriodicThread::setPeriod(period);
412 return PeriodicThread::start();
413}
414
415/* IRateThread interface */
416
418{
419 // Get interface from attached device if any.
420 return true;
421}
422
424{
425 // Detach() calls stop() which in turns calls this functions, therefore no calls to detach here!
426}
427
428bool RgbdSensor_nws_yarp::setCamInfo(const std::string& frame_id, const UInt& seq, const SensorType& sensorType)
429{
430 double phyF = 0.0;
431 double fx = 0.0;
432 double fy = 0.0;
433 double cx = 0.0;
434 double cy = 0.0;
435 double k1 = 0.0;
436 double k2 = 0.0;
437 double t1 = 0.0;
438 double t2 = 0.0;
439 double k3 = 0.0;
440 double stamp = 0.0;
441
442 std::string distModel, currentSensor;
443 UInt i;
444 Property camData;
445 std::vector<param<double> > parVector;
446 param<double>* par;
447 bool ok;
448
449 currentSensor = sensorType == COLOR_SENSOR ? "Rgb" : "Depth";
450 ok = sensorType == COLOR_SENSOR ? sensor_p->getRgbIntrinsicParam(camData) : sensor_p->getDepthIntrinsicParam(camData);
451
452 if (!ok)
453 {
454 yCError(RGBDSENSORNWSYARP) << "Unable to get intrinsic param from" << currentSensor << "sensor!";
455 return false;
456 }
457
458 if(!camData.check("distortionModel"))
459 {
460 yCWarning(RGBDSENSORNWSYARP) << "Missing distortion model";
461 return false;
462 }
463
464 distModel = camData.find("distortionModel").asString();
465 if (distModel != "plumb_bob")
466 {
467 yCError(RGBDSENSORNWSYARP) << "Distortion model not supported";
468 return false;
469 }
470
471 //std::vector<param<std::string> > rosStringParam;
472 //rosStringParam.push_back(param<std::string>(nodeName, "asd"));
473
474 parVector.emplace_back(phyF,"physFocalLength");
475 parVector.emplace_back(fx,"focalLengthX");
476 parVector.emplace_back(fy,"focalLengthY");
477 parVector.emplace_back(cx,"principalPointX");
478 parVector.emplace_back(cy,"principalPointY");
479 parVector.emplace_back(k1,"k1");
480 parVector.emplace_back(k2,"k2");
481 parVector.emplace_back(t1,"t1");
482 parVector.emplace_back(t2,"t2");
483 parVector.emplace_back(k3,"k3");
484 parVector.emplace_back(stamp,"stamp");
485 for(i = 0; i < parVector.size(); i++)
486 {
487 par = &parVector[i];
488
489 if(!camData.check(par->parname))
490 {
491 yCWarning(RGBDSENSORNWSYARP) << "Driver has not the param:" << par->parname;
492 return false;
493 }
494 *par->var = camData.find(par->parname).asFloat64();
495 }
496
497 return true;
498}
499
500bool RgbdSensor_nws_yarp::writeData()
501{
502 //colorImage.setPixelCode(VOCAB_PIXEL_RGB);
503 // depthImage.setPixelCode(VOCAB_PIXEL_MONO_FLOAT);
504
505 // colorImage.resize(hDim, vDim); // Has this to be done each time? If size is the same what it does?
506 // depthImage.resize(hDim, vDim);
507 if (!sensor_p->getImages(colorImage, depthImage, &colorStamp, &depthStamp))
508 {
509 return false;
510 }
511
512 static Stamp oldColorStamp = Stamp(0, 0);
513 static Stamp oldDepthStamp = Stamp(0, 0);
514 bool rgb_data_ok = true;
515 bool depth_data_ok = true;
516
517 if (((colorStamp.getTime() - oldColorStamp.getTime()) > 0) == false)
518 {
519 rgb_data_ok=false;
520 //return true;
521 }
522 else { oldColorStamp = colorStamp; }
523
524 if (((depthStamp.getTime() - oldDepthStamp.getTime()) > 0) == false)
525 {
526 depth_data_ok=false;
527 //return true;
528 }
529 else { oldDepthStamp = depthStamp; }
530
531 // TBD: We should check here somehow if the timestamp was correctly updated and, if not, update it ourselves.
532 if (rgb_data_ok)
533 {
534 FlexImage& yColorImage = colorFrame_StreamingPort.prepare();
535 yColorImage.setPixelCode(colorImage.getPixelCode());
536 yColorImage.setQuantum(colorImage.getQuantum());
537 yColorImage.setExternal(colorImage.getRawImage(), colorImage.width(), colorImage.height());
538 colorFrame_StreamingPort.setEnvelope(colorStamp);
539 colorFrame_StreamingPort.write();
540 }
541 if (depth_data_ok)
542 {
543 ImageOf<PixelFloat>& yDepthImage = depthFrame_StreamingPort.prepare();
544 yDepthImage.setQuantum(depthImage.getQuantum());
546 depthFrame_StreamingPort.setEnvelope(depthStamp);
547 depthFrame_StreamingPort.write();
548 }
549
550 return true;
551}
552
554{
555 if (sensor_p!=nullptr)
556 {
557 static int i = 0;
558 sensorStatus = sensor_p->getSensorStatus();
559 switch (sensorStatus)
560 {
561 case(IRGBDSensor::RGBD_SENSOR_OK_IN_USE) :
562 {
563 if (!writeData()) {
564 yCError(RGBDSENSORNWSYARP, "Image not captured.. check hardware configuration");
565 }
566 i = 0;
567 }
568 break;
569 case(IRGBDSensor::RGBD_SENSOR_NOT_READY):
570 {
571 if(i < 1000) {
572 if((i % 30) == 0) {
573 yCInfo(RGBDSENSORNWSYARP) << "Device not ready, waiting...";
574 }
575 } else {
576 yCWarning(RGBDSENSORNWSYARP) << "Device is taking too long to start..";
577 }
578 i++;
579 }
580 break;
581 default:
582 {
583 if (verbose >= 1) { // better not to print it every cycle anyway, too noisy
584 yCError(RGBDSENSORNWSYARP, "%s: Sensor returned error", sensorId.c_str());
585 }
586 }
587 }
588 }
589 else
590 {
591 if(verbose >= 6) {
592 yCError(RGBDSENSORNWSYARP, "%s: Sensor interface is not valid", sensorId.c_str());
593 }
594 }
595}
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
#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.
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: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.
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
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: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
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: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
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
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 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
void setQuantum(size_t imgQuantum)
Definition: Image.h:426
void setPixelCode(int imgPixelCode)
Definition: Image.h:414
void setQuantum(size_t imgQuantum)
Definition: Image.cpp:502
size_t width() const
Gets width of image in pixels.
Definition: Image.h:163
void setExternal(const void *data, size_t imgWidth, size_t imgHeight)
Use this to wrap an external image.
Definition: Image.cpp:904
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition: Image.cpp:542
size_t getQuantum() const
The size of a row is constrained to be a multiple of the "quantum".
Definition: Image.h:196
size_t height() const
Gets height of image in pixels.
Definition: Image.h:169
virtual int getPixelCode() const
Gets pixel type identifier.
Definition: Image.cpp:441
A class for a Matrix.
Definition: Matrix.h:39
#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
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.