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
39
44{
45 switch(type)
46 {
48 return 3;
49 break;
51 return 3;
52 break;
54 return 3;
55 break;
57 return 3;
58 break;
60 return 3;
61 break;
62 case PositionSensors:
63 return 3;
64 break;
66 return 3;
67 break;
69 return 1;
70 break;
72 return 6;
73 break;
74 default:
75 assert(false);
76 // "MAS_getMeasureSizeFromEnum passed unexepcted enum";
77 return 0;
78 break;
79 }
80}
81
82inline std::string MAS_getStatusString(const yarp::dev::MAS_status status)
83{
84 switch(status)
85 {
87 return "MAS_OK";
88 break;
90 return "MAS_ERROR";
91 break;
93 return "MAS_OVF";
94 break;
96 return "MAS_TIMEOUT";
97 break;
99 return "MAS_WAITING_FOR_FIRST_READ";
100 break;
102 return "MAS_UNKNOWN";
103 break;
104 default:
105 assert(false);
106 // "MAS_getStatusString passed unexepcted enum";
107 return "";
108 break;
109 }
110}
111
112
113
115 PeriodicThread(0.02)
116{
117}
118
120
122{
123 if (!parseParams(config)) { return false; }
124
125 m_periodInS = m_period / 1000.0;
126
127 if (m_periodInS <= 0)
128 {
129 yCError(MULTIPLEANALOGSENSORSSERVER,
130 "Period parameter is present (%f) but it is not a positive integer, exiting.",
131 m_periodInS);
132 return false;
133 }
134
135 // Reserve a fair amount of elements
136 // It would be great if yarp::sig::Vector had a reserve method
137 m_buffer.resize(100);
138 m_buffer.resize(0);
139
140 // TODO(traversaro) Add port name validation when ready,
141 // see https://github.com/robotology/yarp/pull/1508
142 m_RPCPortName = m_name + "/rpc:o";
143 m_streamingPortName = m_name + "/measures:o";
144
145 return true;
146}
147
149{
150 bool ok = this->detachAll();
151
152 return ok;
153}
154
155// Note: as soon as we support only C++17, we can switch to using std::invoke
156// See https://isocpp.org/wiki/faq/pointers-to-members#fnptr-vs-memfnptr-types
157#define MAS_CALL_MEMBER_FN(object, ptrToMember) ((*object).*(ptrToMember))
158
159template<typename Interface>
160bool MultipleAnalogSensorsServer::populateSensorsMetadata(Interface * wrappedDeviceInterface,
161 std::vector<SensorMetadata>& metadataVector, const std::string& tag,
162 size_t (Interface::*getNrOfSensorsMethodPtr)() const,
163 bool (Interface::*getNameMethodPtr)(size_t, std::string&) const,
164 bool (Interface::*getFrameNameMethodPtr)(size_t, std::string&) const)
165{
166 if (wrappedDeviceInterface)
167 {
168 size_t nrOfSensors = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNrOfSensorsMethodPtr)();
169 metadataVector.resize(nrOfSensors);
170 for (size_t i=0; i < nrOfSensors; i++)
171 {
172 std::string sensorName;
173 bool ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNameMethodPtr)(i, sensorName);
174 if (!ok)
175 {
176 yCError(MULTIPLEANALOGSENSORSSERVER,
177 "Failure in reading name of sensor of type %s at index %zu.",
178 tag.c_str(),
179 i);
180 return false;
181 }
182 std::string frameName;
183 ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getFrameNameMethodPtr)(i, frameName);
184 if (!ok)
185 {
186 yCError(MULTIPLEANALOGSENSORSSERVER,
187 "Failure in reading frame name of sensor of type %s at index %zu.",
188 tag.c_str(),
189 i);
190 return false;
191 }
192
193 metadataVector[i].name = sensorName;
194 metadataVector[i].frameName = frameName;
195 metadataVector[i].additionalMetadata = "";
196 }
197
198 }
199 else
200 {
201 metadataVector.resize(0);
202 }
203 return true;
204}
205
206template<typename Interface>
207bool MultipleAnalogSensorsServer::populateSensorsMetadataNoFrameName(Interface * wrappedDeviceInterface,
208 std::vector<SensorMetadata>& metadataVector, const std::string& tag,
209 size_t (Interface::*getNrOfSensorsMethodPtr)() const,
210 bool (Interface::*getNameMethodPtr)(size_t, std::string&) const)
211{
212 if (wrappedDeviceInterface)
213 {
214 size_t nrOfSensors = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNrOfSensorsMethodPtr)();
215 metadataVector.resize(nrOfSensors);
216 for (size_t i=0; i < nrOfSensors; i++)
217 {
218 std::string sensorName;
219 bool ok = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getNameMethodPtr)(i, sensorName);
220 if (!ok)
221 {
222 yCError(MULTIPLEANALOGSENSORSSERVER,
223 "Failure in reading name of sensor of type %s at index %zu.",
224 tag.c_str(),
225 i);
226 return false;
227 }
228
229 metadataVector[i].name = sensorName;
230 metadataVector[i].frameName = "";
231 metadataVector[i].additionalMetadata = "";
232 }
233
234 }
235 else
236 {
237 metadataVector.resize(0);
238 }
239 return true;
240}
241
242
243bool MultipleAnalogSensorsServer::populateAllSensorsMetadata()
244{
245 bool ok = true;
246 ok = ok && populateSensorsMetadata(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes, "ThreeAxisGyroscopes",
250 ok = ok && populateSensorsMetadata(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers, "ThreeAxisLinearAccelerometers",
254 ok = ok && populateSensorsMetadata(m_iThreeAxisAngularAccelerometers, m_sensorMetadata.ThreeAxisAngularAccelerometers, "ThreeAxisAngularAccelerometers",
258 ok = ok && populateSensorsMetadata(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers, "ThreeAxisMagnetometers",
262 ok = ok && populateSensorsMetadata(m_iPositionSensors, m_sensorMetadata.PositionSensors, "PositionSensors",
266 ok = ok && populateSensorsMetadata(m_iLinearVelocitySensors, m_sensorMetadata.LinearVelocitySensors, "LinearVelocitySensors",
270 ok = ok && populateSensorsMetadata(m_iOrientationSensors, m_sensorMetadata.OrientationSensors, "OrientationSensors",
274 ok = ok && populateSensorsMetadata(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors, "TemperatureSensors",
278 ok = ok && populateSensorsMetadata(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors, "SixAxisForceTorqueSensors",
282 ok = ok && populateSensorsMetadataNoFrameName(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays, "ContactLoadCellArrays",
285 ok = ok && populateSensorsMetadataNoFrameName(m_iEncoderArrays, m_sensorMetadata.EncoderArrays, "EncoderArrays",
288 ok = ok && populateSensorsMetadataNoFrameName(m_iSkinPatches, m_sensorMetadata.SkinPatches, "ISkinPatches",
291
292 return ok;
293}
294
295// Function to resize the measure vectors, variant where the size is given by a method
296template<typename Interface>
297bool MultipleAnalogSensorsServer::resizeMeasureVectors(Interface* wrappedDeviceInterface,
298 const std::vector< SensorMetadata >& metadataVector,
299 std::vector< SensorMeasurement >& streamingDataVector,
300 size_t (Interface::*getMeasureSizePtr)(size_t) const)
301{
302 if (wrappedDeviceInterface)
303 {
304 size_t nrOfSensors = metadataVector.size();
305 streamingDataVector.resize(nrOfSensors);
306 for (size_t i=0; i < nrOfSensors; i++)
307 {
308 size_t measureSize = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getMeasureSizePtr)(i);
309 streamingDataVector[i].measurement.resize(measureSize, std::numeric_limits<double>::quiet_NaN());
310 }
311 }
312
313 return true;
314}
315
316// Function to resize the measure vectors, variant where the measure size is given by the type of the sensor
317template<typename Interface>
318bool MultipleAnalogSensorsServer::resizeMeasureVectors(Interface* wrappedDeviceInterface,
319 const std::vector< SensorMetadata >& metadataVector,
320 std::vector< SensorMeasurement >& streamingDataVector,
321 size_t measureSize)
322{
323 if (wrappedDeviceInterface)
324 {
325 size_t nrOfSensors = metadataVector.size();
326 streamingDataVector.resize(nrOfSensors);
327 for (size_t i=0; i < nrOfSensors; i++)
328 {
329 streamingDataVector[i].measurement.resize(measureSize, std::numeric_limits<double>::quiet_NaN());
330 }
331 }
332
333 return true;
334}
335
336bool MultipleAnalogSensorsServer::resizeAllMeasureVectors(SensorStreamingData& streamingData)
337{
338 bool ok = true;
339 // The size of each sensor is given in the interface documentation
340 ok = ok && resizeMeasureVectors(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes,
342 ok = ok && resizeMeasureVectors(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers,
344 ok = ok && resizeMeasureVectors(m_iThreeAxisAngularAccelerometers, m_sensorMetadata.ThreeAxisAngularAccelerometers,
346 ok = ok && resizeMeasureVectors(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers,
348 ok = ok && resizeMeasureVectors(m_iPositionSensors, m_sensorMetadata.PositionSensors,
350 ok = ok && resizeMeasureVectors(m_iLinearVelocitySensors, m_sensorMetadata.LinearVelocitySensors,
352 ok = ok && resizeMeasureVectors(m_iOrientationSensors, m_sensorMetadata.OrientationSensors,
354 ok = ok && resizeMeasureVectors(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors,
356 ok = ok && resizeMeasureVectors(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors,
358 ok = ok && resizeMeasureVectors(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays,
360 ok = ok && resizeMeasureVectors(m_iEncoderArrays, m_sensorMetadata.EncoderArrays,
362 ok = ok && resizeMeasureVectors(m_iSkinPatches, m_sensorMetadata.SkinPatches,
364
365 return ok;
366}
367
369{
370 if (!poly)
371 {
372 yCError(MULTIPLEANALOGSENSORSSERVER, "Null pointer passed to attach.");
373 close();
374 return false;
375 }
376
377 // View all the interfaces
378 poly->view(m_iThreeAxisGyroscopes);
379 poly->view(m_iThreeAxisLinearAccelerometers);
380 poly->view(m_iThreeAxisAngularAccelerometers);
381 poly->view(m_iThreeAxisMagnetometers);
382 poly->view(m_iPositionSensors);
383 poly->view(m_iLinearVelocitySensors);
384 poly->view(m_iOrientationSensors);
385 poly->view(m_iTemperatureSensors);
386 poly->view(m_iSixAxisForceTorqueSensors);
387 poly->view(m_iContactLoadCellArrays);
388 poly->view(m_iEncoderArrays);
389 poly->view(m_iSkinPatches);
390
391
392 // Populate the RPC data to be served on the RPC port
393 bool ok = populateAllSensorsMetadata();
394
395 if(!ok)
396 {
397 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in populateAllSensorsMetadata()");
398 close();
399 return false;
400 }
401
402 // Attach was successful, open the ports
403 ok = m_streamingPort.open(m_streamingPortName);
404 if (!ok)
405 {
406 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in opening port named %s.", m_streamingPortName.c_str());
407 close();
408 return false;
409 }
410
411 ok = this->yarp().attachAsServer(m_rpcPort);
412 if (!ok)
413 {
414 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in attaching RPC port to thrift RPC interface.");
415 close();
416 return false;
417 }
418
419 ok = m_rpcPort.open(m_RPCPortName);
420 if (!ok)
421 {
422 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in opening port named %s.", m_RPCPortName.c_str());
423 close();
424 return false;
425 }
426
427 // Set rate period
428 ok = this->setPeriod(m_periodInS);
429 ok = ok && this->start();
430 if (!ok)
431 {
432 yCError(MULTIPLEANALOGSENSORSSERVER, "Failure in starting thread.");
433 close();
434 return false;
435 }
436
437 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Attach complete");
438 return true;
439}
440
442{
443 // Stop the thread on detach
444 if (this->isRunning())
445 {
446 this->stop();
447 }
448
449 m_rpcPort.close();
450 m_streamingPort.close();
451
452 yCDebug(MULTIPLEANALOGSENSORSSERVER, "Detach complete");
453 return true;
454}
455
457{
458 return m_sensorMetadata;
459}
460
461template<typename Interface>
462bool MultipleAnalogSensorsServer::genericStreamData(Interface* wrappedDeviceInterface,
463 const std::vector< SensorMetadata >& metadataVector,
464 std::vector< SensorMeasurement >& streamingDataVector,
465 yarp::dev::MAS_status (Interface::*getStatusMethodPtr)(size_t) const,
466 bool (Interface::*getMeasureMethodPtr)(size_t, yarp::sig::Vector&, double&) const,
467 const char* sensorType)
468{
469 if (wrappedDeviceInterface)
470 {
471 size_t nrOfSensors = metadataVector.size();
472 for (size_t i=0; i < nrOfSensors; i++)
473 {
474 yarp::sig::Vector& outputBuffer = streamingDataVector[i].measurement;
475 double& outputTimestamp = streamingDataVector[i].timestamp;
476 yarp::dev::MAS_status status = MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getStatusMethodPtr)(i);
477 if (status == yarp::dev::MAS_OK)
478 {
479 MAS_CALL_MEMBER_FN(wrappedDeviceInterface, getMeasureMethodPtr)(i, outputBuffer, outputTimestamp);
480 } else
481 {
482 yCError(MULTIPLEANALOGSENSORSSERVER,
483 "Failure in reading data from sensor %s of type %s with code %s, no data will be sent on the port.",
484 metadataVector[i].name.c_str(), sensorType, MAS_getStatusString(status).c_str());
485 return false;
486 }
487 }
488 }
489
490 return true;
491}
492
493
495{
496 SensorStreamingData& streamingData = m_streamingPort.prepare();
497
498 // Resize the output streaming buffer vectors to be of the correct size
499 bool ok = true;
500 ok = resizeAllMeasureVectors(streamingData);
501
502 // Populate buffers
503 ok = ok && genericStreamData(m_iThreeAxisGyroscopes, m_sensorMetadata.ThreeAxisGyroscopes,
504 streamingData.ThreeAxisGyroscopes.measurements,
507 "ThreeAxisGyroscope");
508
509 ok = ok && genericStreamData(m_iThreeAxisLinearAccelerometers, m_sensorMetadata.ThreeAxisLinearAccelerometers,
513 "ThreeAxisLinearAccelerometer");
514
515 ok = ok && genericStreamData(m_iThreeAxisAngularAccelerometers, m_sensorMetadata.ThreeAxisAngularAccelerometers,
519 "ThreeAxisAngularAccelerometer");
520
521 ok = ok && genericStreamData(m_iThreeAxisMagnetometers, m_sensorMetadata.ThreeAxisMagnetometers,
525 "ThreeAxisMagnetometer");
526
527 ok = ok && genericStreamData(m_iPositionSensors, m_sensorMetadata.PositionSensors,
528 streamingData.PositionSensors.measurements,
531 "PositionSensor");
532
533 ok = ok && genericStreamData(m_iLinearVelocitySensors, m_sensorMetadata.LinearVelocitySensors,
537 "LinearVelocitySensor");
538
539 ok = ok && genericStreamData(m_iOrientationSensors, m_sensorMetadata.OrientationSensors,
540 streamingData.OrientationSensors.measurements,
543 "OrientationSensor");
544
545 ok = ok && genericStreamData(m_iTemperatureSensors, m_sensorMetadata.TemperatureSensors,
546 streamingData.TemperatureSensors.measurements,
549 "TemperatureSensor");
550
551 ok = ok && genericStreamData(m_iSixAxisForceTorqueSensors, m_sensorMetadata.SixAxisForceTorqueSensors,
555 "SixAxisForceTorqueSensor");
556
557 ok = ok && genericStreamData(m_iContactLoadCellArrays, m_sensorMetadata.ContactLoadCellArrays,
561 "ContactLoadCellArrays");
562
563 ok = ok && genericStreamData(m_iEncoderArrays, m_sensorMetadata.EncoderArrays,
564 streamingData.EncoderArrays.measurements,
567 "EncoderArray");
568
569 ok = ok && genericStreamData(m_iSkinPatches, m_sensorMetadata.SkinPatches,
570 streamingData.SkinPatches.measurements,
573 "SkinPatch");
574
575 if (ok)
576 {
577 m_stamp.update();
578 m_streamingPort.setEnvelope(m_stamp);
579 m_streamingPort.write();
580 }
581 else
582 {
583 m_streamingPort.unprepare();
584 }
585}
586
size_t size_t
#define MAS_CALL_MEMBER_FN(object, ptrToMember)
@ ThreeAxisAngularAccelerometers
@ 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.
@ ThreeAxisAngularAccelerometers
@ ThreeAxisLinearAccelerometers
size_t MAS_getMeasureSizeFromEnum(const MAS_SensorTypeServer type)
Get measure size for sensors with fixed size measure.
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
bool detach() 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 attach(yarp::dev::PolyDriver *p) override
Attach to another object.
bool open(yarp::os::Searchable &params) override
Open the DeviceDriver.
std::vector< SensorMeasurement > measurements
std::vector< SensorMetadata > SkinPatches
std::vector< SensorMetadata > ContactLoadCellArrays
std::vector< SensorMetadata > ThreeAxisAngularAccelerometers
std::vector< SensorMetadata > EncoderArrays
std::vector< SensorMetadata > PositionSensors
std::vector< SensorMetadata > ThreeAxisGyroscopes
std::vector< SensorMetadata > ThreeAxisLinearAccelerometers
std::vector< SensorMetadata > LinearVelocitySensors
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 ThreeAxisAngularAccelerometers
SensorMeasurements ContactLoadCellArrays
SensorMeasurements LinearVelocitySensors
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 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 container for a device driver.
Definition PolyDriver.h:23
bool detachAll() final
Detach the object (you must have first called attach).
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 base class for nested structures that can be searched.
Definition Searchable.h:31
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 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