YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
MultipleAnalogSensorsRemapper.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
8#include <map>
9
11#include <yarp/os/LogStream.h>
12#include <yarp/os/Searchable.h>
13
14using namespace yarp::os;
15using namespace yarp::dev;
16
17namespace {
18YARP_LOG_COMPONENT(MULTIPLEANALOGSENSORSREMAPPER, "yarp.device.multipleanalogsensorsremapper")
19}
20
21const size_t MAS_NrOfSensorTypes{12};
22static_assert(MAS_SensorType::ThreeAxisAngularAccelerometers+1 == MAS_NrOfSensorTypes, "Consistency error between MAS_NrOfSensorTypes and MAS_SensorType");
23
27inline std::string MAS_getTagFromEnum(const MAS_SensorType type)
28{
29 switch(type)
30 {
32 return "ThreeAxisGyroscopes";
33 break;
35 return "ThreeAxisLinearAccelerometers";
36 break;
38 return "ThreeAxisAngularAccelerometers";
39 break;
41 return "ThreeAxisMagnetometers";
42 break;
44 return "OrientationSensors";
45 break;
47 return "TemperatureSensors";
48 break;
50 return "SixAxisForceTorqueSensors";
51 break;
53 return "ContactLoadCellArrays";
54 break;
55 case EncoderArrays:
56 return "EncoderArrays";
57 break;
58 case SkinPatches:
59 return "SkinPatches";
60 break;
61 case PositionSensors:
62 return "PositionSensors";
63 break;
65 return "LinearVelocitySensors";
66 break;
67 default:
68 assert(false);
69 return "MAS_getTagFromEnum_notExpectedEnum";
70 break;
71 }
72}
73
78
80{
81 Property prop;
82 prop.fromString(config.toString());
83
84 m_verbose = (prop.check("verbose","if present, give detailed output"));
85 if (m_verbose)
86 {
87 yCInfo(MULTIPLEANALOGSENSORSREMAPPER, "Running with verbose output\n");
88 }
89
90 if(!parseOptions(prop))
91 {
92 return false;
93 }
94
95 return true;
96}
97
98// Return an empty list if the key is not found, and an error (false) if the key was found but it is not a list of strings
99bool getVectorOfStringFromListInConfig(const std::string& key, const yarp::os::Searchable& config, std::vector<std::string> & vectorOfStrings)
100{
102 prop.fromString(config.toString());
103 bool keyExists = prop.check(key);
104
106 if (!propList && keyExists)
107 {
108 yCError(MULTIPLEANALOGSENSORSREMAPPER) << "Error parsing parameters: if present " << key << " should be followed by a list of strings.\n";
109 return false;
110 }
111
112 if (!propList && !keyExists)
113 {
114 vectorOfStrings.resize(0);
115 return true;
116 }
117
118 vectorOfStrings.resize(propList->size());
119 for (size_t ax=0; ax < propList->size(); ax++)
120 {
121 vectorOfStrings[ax] = propList->get(ax).asString();
122 }
123
124 return true;
125}
126
127bool MultipleAnalogSensorsRemapper::parseOptions(const Property& prop)
128{
129 bool ok = true;
130
131 m_remappedSensors.resize(MAS_NrOfSensorTypes);
132
133 for (size_t i = 0; i < MAS_NrOfSensorTypes; i++)
134 {
135 auto sensType = static_cast<MAS_SensorType>(i);
136 std::string optionName = MAS_getTagFromEnum(sensType) +"Names";
137 ok = getVectorOfStringFromListInConfig(optionName , prop, m_remappedSensors[i]);
138 if (!ok)
139 {
140 yCError(MULTIPLEANALOGSENSORSREMAPPER) << optionName << "should be followed by a list of string.";
141 return false;
142 }
143 }
144
145 return ok;
146}
147
148// Note: as soon as we support only C++17, we can switch to using std::invoke
149// See https://isocpp.org/wiki/faq/pointers-to-members#fnptr-vs-memfnptr-types
150#define MAS_CALL_MEMBER_FN(object, ptrToMember) ((*object).*(ptrToMember))
151
152
153template<typename Interface>
154bool MultipleAnalogSensorsRemapper::genericAttachAll(const MAS_SensorType sensorType,
155 std::vector<Interface *>& subDeviceVec,
157 bool (Interface::*getNameMethodPtr)(size_t, std::string&) const,
159{
160 std::map<std::string, SensorInSubDevice> sensorLocationMap;
161
162 subDeviceVec.resize(polylist.size());
163
164 for(int p=0; p<polylist.size(); p++)
165 {
166 // If this fails it is ok, this just means that this devices does not expose this kind of sensors
167 polylist[p]->poly->view(subDeviceVec[p]);
168
169 if (subDeviceVec[p])
170 {
172 for (size_t s=0; s < nrOfSensorsInSubDevice; s++)
173 {
174 std::string name;
176 if (!ok)
177 {
178 yCError(MULTIPLEANALOGSENSORSREMAPPER) << "Failure in getting a name in the device " << polylist[p]->key;
179 return false;
180 }
181
182 // If the name is already in the map, raise an error
183 if (sensorLocationMap.find(name) != sensorLocationMap.end())
184 {
185 SensorInSubDevice deviceWithSameName = sensorLocationMap.find(name)->second;
187 << "Sensor ambiguity: sensor with name"
188 << name
189 << "present on both device"
190 << polylist[p]->key
191 << polylist[deviceWithSameName.subDevice]->key;
192 return false;
193 }
194
195 sensorLocationMap[name] = SensorInSubDevice(p, s);
196 }
197 }
198 }
199
200 // Fill the indices map given the name of all the subdevices
201 std::vector<SensorInSubDevice>& sensIndicesMap = m_indicesMap[static_cast<size_t>(sensorType)];
202 sensIndicesMap.resize(m_remappedSensors[sensorType].size());
203 for(size_t i=0; i < m_remappedSensors[sensorType].size(); i++)
204 {
205 std::string name = m_remappedSensors[sensorType][i];
206 if (sensorLocationMap.find(name) == sensorLocationMap.end())
207 {
208 yCError(MULTIPLEANALOGSENSORSREMAPPER) << "Impossible to find sensor name" << name << ", exiting.";
209 yCError(MULTIPLEANALOGSENSORSREMAPPER) << " Names of available sensors are:";
211 {
213 }
214 return false;
215 }
216
217 sensIndicesMap[i] = sensorLocationMap.find(name)->second;
218 }
219
220 return true;
221}
222
223
224
226{
227 bool ok = true;
228 m_indicesMap.resize(MAS_NrOfSensorTypes);
229 ok = ok && genericAttachAll(ThreeAxisGyroscopes, m_iThreeAxisGyroscopes, polylist,
231 ok = ok && genericAttachAll(ThreeAxisLinearAccelerometers, m_iThreeAxisLinearAccelerometers, polylist,
233 ok = ok && genericAttachAll(ThreeAxisAngularAccelerometers, m_iThreeAxisAngularAccelerometers, polylist,
235 ok = ok && genericAttachAll(ThreeAxisMagnetometers, m_iThreeAxisMagnetometers, polylist,
237 ok = ok && genericAttachAll(PositionSensors, m_iPositionSensors, polylist,
239 ok = ok && genericAttachAll(LinearVelocitySensors, m_iLinearVelocitySensors, polylist,
241 ok = ok && genericAttachAll(OrientationSensors, m_iOrientationSensors, polylist,
243 ok = ok && genericAttachAll(TemperatureSensors, m_iTemperatureSensors, polylist,
245 ok = ok && genericAttachAll(SixAxisForceTorqueSensors, m_iSixAxisForceTorqueSensors, polylist,
247 ok = ok && genericAttachAll(ContactLoadCellArrays, m_iContactLoadCellArrays, polylist,
249 ok = ok && genericAttachAll(EncoderArrays, m_iEncoderArrays, polylist,
251 ok = ok && genericAttachAll(SkinPatches, m_iSkinPatches, polylist,
253
254 return ok;
255}
256
258{
259 m_iThreeAxisGyroscopes.resize(0);
260 m_iThreeAxisLinearAccelerometers.resize(0);
261 m_iThreeAxisAngularAccelerometers.resize(0);
262 m_iThreeAxisMagnetometers.resize(0);
263 m_iPositionSensors.resize(0);
264 m_iLinearVelocitySensors.resize(0);
265 m_iOrientationSensors.resize(0);
266 m_iTemperatureSensors.resize(0);
267 m_iSixAxisForceTorqueSensors.resize(0);
268 m_iContactLoadCellArrays.resize(0);
269 m_iEncoderArrays.resize(0);
270 m_iSkinPatches.resize(0);
271 m_indicesMap.resize(0);
272 return true;
273}
274
275
276template<typename Interface>
277MAS_status MultipleAnalogSensorsRemapper::genericGetStatus(const MAS_SensorType sensorType,
278 size_t& sens_index,
279 const std::vector<Interface *>& subDeviceVec,
281{
282 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
284 {
285 if (m_verbose)
286 {
287 yCError(MULTIPLEANALOGSENSORSREMAPPER, "genericGetStatus sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
288 }
289 return MAS_ERROR;
290 }
291
292 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
293 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice);
294}
295
296template<typename Interface>
297bool MultipleAnalogSensorsRemapper::genericGetName(const MAS_SensorType sensorType,
298 size_t& sens_index, std::string &name,
299 const std::vector<Interface *>& subDeviceVec,
300 bool (Interface::*methodPtr)(size_t, std::string &) const) const
301{
302 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
304 {
305 if (m_verbose)
306 {
307 yCError(MULTIPLEANALOGSENSORSREMAPPER, "genericGetName sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
308 }
309 return MAS_ERROR;
310 }
311
312 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
313 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, name);
314}
315
316template<typename Interface>
317bool MultipleAnalogSensorsRemapper::genericGetFrameName(const MAS_SensorType sensorType,
318 size_t& sens_index, std::string &name,
319 const std::vector<Interface *>& subDeviceVec,
320 bool (Interface::*methodPtr)(size_t, std::string &) const) const
321{
322 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
324 {
325 if (m_verbose)
326 {
327 yCError(MULTIPLEANALOGSENSORSREMAPPER, "genericGetFrameName sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
328 }
329 return MAS_ERROR;
330 }
331
332 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
333 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, name);
334}
335
336
337template<typename Interface>
338bool MultipleAnalogSensorsRemapper::genericGetMeasure(const MAS_SensorType sensorType,
339 size_t& sens_index, yarp::sig::Vector& out, double& timestamp,
340 const std::vector<Interface *>& subDeviceVec,
342{
343 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
345 {
346 if (m_verbose)
347 {
348 yCError(MULTIPLEANALOGSENSORSREMAPPER, "genericGetMeasure sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
349 }
350 return MAS_ERROR;
351 }
352
353 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
354 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, out, timestamp);
355}
356
357template<typename Interface>
358size_t MultipleAnalogSensorsRemapper::genericGetSize(const MAS_SensorType sensorType,
359 size_t& sens_index,
360 const std::vector<Interface *>& subDeviceVec,
362{
363 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
365 {
366 if (m_verbose)
367 {
368 yCError(MULTIPLEANALOGSENSORSREMAPPER, "genericGetSize sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
369 }
370 return MAS_ERROR;
371 }
372
373 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
374 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice);
375}
376
377/*
378All the sensor specific methods (excluding the IOrientationSensor and the ISkinPatches) are just an instantiation of the following template (note: we avoid code generation for the sake of readability):
379
380size_t MultipleAnalogSensorsRemapper::getNrOf{{SensorTag}}s() const
381{
382 return m_indicesMap[{{SensorTag}}s].size();
383}
384
385MAS_status MultipleAnalogSensorsRemapper::get{{SensorTag}}Status(size_t sens_index) const
386{
387 return genericGetStatus({{SensorTag}}s, sens_index, m_i{{SensorTag}}s, &I{{SensorTag}}s::get{{SensorTag}}Status);
388}
389
390bool MultipleAnalogSensorsRemapper::get{{SensorTag}}Name(size_t sens_index, std::string& name) const
391{
392 return genericGetName({{SensorTag}}s, sens_index, name, m_i{{SensorTag}}s, &I{{SensorTag}}s::get{{SensorTag}}Name);
393}
394
395bool MultipleAnalogSensorsRemapper::get{{SensorTag}}Measure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const
396{
397 return genericGetMeasure({{SensorTag}}s, sens_index, out, timestamp, m_i{{SensorTag}}s, &I{{SensorTag}}s::get{{SensorTag}}Measure);
398}
399
400For the sensors (EncoderArray and SkinPatch) of which the measurements can change size, we also have:
401size_t MultipleAnalogSensorsRemapper::get{{SensorTag}}Size(size_t sens_index) const
402{
403 return genericGetSize({{SensorTag}}s, sens_index, m_i{{SensorTag}}s, &I{{SensorTag}}s::get{{SensorTag}}Size);
404}
405
406*/
407
409{
410 return m_indicesMap[ThreeAxisGyroscopes].size();
411}
412
417
419{
420 return genericGetName(ThreeAxisGyroscopes, sens_index, name, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeName);
421}
422
424{
425 return genericGetFrameName(ThreeAxisGyroscopes, sens_index, frameName, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeFrameName);
426}
427
429{
430 return genericGetMeasure(ThreeAxisGyroscopes, sens_index, out, timestamp, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeMeasure);
431}
432
437
442
444{
445 return genericGetName(ThreeAxisLinearAccelerometers, sens_index, name, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerName);
446}
447
449{
450 return genericGetFrameName(ThreeAxisLinearAccelerometers, sens_index, frameName, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerFrameName);
451}
452
454{
455 return genericGetMeasure(ThreeAxisLinearAccelerometers, sens_index, out, timestamp, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerMeasure);
456}
457
462
467
472
474{
475 return genericGetFrameName(ThreeAxisAngularAccelerometers, sens_index, frameName, m_iThreeAxisAngularAccelerometers, &IThreeAxisAngularAccelerometers::getThreeAxisAngularAccelerometerFrameName);
476}
477
479{
480 return genericGetMeasure(ThreeAxisAngularAccelerometers, sens_index, out, timestamp, m_iThreeAxisAngularAccelerometers, &IThreeAxisAngularAccelerometers::getThreeAxisAngularAccelerometerMeasure);
481}
482
484{
485 return m_indicesMap[ThreeAxisMagnetometers].size();
486}
487
492
494{
495 return genericGetName(ThreeAxisMagnetometers, sens_index, name, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerName);
496}
497
499{
500 return genericGetFrameName(ThreeAxisMagnetometers, sens_index, frameName, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerFrameName);
501}
502
504{
505 return genericGetMeasure(ThreeAxisMagnetometers, sens_index, out, timestamp, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerMeasure);
506}
507
509{
510 return m_indicesMap[PositionSensors].size();
511}
512
517
519{
520 return genericGetName(PositionSensors, sens_index, name, m_iPositionSensors, &IPositionSensors::getPositionSensorName);
521}
522
524{
525 return genericGetFrameName(PositionSensors, sens_index, frameName, m_iPositionSensors, &IPositionSensors::getPositionSensorFrameName);
526}
527
529{
530 return genericGetMeasure(PositionSensors, sens_index, out, timestamp, m_iPositionSensors, &IPositionSensors::getPositionSensorMeasure);
531}
532
534{
535 return m_indicesMap[LinearVelocitySensors].size();
536}
537
542
544{
545 return genericGetName(LinearVelocitySensors, sens_index, name, m_iLinearVelocitySensors, &ILinearVelocitySensors::getLinearVelocitySensorName);
546}
547
549{
550 return genericGetFrameName(LinearVelocitySensors, sens_index, frameName, m_iLinearVelocitySensors, &ILinearVelocitySensors::getLinearVelocitySensorFrameName);
551}
552
554{
555 return genericGetMeasure(LinearVelocitySensors, sens_index, out, timestamp, m_iLinearVelocitySensors, &ILinearVelocitySensors::getLinearVelocitySensorMeasure);
556}
557
559{
560 return m_indicesMap[OrientationSensors].size();
561}
562
567
569{
570 return genericGetName(OrientationSensors, sens_index, name, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorName);
571}
572
574{
575 return genericGetFrameName(OrientationSensors, sens_index, frameName, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorFrameName);
576}
577
579{
580 return genericGetMeasure(OrientationSensors, sens_index, out, timestamp, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorMeasureAsRollPitchYaw);
581}
582
584{
585 return m_indicesMap[TemperatureSensors].size();
586}
587
592
594{
595 return genericGetName(TemperatureSensors, sens_index, name, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorName);
596}
597
599{
600 return genericGetFrameName(TemperatureSensors, sens_index, frameName, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorFrameName);
601}
602
604{
605 return genericGetMeasure(TemperatureSensors, sens_index, out, timestamp, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorMeasure);
606}
607
608bool MultipleAnalogSensorsRemapper::getTemperatureSensorMeasure(size_t sens_index, double& out, double& timestamp) const
609{
610 yarp::sig::Vector dummy(1);
611 bool ok = genericGetMeasure(TemperatureSensors, sens_index, dummy, timestamp, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorMeasure);
612 out = dummy[0];
613 return ok;
614}
615
620
625
627{
628 return genericGetName(SixAxisForceTorqueSensors, sens_index, name, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorName);
629}
630
632{
633 return genericGetFrameName(SixAxisForceTorqueSensors, sens_index, frameName, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorFrameName);
634}
635
637{
638 return genericGetMeasure(SixAxisForceTorqueSensors, sens_index, out, timestamp, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorMeasure);
639}
640
642{
643 return m_indicesMap[ContactLoadCellArrays].size();
644}
645
650
652{
653 return genericGetName(ContactLoadCellArrays, sens_index, name, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArrayName);
654}
655
657{
658 return genericGetMeasure(ContactLoadCellArrays, sens_index, out, timestamp, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArrayMeasure);
659}
660
665
667{
668 return m_indicesMap[EncoderArrays].size();
669}
670
675
677{
678 return genericGetName(EncoderArrays, sens_index, name, m_iEncoderArrays, &IEncoderArrays::getEncoderArrayName);
679}
680
682{
683 return genericGetMeasure(EncoderArrays, sens_index, out, timestamp, m_iEncoderArrays, &IEncoderArrays::getEncoderArrayMeasure);
684}
685
687{
688 return genericGetSize(EncoderArrays, sens_index, m_iEncoderArrays, &IEncoderArrays::getEncoderArraySize);
689}
690
692{
693 return m_indicesMap[SkinPatches].size();
694}
695
700
702{
703 return genericGetName(SkinPatches, sens_index, name, m_iSkinPatches, &ISkinPatches::getSkinPatchName);
704}
705
707{
708 return genericGetMeasure(SkinPatches, sens_index, out, timestamp, m_iSkinPatches, &ISkinPatches::getSkinPatchMeasure);
709}
710
712{
713 return genericGetSize(SkinPatches, sens_index, m_iSkinPatches, &ISkinPatches::getSkinPatchSize);
714}
size_t size_t
const size_t MAS_NrOfSensorTypes
#define MAS_CALL_MEMBER_FN(object, ptrToMember)
bool getVectorOfStringFromListInConfig(const std::string &key, const yarp::os::Searchable &config, std::vector< std::string > &vectorOfStrings)
std::string MAS_getTagFromEnum(const MAS_SensorType type)
Internal identifier of the type of sensors.
MAS_SensorType
Internal identifier of the type of sensors.
@ ThreeAxisAngularAccelerometers
@ ThreeAxisLinearAccelerometers
bool getThreeAxisAngularAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
size_t getNrOfEncoderArrays() const override
Get the number of encoder arrays exposed by this device.
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
size_t getContactLoadCellArraySize(size_t sens_index) const override
Get the size of the specified contact load cell array.
size_t getNrOfSkinPatches() const override
Get the number of skin patches exposed by this device.
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers exposed by this device.
bool getThreeAxisAngularAccelerometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getTemperatureSensorMeasure(size_t sens_index, double &out, double &timestamp) const override
Get the last reading of the specified sensor.
yarp::dev::MAS_status getLinearVelocitySensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getLinearVelocitySensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getEncoderArrayMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
bool close() override
Close the DeviceDriver.
bool getContactLoadCellArrayMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool detachAll() override
Detach the object (you must have first called attach).
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool attachAll(const yarp::dev::PolyDriverList &p) override
MultipeWrapper methods.
size_t getNrOfLinearVelocitySensors() const override
Get the number of linear velocity sensors exposed by this device.
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
yarp::dev::MAS_status getThreeAxisAngularAccelerometerStatus(size_t sens_index) const override
Get the status of the specified sensor.
size_t getNrOfOrientationSensors() const override
Get the number of orientation sensors exposed by this device.
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the gyroscope.
size_t getNrOfPositionSensors() const override
Get the number of position sensors exposed by this device.
bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
size_t getNrOfThreeAxisAngularAccelerometers() const override
Get the number of three axis angular accelerometers exposed by this device.
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes exposed by this sensor.
bool getPositionSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
size_t getEncoderArraySize(size_t sens_index) const override
Get the size of the specified encoder array.
bool getPositionSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getContactLoadCellArrayName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
size_t getNrOfThreeAxisMagnetometers() const override
Get the number of magnetometers exposed by this device.
bool getLinearVelocitySensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
yarp::dev::MAS_status getSkinPatchStatus(size_t sens_index) const override
Get the status of the specified sensor.
size_t getNrOfContactLoadCellArrays() const override
Get the number of contact load cell array exposed by this device.
yarp::dev::MAS_status getEncoderArrayStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getTemperatureSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getSixAxisForceTorqueSensorMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
bool getLinearVelocitySensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const override
Get the last reading of the linear velocity sensor as x y z.
bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const override
Get the last reading of the position sensor as x y z.
yarp::dev::MAS_status getSixAxisForceTorqueSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
size_t getNrOfTemperatureSensors() const override
Get the number of temperature sensors exposed by this device.
bool getTemperatureSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
yarp::dev::MAS_status getContactLoadCellArrayStatus(size_t sens_index) const override
Get the status of the specified sensor.
yarp::dev::MAS_status getTemperatureSensorStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getSkinPatchMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the specified sensor.
bool getThreeAxisAngularAccelerometerName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
size_t getNrOfSixAxisForceTorqueSensors() const override
Get the number of six axis force torque sensors exposed by this device.
bool getSixAxisForceTorqueSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
size_t getSkinPatchSize(size_t sens_index) const override
Get the size of the specified skin patch.
bool getEncoderArrayName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getSkinPatchName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status of the specified sensor.
bool getSixAxisForceTorqueSensorFrameName(size_t sens_index, std::string &frame) const override
Get the name of the frame of the specified sensor.
bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector &rpy, double &timestamp) const override
Get the last reading of the orientation sensor as roll pitch yaw.
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 getLinearVelocitySensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const =0
Get the last reading of the linear velocity sensor as x y z.
virtual bool getLinearVelocitySensorName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
virtual size_t getNrOfLinearVelocitySensors() const =0
Get the number of linear velocity sensors exposed by this device.
virtual yarp::dev::MAS_status getLinearVelocitySensorStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getLinearVelocitySensorFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame 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 getThreeAxisAngularAccelerometerStatus(size_t sens_index) const =0
Get the status of the specified sensor.
virtual bool getThreeAxisAngularAccelerometerFrameName(size_t sens_index, std::string &frameName) const =0
Get the name of the frame of the specified sensor.
virtual bool getThreeAxisAngularAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
virtual size_t getNrOfThreeAxisAngularAccelerometers() const =0
Get the number of three axis angular accelerometers exposed by this device.
virtual bool getThreeAxisAngularAccelerometerName(size_t sens_index, std::string &name) const =0
Get the name of the specified sensor.
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.
A simple collection of objects that can be described and transmitted in a portable way.
Definition Bottle.h:64
A mini-server for performing network communication in the background.
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.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
A base class for nested structures that can be searched.
Definition Searchable.h:31
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle * asList() const
Get list value.
Definition Value.cpp:240
#define yCInfo(component,...)
#define yCError(component,...)
#define YARP_LOG_COMPONENT(name,...)
STL namespace.
For streams capable of holding different kinds of content, check what they actually have.
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.
@ MAS_ERROR
The sensor is in generic error state.
An interface to the operating system, including Port based communication.
VectorOf< double > Vector
Definition Vector.h:36
The main, catch-all namespace for YARP.
Definition dirs.h:16