YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
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
15namespace yarp::dev {
16class IThreeAxisGyroscopes;
17class IThreeAxisLinearAccelerometers;
18class IThreeAxisAngularAccelerometers;
19class IThreeAxisMagnetometers;
20class IPositionSensors;
21class ILinearVelocitySensors;
22class IOrientationSensors;
23class ITemperatureSensors;
24class ISixAxisForceTorqueSensors;
25class IContactLoadCellArrays;
26class IEncoderArrays;
27class ISkinPatches;
28
41} // namespace yarp::dev
42
59{
60public:
64 virtual size_t getNrOfThreeAxisGyroscopes() const = 0;
65
71 virtual yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const = 0;
72
79 virtual bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const = 0;
80
87 virtual bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const = 0;
88
97 virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
98
100};
101
102
113{
114public:
118 virtual size_t getNrOfThreeAxisLinearAccelerometers() const = 0;
119
124
129 virtual bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const = 0;
130
135 virtual bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const = 0;
136
145 virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
146
148};
149
151{
152public:
156 virtual size_t getNrOfThreeAxisAngularAccelerometers() const = 0;
157
162
167 virtual bool getThreeAxisAngularAccelerometerName(size_t sens_index, std::string &name) const = 0;
168
173 virtual bool getThreeAxisAngularAccelerometerFrameName(size_t sens_index, std::string &frameName) const = 0;
174
183 virtual bool getThreeAxisAngularAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
184
186};
187
198{
199public:
203 virtual size_t getNrOfThreeAxisMagnetometers() const = 0;
204
208 virtual yarp::dev::MAS_status getThreeAxisMagnetometerStatus(size_t sens_index) const = 0;
209
214 virtual bool getThreeAxisMagnetometerName(size_t sens_index, std::string &name) const = 0;
215
220 virtual bool getThreeAxisMagnetometerFrameName(size_t sens_index, std::string &frameName) const = 0;
221
230 virtual bool getThreeAxisMagnetometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
231
233};
234
249{
250public:
254 virtual size_t getNrOfPositionSensors() const = 0;
255
259 virtual yarp::dev::MAS_status getPositionSensorStatus(size_t sens_index) const = 0;
260
265 virtual bool getPositionSensorName(size_t sens_index, std::string& name) const = 0;
266
275 virtual bool getPositionSensorFrameName(size_t sens_index, std::string& frameName) const = 0;
276
285 virtual bool getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector& xyz, double& timestamp) const = 0;
286
288 {
289 }
290};
291
293{
294public:
298 virtual size_t getNrOfLinearVelocitySensors() const = 0;
299
303 virtual yarp::dev::MAS_status getLinearVelocitySensorStatus(size_t sens_index) const = 0;
304
309 virtual bool getLinearVelocitySensorName(size_t sens_index, std::string& name) const = 0;
310
319 virtual bool getLinearVelocitySensorFrameName(size_t sens_index, std::string& frameName) const = 0;
320
329 virtual bool getLinearVelocitySensorMeasure(size_t sens_index, yarp::sig::Vector& xyz, double& timestamp) const = 0;
330
332 {
333 }
334};
335
351{
352public:
356 virtual size_t getNrOfOrientationSensors() const = 0;
357
361 virtual yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const = 0;
362
367 virtual bool getOrientationSensorName(size_t sens_index, std::string &name) const = 0;
368
377 virtual bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
378
426 virtual bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const = 0;
427
429};
430
431
442{
443public:
447 virtual size_t getNrOfTemperatureSensors() const = 0;
448
452 virtual yarp::dev::MAS_status getTemperatureSensorStatus(size_t sens_index) const = 0;
453
457 virtual bool getTemperatureSensorName(size_t sens_index, std::string &name) const = 0;
458
462 virtual bool getTemperatureSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
463
468 virtual bool getTemperatureSensorMeasure(size_t sens_index, double& out, double& timestamp) const = 0;
469
478 virtual bool getTemperatureSensorMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
479
480
482};
483
496{
497public:
501 virtual size_t getNrOfSixAxisForceTorqueSensors() const = 0;
502
506 virtual yarp::dev::MAS_status getSixAxisForceTorqueSensorStatus(size_t sens_index) const = 0;
507
511 virtual bool getSixAxisForceTorqueSensorName(size_t sens_index, std::string &name) const = 0;
512
516 virtual bool getSixAxisForceTorqueSensorFrameName(size_t sens_index, std::string &frameName) const = 0;
517
526 virtual bool getSixAxisForceTorqueSensorMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
527
529};
530
544{
545public:
549 virtual size_t getNrOfContactLoadCellArrays() const = 0;
550
554 virtual yarp::dev::MAS_status getContactLoadCellArrayStatus(size_t sens_index) const = 0;
555
560 virtual bool getContactLoadCellArrayName(size_t sens_index, std::string &name) const = 0;
561
571 virtual bool getContactLoadCellArrayMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
572
576 virtual size_t getContactLoadCellArraySize(size_t sens_index) const = 0;
577
578
580};
581
597{
598public:
602 virtual size_t getNrOfEncoderArrays() const = 0;
603
607 virtual yarp::dev::MAS_status getEncoderArrayStatus(size_t sens_index) const = 0;
608
612 virtual bool getEncoderArrayName(size_t sens_index, std::string &name) const = 0;
613
622 virtual bool getEncoderArrayMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
623
627 virtual size_t getEncoderArraySize(size_t sens_index) const = 0;
628
629
630 virtual ~IEncoderArrays(){}
631};
632
646{
647public:
651 virtual size_t getNrOfSkinPatches() const = 0;
652
656 virtual yarp::dev::MAS_status getSkinPatchStatus(size_t sens_index) const = 0;
657
661 virtual bool getSkinPatchName(size_t sens_index, std::string &name) const = 0;
662
671 virtual bool getSkinPatchMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const = 0;
672
676 virtual size_t getSkinPatchSize(size_t sens_index) const = 0;
677
678
679 virtual ~ISkinPatches(){}
680};
681
682#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.
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.
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.
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.
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.
Definition jointData.cpp:13
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