YARP
Yet Another Robot Platform
MultipleAnalogSensorsInterfaces.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #ifndef YARP_DEV_MULTIPLEANALOGSENSORSINTERFACES_H
7 #define YARP_DEV_MULTIPLEANALOGSENSORSINTERFACES_H
8 
9 #include <cassert>
10 #include <string>
11 
12 #include <yarp/dev/api.h>
13 #include <yarp/sig/Vector.h>
14 
15 namespace yarp::dev {
16 class IThreeAxisGyroscopes;
17 class IThreeAxisLinearAccelerometers;
18 class IThreeAxisMagnetometers;
19 class IPositionSensors;
20 class IOrientationSensors;
21 class ITemperatureSensors;
22 class ISixAxisForceTorqueSensors;
23 class IContactLoadCellArrays;
24 class IEncoderArrays;
25 class ISkinPatches;
26 
31 {
32  MAS_OK = 0,
33  MAS_ERROR = 1,
34  MAS_OVF = 2,
37  MAS_UNKNOWN = 5
38 };
39 } // namespace yarp::dev
40 
57 {
58 public:
62  virtual size_t getNrOfThreeAxisGyroscopes() const = 0;
63 
69  virtual yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const = 0;
70 
77  virtual bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const = 0;
78 
85  virtual bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const = 0;
86 
95  virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
96 
98 };
99 
100 
111 {
112 public:
116  virtual size_t getNrOfThreeAxisLinearAccelerometers() const = 0;
117 
121  virtual yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const = 0;
122 
127  virtual bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const = 0;
128 
133  virtual bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const = 0;
134 
143  virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
144 
146 };
147 
158 {
159 public:
163  virtual size_t getNrOfThreeAxisMagnetometers() const = 0;
164 
168  virtual yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const = 0;
169 
174  virtual bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const = 0;
175 
180  virtual bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const = 0;
181 
190  virtual bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
191 
193 };
194 
209 {
210 public:
214  virtual size_t getNrOfPositionSensors() const = 0;
215 
219  virtual yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const = 0;
220 
225  virtual bool getPositionSensorName(size_t sens_index, std::string& name) const = 0;
226 
235  virtual bool getPositionSensorFrameName(size_t sens_index, std::string& frameName) const = 0;
236 
245  virtual bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector& xyz, double& timestamp) const = 0;
246 
248  {
249  }
250 };
251 
267 {
268 public:
272  virtual size_t getNrOfOrientationSensors() const = 0;
273 
277  virtual yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const = 0;
278 
283  virtual bool getOrientationSensorName(size_t sens_index, std::string &name) const = 0;
284 
293  virtual bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
294 
342  virtual bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const = 0;
343 
345 };
346 
347 
358 {
359 public:
363  virtual size_t getNrOfTemperatureSensors() const = 0;
364 
368  virtual yarp::dev::MAS_status getTemperatureSensorStatus(size_t sens_index) const = 0;
369 
373  virtual bool getTemperatureSensorName(size_t sens_index, std::string &name) const = 0;
374 
378  virtual bool getTemperatureSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
379 
384  virtual bool getTemperatureSensorMeasure(size_t sens_index, double& out, double& timestamp) const = 0;
385 
394  virtual bool getTemperatureSensorMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
395 
396 
398 };
399 
412 {
413 public:
417  virtual size_t getNrOfSixAxisForceTorqueSensors() const = 0;
418 
422  virtual yarp::dev::MAS_status getSixAxisForceTorqueSensorStatus(size_t sens_index) const = 0;
423 
427  virtual bool getSixAxisForceTorqueSensorName(size_t sens_index, std::string &name) const = 0;
428 
432  virtual bool getSixAxisForceTorqueSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
433 
442  virtual bool getSixAxisForceTorqueSensorMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
443 
445 };
446 
460 {
461 public:
465  virtual size_t getNrOfContactLoadCellArrays() const = 0;
466 
470  virtual yarp::dev::MAS_status getContactLoadCellArrayStatus(size_t sens_index) const = 0;
471 
476  virtual bool getContactLoadCellArrayName(size_t sens_index, std::string &name) const = 0;
477 
487  virtual bool getContactLoadCellArrayMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
488 
492  virtual size_t getContactLoadCellArraySize(size_t sens_index) const = 0;
493 
494 
496 };
497 
513 {
514 public:
518  virtual size_t getNrOfEncoderArrays() const = 0;
519 
523  virtual yarp::dev::MAS_status getEncoderArrayStatus(size_t sens_index) const = 0;
524 
528  virtual bool getEncoderArrayName(size_t sens_index, std::string &name) const = 0;
529 
538  virtual bool getEncoderArrayMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
539 
543  virtual size_t getEncoderArraySize(size_t sens_index) const = 0;
544 
545 
546  virtual ~IEncoderArrays(){}
547 };
548 
562 {
563 public:
567  virtual size_t getNrOfSkinPatches() const = 0;
568 
572  virtual yarp::dev::MAS_status getSkinPatchStatus(size_t sens_index) const = 0;
573 
577  virtual bool getSkinPatchName(size_t sens_index, std::string &name) const = 0;
578 
587  virtual bool getSkinPatchMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
588 
592  virtual size_t getSkinPatchSize(size_t sens_index) const = 0;
593 
594 
595  virtual ~ISkinPatches(){}
596 };
597 
598 #endif
contains the definition of a Vector type
Device interface to one or multiple contact load cell arrays.
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.
Device interface to one or multiple arrays of encoders.
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.
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
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.
Device interface to one or multiple position sensors, such as UWB localization sensors.
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.
Device interface to one or multiple six axis force torque 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.
Device interface to one or more groups (patches) of tactile sensors (skin).
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.
Device interface to one or multiple temperature sensors.
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 bool getTemperatureSensorMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
Device interface to one or multiple three axis gyroscopes.
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.
Device interface to one or multiple three axis linear accelerometers.
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.
Device interface to one or multiple three axis magnetometers.
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.
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_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
#define YARP_dev_API
Definition: api.h:18