YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
MultipleAnalogSensorsServer.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
8
10
11#include <yarp/os/Log.h>
13#include <yarp/os/Property.h>
15
16
17namespace {
18YARP_LOG_COMPONENT(MULTIPLEANALOGSENSORSSERVER, "yarp.device.multipleanalogsensorsserver")
19}
20
37
42{
43 switch(type)
44 {
46 return 3;
47 break;
49 return 3;
50 break;
52 return 3;
53 break;
55 return 3;
56 break;
57 case PositionSensors:
58 return 3;
59 break;
61 return 1;
62 break;
64 return 6;
65 break;
66 default:
67 assert(false);
68 // "MAS_getMeasureSizeFromEnum passed unexepcted enum";
69 return 0;
70 break;
71 }
72}
73
74inline std::string MAS_getStatusString(const yarp::dev::MAS_status status)
75{
76 switch(status)
77 {
79 return "MAS_OK";
80 break;
82 return "MAS_ERROR";
83 break;
85 return "MAS_OVF";
86 break;
88 return "MAS_TIMEOUT";
89 break;
91 return "MAS_WAITING_FOR_FIRST_READ";
92 break;
94 return "MAS_UNKNOWN";
95 break;
96 default:
97 assert(false);
98 // "MAS_getStatusString passed unexepcted enum";
99 return "";
100 break;
101 }
102}
103
104
105
107 PeriodicThread(0.02)
108{
109}
110
112
114{
115 if (!config.check("name"))
116 {
117 yCError(MULTIPLEANALOGSENSORSSERVER, "Missing name parameter, exiting.");
118 return false;
119 }
120
121 if (!config.check("period"))
122 {
123 yCError(MULTIPLEANALOGSENSORSSERVER, "Missing period parameter, exiting.");
124 return false;
125 }
126
127 if (!config.find("period").isInt32())
128 {
129 yCError(MULTIPLEANALOGSENSORSSERVER, "Period parameter is present but it is not an integer, exiting.");
130 return false;
131 }
132
133 m_periodInS = config.find("period").asInt32() / 1000.0;
134
135 if (m_periodInS <= 0)
136 {
137 yCError(MULTIPLEANALOGSENSORSSERVER,
138 "Period parameter is present (%f) but it is not a positive integer, exiting.",
139 m_periodInS);
140 return false;
141 }
142
143 std::string name = config.find("name").asString();
144
145 // Reserve a fair amount of elements
146 // It would be great if yarp::sig::Vector had a reserve method
147 m_buffer.resize(100);
148 m_buffer.resize(0);
149
150 // TODO(traversaro) Add port name validation when ready,
151 // see https://github.com/robotology/yarp/pull/1508
152 m_RPCPortName = name + "/rpc:o";
153 m_streamingPortName = name + "/measures:o";
154
155 if (config.check("subdevice"))
156 {
157 std::string subdeviceName = config.find("subdevice").asString();
158
159 yarp::os::Property driverConfig;
160 driverConfig.fromString(config.toString());
161 driverConfig.setMonitor(config.getMonitor(), subdeviceName.c_str()); // pass on any monitoring
162 driverConfig.put("device", subdeviceName);
163
164 if (!m_subdevice.open(driverConfig))
165 {
166 yCError(MULTIPLEANALOGSENSORSSERVER, "Opening subdevice failed.");
167 return false;
168 }
169
170 yarp::dev::PolyDriverList driverList;
171 driverList.push(&m_subdevice, subdeviceName.c_str());
172
173 if (!attachAll(driverList))
174 {
175 yCError(MULTIPLEANALOGSENSORSSERVER, "Attaching subdevice failed.");
176 return false;
177 }
178
179 yCInfo(MULTIPLEANALOGSENSORSSERVER,
180 "Subdevice \"%s\" successfully configured and attached.",
181 subdeviceName.c_str());
182 m_isDeviceOwned = true;
183 }
184
185 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Open complete");
186 return true;
187}
188
190{
191 bool ok = this->detachAll();
192
193 if (m_isDeviceOwned)
194 {
195 ok &= m_subdevice.close();
196 m_isDeviceOwned = false;
197 }
198
199 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Close complete");
200 return ok;
201}
202
203// Note: as soon as we support only C++17, we can switch to using std::invoke
204// See https://isocpp.org/wiki/faq/pointers-to-members#fnptr-vs-memfnptr-types
205#define MAS_CALL_MEMBER_FN(object, ptrToMember) ((*object).*(ptrToMember))
206
207template<typename Interface>
208bool MultipleAnalogSensorsServer::populateSensorsMetadata(Interface * wrappedDeviceInterface,
209 std::vector<SensorMetadata>& metadataVector, const std::string& tag,
210 size_t (Interface::*getNrOfSensorsMethodPtr)() const,
211 bool (Interface::*getNameMethodPtr)(size_t, std::string&) const,
212 bool (Interface::*getFrameNameMethodPtr)(size_t, std::string&) const)
213{
214 if (wrappedDeviceInterface)
215 {
216 size_t nrOfSensors = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNrOfSensorsMethodPtr)();
217 metadataVector.resize(nrOfSensors);
218 for (size_t i=0; i < nrOfSensors; i++)
219 {
220 std::string sensorName;
221 bool ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNameMethodPtr)(i, sensorName);
222 if (!ok)
223 {
224 yCError(MULTIPLEANALOGSENSORSSERVER,
225 "Failure in reading name of sensor of type %s at index %zu.",
226 tag.c_str(),
227 i);
228 return false;
229 }
230 std::string frameName;
231 ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getFrameNameMethodPtr)(i, frameName);
232 if (!ok)
233 {
234 yCError(MULTIPLEANALOGSENSORSSERVER,
235 "Failure in reading frame name of sensor of type %s at index %zu.",
236 tag.c_str(),
237 i);
238 return false;
239 }
240
241 metadataVector[i].name = sensorName;
242 metadataVector[i].frameName = frameName;
243 metadataVector[i].additionalMetadata = "";
244 }
245
246 }
247 else
248 {
249 metadataVector.resize(0);
250 }
251 return true;
252}
253
254template<typename Interface>
255bool MultipleAnalogSensorsServer::populateSensorsMetadataNoFrameName(Interface * wrappedDeviceInterface,
256 std::vector<SensorMetadata>& metadataVector, const std::string& tag,
257 size_t (Interface::*getNrOfSensorsMethodPtr)() const,
258 bool (Interface::*getNameMethodPtr)(size_t, std::string&) const)
259{
260 if (wrappedDeviceInterface)
261 {
262 size_t nrOfSensors = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNrOfSensorsMethodPtr)();
263 metadataVector.resize(nrOfSensors);
264 for (size_t i=0; i < nrOfSensors; i++)
265 {
266 std::string sensorName;
267 bool ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNameMethodPtr)(i, sensorName);
268 if (!ok)
269 {
270 yCError(MULTIPLEANALOGSENSORSSERVER,
271 "Failure in reading name of sensor of type %s at index %zu.",
272 tag.c_str(),
273 i);
274 return false;
275 }
276
277 metadataVector[i].name = sensorName;
278 metadataVector[i].frameName = "";
279 metadataVector[i].additionalMetadata = "";
280 }
281
282 }
283 else
284 {
285 metadataVector.resize(0);
286 }
287 return true;
288}
289
290
291bool MultipleAnalogSensorsServer::populateAllSensorsMetadata()
292{
293 bool ok = true;
294 ok = ok && populateSensorsMetadata(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes, "ThreeAxisGyroscopes",
298 ok = ok && populateSensorsMetadata(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers, "ThreeAxisLinearAccelerometers",
302 ok = ok && populateSensorsMetadata(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers, "ThreeAxisMagnetometers",
306 ok = ok && populateSensorsMetadata(m_iPositionSensors, m_sensorMetadata.PositionSensors, "PositionSensors",
310 ok = ok && populateSensorsMetadata(m_iOrientationSensors, m_sensorMetadata.OrientationSensors, "OrientationSensors",
314 ok = ok && populateSensorsMetadata(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors, "TemperatureSensors",
318 ok = ok && populateSensorsMetadata(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors, "SixAxisForceTorqueSensors",
322 ok = ok && populateSensorsMetadataNoFrameName(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays, "ContactLoadCellArrays",
325 ok = ok && populateSensorsMetadataNoFrameName(m_iEncoderArrays, m_sensorMetadata.EncoderArrays, "EncoderArrays",
328 ok = ok && populateSensorsMetadataNoFrameName(m_iSkinPatches, m_sensorMetadata.SkinPatches, "ISkinPatches",
331
332 return ok;
333}
334
335// Function to resize the measure vectors, variant where the size is given by a method
336template<typename Interface>
337bool MultipleAnalogSensorsServer::resizeMeasureVectors(Interface* wrappedDeviceInterface,
338 const std::vector< SensorMetadata >& metadataVector,
339 std::vector< SensorMeasurement >& streamingDataVector,
340 size_t (Interface::*getMeasureSizePtr)(size_t) const)
341{
342 if (wrappedDeviceInterface)
343 {
344 size_t nrOfSensors = metadataVector.size();
345 streamingDataVector.resize(nrOfSensors);
346 for (size_t i=0; i < nrOfSensors; i++)
347 {
348 size_t measureSize = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getMeasureSizePtr)(i);
349 streamingDataVector[i].measurement.resize(measureSize, std::numeric_limits<double>::quiet_NaN());
350 }
351 }
352
353 return true;
354}
355
356// Function to resize the measure vectors, variant where the measure size is given by the type of the sensor
357template<typename Interface>
358bool MultipleAnalogSensorsServer::resizeMeasureVectors(Interface* wrappedDeviceInterface,
359 const std::vector< SensorMetadata >& metadataVector,
360 std::vector< SensorMeasurement >& streamingDataVector,
361 size_t measureSize)
362{
363 if (wrappedDeviceInterface)
364 {
365 size_t nrOfSensors = metadataVector.size();
366 streamingDataVector.resize(nrOfSensors);
367 for (size_t i=0; i < nrOfSensors; i++)
368 {
369 streamingDataVector[i].measurement.resize(measureSize, std::numeric_limits<double>::quiet_NaN());
370 }
371 }
372
373 return true;
374}
375
376bool MultipleAnalogSensorsServer::resizeAllMeasureVectors(SensorStreamingData& streamingData)
377{
378 bool ok = true;
379 // The size of each sensor is given in the interface documentation
380 ok = ok && resizeMeasureVectors(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes,
382 ok = ok && resizeMeasureVectors(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers,
384 ok = ok && resizeMeasureVectors(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers,
386 ok = ok && resizeMeasureVectors(m_iPositionSensors, m_sensorMetadata.PositionSensors,
388 ok = ok && resizeMeasureVectors(m_iOrientationSensors, m_sensorMetadata.OrientationSensors,
390 ok = ok && resizeMeasureVectors(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors,
392 ok = ok && resizeMeasureVectors(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors,
394 ok = ok && resizeMeasureVectors(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays,
396 ok = ok && resizeMeasureVectors(m_iEncoderArrays, m_sensorMetadata.EncoderArrays,
398 ok = ok && resizeMeasureVectors(m_iSkinPatches, m_sensorMetadata.SkinPatches,
400
401 return ok;
402}
403
405{
406 // Attach the device
407 if (p.size() > 1)
408 {
409 yCError(MULTIPLEANALOGSENSORSSERVER,
410 "This device only supports exposing a "
411 "single MultipleAnalogSensors device on YARP ports, but %d devices have been passed in attachAll.",
412 p.size());
413 yCError(MULTIPLEANALOGSENSORSSERVER,
414 "Please use the multipleanalogsensorsremapper device to combine several device in a new device.");
415 close();
416 return false;
417 }
418
419 if (p.size() == 0)
420 {
421 yCError(MULTIPLEANALOGSENSORSSERVER, "No device passed to attachAll, please pass a device to expose on YARP ports.");
422 close();
423 return false;
424 }
425
426 yarp::dev::PolyDriver* poly = p[0]->poly;
427
428 if (!poly)
429 {
430 yCError(MULTIPLEANALOGSENSORSSERVER, "Null pointer passed to attachAll.");
431 close();
432 return false;
433 }
434
435 // View all the interfaces
436 poly->view(m_iThreeAxisGyroscopes);
437 poly->view(m_iThreeAxisLinearAccelerometers);
438 poly->view(m_iThreeAxisMagnetometers);
439 poly->view(m_iPositionSensors);
440 poly->view(m_iOrientationSensors);
441 poly->view(m_iTemperatureSensors);
442 poly->view(m_iSixAxisForceTorqueSensors);
443 poly->view(m_iContactLoadCellArrays);
444 poly->view(m_iEncoderArrays);
445 poly->view(m_iSkinPatches);
446
447
448 // Populate the RPC data to be served on the RPC port
449 bool ok = populateAllSensorsMetadata();
450
451 if(!ok)
452 {
453 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in populateAllSensorsMetadata()");
454 close();
455 return false;
456 }
457
458 // Attach was successful, open the ports
459 ok = m_streamingPort.open(m_streamingPortName);
460 if (!ok)
461 {
462 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in opening port named %s.", m_streamingPortName.c_str());
463 close();
464 return false;
465 }
466
467 ok = this->yarp().attachAsServer(m_rpcPort);
468 if (!ok)
469 {
470 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in attaching RPC port to thrift RPC interface.");
471 close();
472 return false;
473 }
474
475 ok = m_rpcPort.open(m_RPCPortName);
476 if (!ok)
477 {
478 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in opening port named %s.", m_RPCPortName.c_str());
479 close();
480 return false;
481 }
482
483 // Set rate period
484 ok = this->setPeriod(m_periodInS);
485 ok = ok && this->start();
486 if (!ok)
487 {
488 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in starting thread.");
489 close();
490 return false;
491 }
492
493 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Attach complete");
494 return true;
495}
496
498{
499 // Stop the thread on detach
500 if (this->isRunning())
501 {
502 this->stop();
503 }
504
505 m_rpcPort.close();
506 m_streamingPort.close();
507
508 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Detach complete");
509 return true;
510}
511
513{
514 return m_sensorMetadata;
515}
516
517template<typename Interface>
518bool MultipleAnalogSensorsServer::genericStreamData(Interface* wrappedDeviceInterface,
519 const std::vector< SensorMetadata >& metadataVector,
520 std::vector< SensorMeasurement >& streamingDataVector,
521 yarp::dev::MAS_status (Interface::*getStatusMethodPtr)(size_t) const,
522 bool (Interface::*getMeasureMethodPtr)(size_t, yarp::sig::Vector&, double&) const,
523 const char* sensorType)
524{
525 if (wrappedDeviceInterface)
526 {
527 size_t nrOfSensors = metadataVector.size();
528 for (size_t i=0; i < nrOfSensors; i++)
529 {
530 yarp::sig::Vector& outputBuffer = streamingDataVector[i].measurement;
531 double& outputTimestamp = streamingDataVector[i].timestamp;
532 yarp::dev::MAS_status status = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getStatusMethodPtr)(i);
533 if (status == yarp::dev::MAS_OK)
534 {
535 MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getMeasureMethodPtr)(i, outputBuffer, outputTimestamp);
536 } else
537 {
538 yCError(MULTIPLEANALOGSENSORSSERVER,
539 "Failure in reading data from sensor %s of type %s with code %s, no data will be sent on the port.",
540 metadataVector[i].name.c_str(), sensorType, MAS_getStatusString(status).c_str());
541 return false;
542 }
543 }
544 }
545
546 return true;
547}
548
549
551{
552 SensorStreamingData& streamingData = m_streamingPort.prepare();
553
554 // Resize the output streaming buffer vectors to be of the correct size
555 bool ok = true;
556 ok = resizeAllMeasureVectors(streamingData);
557
558 // Populate buffers
559 ok = ok && genericStreamData(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes,
560 streamingData.ThreeAxisGyroscopes.measurements,
563 "ThreeAxisGyroscope");
564
565 ok = ok && genericStreamData(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers,
569 "ThreeAxisLinearAccelerometer");
570
571 ok = ok && genericStreamData(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers,
575 "ThreeAxisMagnetometer");
576
577 ok = ok && genericStreamData(m_iPositionSensors, m_sensorMetadata.PositionSensors,
578 streamingData.PositionSensors.measurements,
581 "PositionSensor");
582
583 ok = ok && genericStreamData(m_iOrientationSensors, m_sensorMetadata.OrientationSensors,
584 streamingData.OrientationSensors.measurements,
587 "OrientationSensor");
588
589 ok = ok && genericStreamData(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors,
590 streamingData.TemperatureSensors.measurements,
593 "TemperatureSensor");
594
595 ok = ok && genericStreamData(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors,
599 "SixAxisForceTorqueSensor");
600
601 ok = ok && genericStreamData(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays,
605 "ContactLoadCellArrays");
606
607 ok = ok && genericStreamData(m_iEncoderArrays, m_sensorMetadata.EncoderArrays,
608 streamingData.EncoderArrays.measurements,
611 "EncoderArray");
612
613 ok = ok && genericStreamData(m_iSkinPatches, m_sensorMetadata.SkinPatches,
614 streamingData.SkinPatches.measurements,
617 "SkinPatch");
618
619 if (ok)
620 {
621 m_stamp.update();
622 m_streamingPort.setEnvelope(m_stamp);
623 m_streamingPort.write();
624 }
625 else
626 {
627 m_streamingPort.unprepare();
628 }
629}
630
size_t size_t
#define MAS_CALL_MEMBER_FN(object, ptrToMember)
@ ThreeAxisLinearAccelerometers
std::string MAS_getStatusString(const yarp::dev::MAS_status status)
#define MAS_CALL_MEMBER_FN(object, ptrToMember)
MAS_SensorTypeServer
Internal identifier of the type of sensors.
@ ThreeAxisLinearAccelerometers
size_t MAS_getMeasureSizeFromEnum(const MAS_SensorTypeServer type)
Get measure size for sensors with fixed size measure.
bool detachAll() override
Detach the object (you must have first called attach).
SensorRPCData getMetadata() override
Read the sensor metadata necessary to configure the MultipleAnalogSensorsClient device.
void threadRelease() override
Release method.
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
bool attachAll(const yarp::dev::PolyDriverList &p) override
Attach to a list of objects.
std::vector< SensorMeasurement > measurements
std::vector< SensorMetadata > SkinPatches
std::vector< SensorMetadata > ContactLoadCellArrays
std::vector< SensorMetadata > EncoderArrays
std::vector< SensorMetadata > PositionSensors
std::vector< SensorMetadata > ThreeAxisGyroscopes
std::vector< SensorMetadata > ThreeAxisLinearAccelerometers
std::vector< SensorMetadata > ThreeAxisMagnetometers
std::vector< SensorMetadata > OrientationSensors
std::vector< SensorMetadata > SixAxisForceTorqueSensors
std::vector< SensorMetadata > TemperatureSensors
SensorMeasurements EncoderArrays
SensorMeasurements ThreeAxisLinearAccelerometers
SensorMeasurements PositionSensors
SensorMeasurements OrientationSensors
SensorMeasurements ThreeAxisMagnetometers
SensorMeasurements ThreeAxisGyroscopes
SensorMeasurements SixAxisForceTorqueSensors
SensorMeasurements SkinPatches
SensorMeasurements ContactLoadCellArrays
SensorMeasurements TemperatureSensors
bool view(T *&x)
Get an interface to the device driver.
virtual yarp::dev::MAS_status getContactLoadCellArrayStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getContactLoadCellArrayName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getContactLoadCellArraySize(size_t sens_index) const =0
Get the size of the specified contact load cell array.
virtual bool getContactLoadCellArrayMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual size_t getNrOfContactLoadCellArrays() const =0
Get the number of contact load cell array exposed by this device.
virtual bool getEncoderArrayMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual size_t getEncoderArraySize(size_t sens_index) const =0
Get the size of the specified encoder array.
virtual size_t getNrOfEncoderArrays() const =0
Get the number of encoder arrays exposed by this device.
virtual yarp::dev::MAS_status getEncoderArrayStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getEncoderArrayName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getOrientationSensorName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfOrientationSensors() const =0
Get the number of orientation sensors exposed by this device.
virtual bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double &timestamp) const =0
Get the last reading of the orientation sensor as roll pitch yaw.
virtual bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const =0
Get the last reading of the position sensor as x y z.
virtual bool getPositionSensorName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfPositionSensors() const =0
Get the number of position sensors exposed by this device.
virtual yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getPositionSensorFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getSixAxisForceTorqueSensorFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual size_t getNrOfSixAxisForceTorqueSensors() const =0
Get the number of six axis force torque sensors exposed by this device.
virtual yarp::dev::MAS_status getSixAxisForceTorqueSensorStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getSixAxisForceTorqueSensorName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual bool getSixAxisForceTorqueSensorMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual bool getSkinPatchName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfSkinPatches() const =0
Get the number of skin patches exposed by this device.
virtual size_t getSkinPatchSize(size_t sens_index) const =0
Get the size of the specified skin patch.
virtual yarp::dev::MAS_status getSkinPatchStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getSkinPatchMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual bool getTemperatureSensorFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getTemperatureSensorName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual yarp::dev::MAS_status getTemperatureSensorStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getTemperatureSensorMeasure(size_t sens_index, double &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual size_t getNrOfTemperatureSensors() const =0
Get the number of temperature sensors exposed by this device.
virtual yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfThreeAxisGyroscopes() const =0
Get the number of three axis gyroscopes exposed by this sensor.
virtual bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the gyroscope.
virtual bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfThreeAxisLinearAccelerometers() const =0
Get the number of three axis linear accelerometers exposed by this device.
virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfThreeAxisMagnetometers() const =0
Get the number of magnetometers exposed by this device.
virtual yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
void push(PolyDriver *p, const char *k)
A container for a device driver.
Definition PolyDriver.h:23
bool close() override
Close the DeviceDriver.
bool open(const std::string &txt)
Construct and configure a device by its common name.
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 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.
bool unprepare()
Give the last prepared object back to YARP without writing it.
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 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
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
Definition Searchable.h:56
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.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
yarp::os::WireLink & yarp()
Get YARP state associated with this object.
Definition Wire.h:28
void resize(size_t size) override
Resize the vector.
Definition Vector.h:221
#define yCInfo(component,...)
#define yCError(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
STL namespace.
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.
@ MAS_UNKNOWN
The sensor is in an unknown state.
@ MAS_TIMEOUT
The sensor is read through the network, and the latest measurement was received before an implementat...
@ MAS_ERROR
The sensor is in generic error state.
@ MAS_WAITING_FOR_FIRST_READ
The sensor is read through the network, and the device is waiting to receive the first measurement.
@ MAS_OK
The sensor is working correctly.
@ MAS_OVF
The sensor reached an overflow.
The main, catch-all namespace for YARP.
Definition dirs.h:16