18 YARP_LOG_COMPONENT(MULTIPLEANALOGSENSORSREMAPPER,
"yarp.device.multipleanalogsensorsremapper")
32 return "ThreeAxisGyroscopes";
35 return "ThreeAxisLinearAccelerometers";
38 return "ThreeAxisMagnetometers";
41 return "OrientationSensors";
44 return "TemperatureSensors";
47 return "SixAxisForceTorqueSensors";
50 return "ContactLoadCellArrays";
53 return "EncoderArrays";
59 return "PositionSensors";
63 return "MAS_getTagFromEnum_notExpectedEnum";
78 m_verbose = (prop.
check(
"verbose",
"if present, give detailed output"));
81 yCInfo(MULTIPLEANALOGSENSORSREMAPPER,
"Running with verbose output\n");
84 if(!parseOptions(prop))
97 bool keyExists = prop.
check(key);
100 if (!propList && keyExists)
102 yCError(MULTIPLEANALOGSENSORSREMAPPER) <<
"Error parsing parameters: if present " << key <<
" should be followed by a list of strings.\n";
106 if (!propList && !keyExists)
108 vectorOfStrings.resize(0);
112 vectorOfStrings.resize(propList->
size());
113 for (
size_t ax=0; ax < propList->
size(); ax++)
115 vectorOfStrings[ax] = propList->
get(ax).
asString();
121 bool MultipleAnalogSensorsRemapper::parseOptions(
const Property& prop)
134 yCError(MULTIPLEANALOGSENSORSREMAPPER) << optionName <<
"should be followed by a list of string.";
144 #define MAS_CALL_MEMBER_FN(object, ptrToMember) ((*object).*(ptrToMember))
147 template<
typename Interface>
148 bool MultipleAnalogSensorsRemapper::genericAttachAll(
const MAS_SensorType sensorType,
149 std::vector<Interface *>& subDeviceVec,
151 bool (Interface::*getNameMethodPtr)(
size_t, std::string&)
const,
152 size_t (Interface::*getNrOfSensorsMethodPtr)()
const)
154 std::map<std::string, SensorInSubDevice> sensorLocationMap;
156 subDeviceVec.resize(polylist.
size());
158 for(
int p=0; p<polylist.
size(); p++)
161 polylist[p]->poly->view(subDeviceVec[p]);
165 size_t nrOfSensorsInSubDevice =
MAS_CALL_MEMBER_FN(subDeviceVec[p], getNrOfSensorsMethodPtr)();
166 for (
size_t s=0; s < nrOfSensorsInSubDevice; s++)
172 yCError(MULTIPLEANALOGSENSORSREMAPPER) <<
"Failure in getting a name in the device " << polylist[p]->key;
177 if (sensorLocationMap.find(name) != sensorLocationMap.end())
179 SensorInSubDevice deviceWithSameName = sensorLocationMap.find(name)->second;
180 yCError(MULTIPLEANALOGSENSORSREMAPPER)
181 <<
"Sensor ambiguity: sensor with name"
183 <<
"present on both device"
185 << polylist[deviceWithSameName.subDevice]->key;
189 sensorLocationMap[name] = SensorInSubDevice(p, s);
195 std::vector<SensorInSubDevice>& sensIndicesMap = m_indicesMap[
static_cast<size_t>(sensorType)];
196 sensIndicesMap.resize(m_remappedSensors[sensorType].size());
197 for(
size_t i=0; i < m_remappedSensors[sensorType].size(); i++)
199 std::string name = m_remappedSensors[sensorType][i];
200 if (sensorLocationMap.find(name) == sensorLocationMap.end())
202 yCError(MULTIPLEANALOGSENSORSREMAPPER) <<
"Impossible to find sensor name" << name <<
", exiting.";
206 sensIndicesMap[i] = sensorLocationMap.find(name)->second;
219 &IThreeAxisGyroscopes::getThreeAxisGyroscopeName, &IThreeAxisGyroscopes::getNrOfThreeAxisGyroscopes);
221 &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerName, &IThreeAxisLinearAccelerometers::getNrOfThreeAxisLinearAccelerometers);
223 &IThreeAxisMagnetometers::getThreeAxisMagnetometerName, &IThreeAxisMagnetometers::getNrOfThreeAxisMagnetometers);
224 ok = ok && genericAttachAll(
PositionSensors, m_iPositionSensors, polylist,
225 &IPositionSensors::getPositionSensorName, &IPositionSensors::getNrOfPositionSensors);
227 &IOrientationSensors::getOrientationSensorName, &IOrientationSensors::getNrOfOrientationSensors);
229 &ITemperatureSensors::getTemperatureSensorName, &ITemperatureSensors::getNrOfTemperatureSensors);
231 &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorName, &ISixAxisForceTorqueSensors::getNrOfSixAxisForceTorqueSensors);
233 &IContactLoadCellArrays::getContactLoadCellArrayName, &IContactLoadCellArrays::getNrOfContactLoadCellArrays);
234 ok = ok && genericAttachAll(
EncoderArrays, m_iEncoderArrays, polylist,
235 &IEncoderArrays::getEncoderArrayName, &IEncoderArrays::getNrOfEncoderArrays);
236 ok = ok && genericAttachAll(
SkinPatches, m_iSkinPatches, polylist,
237 &ISkinPatches::getSkinPatchName, &ISkinPatches::getNrOfSkinPatches);
244 m_iThreeAxisGyroscopes.resize(0);
245 m_iThreeAxisLinearAccelerometers.resize(0);
246 m_iThreeAxisMagnetometers.resize(0);
247 m_iPositionSensors.resize(0);
248 m_iOrientationSensors.resize(0);
249 m_iTemperatureSensors.resize(0);
250 m_iSixAxisForceTorqueSensors.resize(0);
251 m_iContactLoadCellArrays.resize(0);
252 m_iEncoderArrays.resize(0);
253 m_iSkinPatches.resize(0);
254 m_indicesMap.resize(0);
259 template<
typename Interface>
262 const std::vector<Interface *>& subDeviceVec,
263 MAS_status (Interface::*methodPtr)(
size_t)
const)
const
265 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
266 if (sens_index >= nrOfAvailableSensors)
270 yCError(MULTIPLEANALOGSENSORSREMAPPER,
"genericGetStatus sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
275 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
276 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice);
279 template<
typename Interface>
280 bool MultipleAnalogSensorsRemapper::genericGetName(
const MAS_SensorType sensorType,
281 size_t& sens_index, std::string &name,
282 const std::vector<Interface *>& subDeviceVec,
283 bool (Interface::*methodPtr)(
size_t, std::string &)
const)
const
285 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
286 if (sens_index >= nrOfAvailableSensors)
290 yCError(MULTIPLEANALOGSENSORSREMAPPER,
"genericGetName sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
295 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
296 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, name);
299 template<
typename Interface>
300 bool MultipleAnalogSensorsRemapper::genericGetFrameName(
const MAS_SensorType sensorType,
301 size_t& sens_index, std::string &name,
302 const std::vector<Interface *>& subDeviceVec,
303 bool (Interface::*methodPtr)(
size_t, std::string &)
const)
const
305 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
306 if (sens_index >= nrOfAvailableSensors)
310 yCError(MULTIPLEANALOGSENSORSREMAPPER,
"genericGetFrameName sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
315 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
316 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, name);
320 template<
typename Interface>
321 bool MultipleAnalogSensorsRemapper::genericGetMeasure(
const MAS_SensorType sensorType,
323 const std::vector<Interface *>& subDeviceVec,
326 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
327 if (sens_index >= nrOfAvailableSensors)
331 yCError(MULTIPLEANALOGSENSORSREMAPPER,
"genericGetMeasure sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
336 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
337 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice, out, timestamp);
340 template<
typename Interface>
341 size_t MultipleAnalogSensorsRemapper::genericGetSize(
const MAS_SensorType sensorType,
343 const std::vector<Interface *>& subDeviceVec,
344 size_t (Interface::*methodPtr)(
size_t)
const)
const
346 size_t nrOfAvailableSensors = m_indicesMap[sensorType].size();
347 if (sens_index >= nrOfAvailableSensors)
351 yCError(MULTIPLEANALOGSENSORSREMAPPER,
"genericGetSize sens_index %zu out of range of available sensors (%zu).", sens_index, nrOfAvailableSensors);
356 SensorInSubDevice subDeviceSensor = m_indicesMap[sensorType][sens_index];
357 return MAS_CALL_MEMBER_FN(subDeviceVec[subDeviceSensor.subDevice], methodPtr)(subDeviceSensor.indexInSubDevice);
398 return genericGetStatus(
ThreeAxisGyroscopes, sens_index, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeStatus);
403 return genericGetName(
ThreeAxisGyroscopes, sens_index, name, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeName);
408 return genericGetFrameName(
ThreeAxisGyroscopes, sens_index, frameName, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeFrameName);
413 return genericGetMeasure(
ThreeAxisGyroscopes, sens_index, out, timestamp, m_iThreeAxisGyroscopes, &IThreeAxisGyroscopes::getThreeAxisGyroscopeMeasure);
423 return genericGetStatus(
ThreeAxisLinearAccelerometers, sens_index, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerStatus);
428 return genericGetName(
ThreeAxisLinearAccelerometers, sens_index, name, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerName);
433 return genericGetFrameName(
ThreeAxisLinearAccelerometers, sens_index, frameName, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerFrameName);
438 return genericGetMeasure(
ThreeAxisLinearAccelerometers, sens_index, out, timestamp, m_iThreeAxisLinearAccelerometers, &IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerMeasure);
448 return genericGetStatus(
ThreeAxisMagnetometers, sens_index, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerStatus);
453 return genericGetName(
ThreeAxisMagnetometers, sens_index, name, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerName);
458 return genericGetFrameName(
ThreeAxisMagnetometers, sens_index, frameName, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerFrameName);
463 return genericGetMeasure(
ThreeAxisMagnetometers, sens_index, out, timestamp, m_iThreeAxisMagnetometers, &IThreeAxisMagnetometers::getThreeAxisMagnetometerMeasure);
473 return genericGetStatus(
PositionSensors, sens_index, m_iPositionSensors, &IPositionSensors::getPositionSensorStatus);
478 return genericGetName(
PositionSensors, sens_index, name, m_iPositionSensors, &IPositionSensors::getPositionSensorName);
483 return genericGetFrameName(
PositionSensors, sens_index, frameName, m_iPositionSensors, &IPositionSensors::getPositionSensorFrameName);
488 return genericGetMeasure(
PositionSensors, sens_index, out, timestamp, m_iPositionSensors, &IPositionSensors::getPositionSensorMeasure);
498 return genericGetStatus(
OrientationSensors, sens_index, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorStatus);
503 return genericGetName(
OrientationSensors, sens_index, name, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorName);
508 return genericGetFrameName(
OrientationSensors, sens_index, frameName, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorFrameName);
513 return genericGetMeasure(
OrientationSensors, sens_index, out, timestamp, m_iOrientationSensors, &IOrientationSensors::getOrientationSensorMeasureAsRollPitchYaw);
523 return genericGetStatus(
TemperatureSensors, sens_index, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorStatus);
528 return genericGetName(
TemperatureSensors, sens_index, name, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorName);
533 return genericGetFrameName(
TemperatureSensors, sens_index, frameName, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorFrameName);
538 return genericGetMeasure(
TemperatureSensors, sens_index, out, timestamp, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorMeasure);
544 bool ok = genericGetMeasure(
TemperatureSensors, sens_index, dummy, timestamp, m_iTemperatureSensors, &ITemperatureSensors::getTemperatureSensorMeasure);
556 return genericGetStatus(
SixAxisForceTorqueSensors, sens_index, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorStatus);
561 return genericGetName(
SixAxisForceTorqueSensors, sens_index, name, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorName);
566 return genericGetFrameName(
SixAxisForceTorqueSensors, sens_index, frameName, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorFrameName);
571 return genericGetMeasure(
SixAxisForceTorqueSensors, sens_index, out, timestamp, m_iSixAxisForceTorqueSensors, &ISixAxisForceTorqueSensors::getSixAxisForceTorqueSensorMeasure);
581 return genericGetStatus(
ContactLoadCellArrays, sens_index, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArrayStatus);
586 return genericGetName(
ContactLoadCellArrays, sens_index, name, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArrayName);
591 return genericGetMeasure(
ContactLoadCellArrays, sens_index, out, timestamp, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArrayMeasure);
596 return genericGetSize(
ContactLoadCellArrays, sens_index, m_iContactLoadCellArrays, &IContactLoadCellArrays::getContactLoadCellArraySize);
606 return genericGetStatus(
EncoderArrays, sens_index, m_iEncoderArrays, &IEncoderArrays::getEncoderArrayStatus);
611 return genericGetName(
EncoderArrays, sens_index, name, m_iEncoderArrays, &IEncoderArrays::getEncoderArrayName);
616 return genericGetMeasure(
EncoderArrays, sens_index, out, timestamp, m_iEncoderArrays, &IEncoderArrays::getEncoderArrayMeasure);
621 return genericGetSize(
EncoderArrays, sens_index, m_iEncoderArrays, &IEncoderArrays::getEncoderArraySize);
631 return genericGetStatus(
SkinPatches, sens_index, m_iSkinPatches, &ISkinPatches::getSkinPatchStatus);
636 return genericGetName(
SkinPatches, sens_index, name, m_iSkinPatches, &ISkinPatches::getSkinPatchName);
641 return genericGetMeasure(
SkinPatches, sens_index, out, timestamp, m_iSkinPatches, &ISkinPatches::getSkinPatchMeasure);
646 return genericGetSize(
SkinPatches, sens_index, m_iSkinPatches, &ISkinPatches::getSkinPatchSize);
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.
@ ThreeAxisLinearAccelerometers
@ SixAxisForceTorqueSensors
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 ×tamp) 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 getTemperatureSensorMeasure(size_t sens_index, double &out, double ×tamp) const override
Get the last reading of the specified sensor.
bool getEncoderArrayMeasure(size_t sens_index, yarp::sig::Vector &out, double ×tamp) 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 ×tamp) 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.
bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame 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 ×tamp) 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 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.
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 ×tamp) 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 ×tamp) const override
Get the last reading of the specified sensor.
bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double ×tamp) 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 ×tamp) const override
Get the last reading 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 ×tamp) const override
Get the last reading of the orientation sensor as roll pitch yaw.
A simple collection of objects that can be described and transmitted in a portable way.
size_type size() const
Gets the number of elements in the bottle.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
A class for storing options and configuration information.
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.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle * asList() const
Get list value.
virtual std::string asString() const
Get string value.
#define yCInfo(component,...)
#define yCError(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
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.