Public Member Functions | |
realsense2Tracking () | |
~realsense2Tracking () override=default | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. | |
bool | close () override |
Close the DeviceDriver. | |
size_t | getNrOfThreeAxisGyroscopes () const override |
Get the number of three axis gyroscopes exposed by this sensor. | |
yarp::dev::MAS_status | getThreeAxisGyroscopeStatus (size_t sens_index) const override |
Get the status of the specified sensor. | |
bool | getThreeAxisGyroscopeName (size_t sens_index, std::string &name) const override |
Get the name 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 | getThreeAxisGyroscopeMeasure (size_t sens_index, yarp::sig::Vector &out, double ×tamp) const override |
Get the last reading of the gyroscope. | |
size_t | getNrOfThreeAxisLinearAccelerometers () const override |
Get the number of three axis linear accelerometers exposed by this device. | |
yarp::dev::MAS_status | getThreeAxisLinearAccelerometerStatus (size_t sens_index) const override |
Get the status of the specified sensor. | |
bool | getThreeAxisLinearAccelerometerName (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 | getThreeAxisLinearAccelerometerMeasure (size_t sens_index, yarp::sig::Vector &out, double ×tamp) const override |
Get the last reading of the specified sensor. | |
size_t | getNrOfThreeAxisAngularAccelerometers () const override |
Get the number of three axis angular accelerometers exposed by this device. | |
yarp::dev::MAS_status | getThreeAxisAngularAccelerometerStatus (size_t sens_index) const override |
Get the status of the specified sensor. | |
bool | getThreeAxisAngularAccelerometerName (size_t sens_index, std::string &name) const override |
Get the name of the specified sensor. | |
bool | getThreeAxisAngularAccelerometerFrameName (size_t sens_index, std::string &frameName) const override |
Get the name of the frame of the specified sensor. | |
bool | getThreeAxisAngularAccelerometerMeasure (size_t sens_index, yarp::sig::Vector &out, double ×tamp) const override |
Get the last reading of the specified sensor. | |
size_t | getNrOfOrientationSensors () const override |
Get the number of orientation sensors exposed by this device. | |
yarp::dev::MAS_status | getOrientationSensorStatus (size_t sens_index) const override |
Get the status of the specified sensor. | |
bool | getOrientationSensorName (size_t sens_index, std::string &name) const override |
Get the name of the specified sensor. | |
bool | getOrientationSensorFrameName (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. | |
size_t | getNrOfPositionSensors () const override |
Get the number of position sensors exposed by this device. | |
yarp::dev::MAS_status | getPositionSensorStatus (size_t sens_index) const override |
Get the status of the specified sensor. | |
bool | getPositionSensorName (size_t sens_index, std::string &name) const override |
Get the name of the specified sensor. | |
bool | getPositionSensorFrameName (size_t sens_index, std::string &frameName) const override |
Get the name of the frame 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. | |
size_t | getNrOfLinearVelocitySensors () const override |
Get the number of linear velocity sensors exposed by this device. | |
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 | getLinearVelocitySensorFrameName (size_t sens_index, std::string &frameName) const override |
Get the name of the frame of the specified sensor. | |
bool | getLinearVelocitySensorMeasure (size_t sens_index, yarp::sig::Vector &xyz, double ×tamp) const override |
Get the last reading of the linear velocity sensor as x y z. | |
![]() | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
virtual | ~DeviceDriver () |
virtual std::string | id () const |
Return the id assigned to the PolyDriver. | |
virtual void | setId (const std::string &id) |
Set the id for this device. | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. | |
![]() | |
virtual | ~IThreeAxisGyroscopes () |
![]() | |
virtual | ~IThreeAxisLinearAccelerometers () |
![]() | |
virtual | ~IThreeAxisAngularAccelerometers () |
![]() | |
virtual | ~IOrientationSensors () |
![]() | |
virtual | ~IPositionSensors () |
![]() | |
virtual | ~ILinearVelocitySensors () |
Protected Types | |
enum | timestamp_enumtype { yarp_timestamp =0 , rs_timestamp } |
Protected Attributes | |
rs2_vector | m_last_gyro |
rs2_vector | m_last_accel |
rs2_pose | m_last_pose |
std::string | m_inertial_sensor_name_prefix |
const std::string | m_accel_sensor_tag = "accelerations_sensor" |
const std::string | m_gyro_sensor_tag = "gyro_sensor" |
const std::string | m_orientation_sensor_tag = "orientation_sensor" |
const std::string | m_position_sensor_tag = "position_sensor" |
const std::string | m_pose_sensor_tag = "pose_sensor" |
std::string | m_gyroFrameName |
std::string | m_accelFrameName |
std::string | m_orientationFrameName |
std::string | m_positionFrameName |
std::string | m_poseFrameName |
rs2::config | m_cfg |
std::mutex | m_mutex |
rs2::pipeline | m_pipeline |
rs2::pipeline_profile | m_profile |
std::string | m_lastError |
timestamp_enumtype | m_timestamp_type |
Definition at line 30 of file realsense2Tracking.h.
|
protected |
Enumerator | |
---|---|
yarp_timestamp | |
rs_timestamp |
Definition at line 137 of file realsense2Tracking.h.
realsense2Tracking::realsense2Tracking | ( | ) |
Definition at line 150 of file realsense2Tracking.cpp.
|
overridedefault |
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 224 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::ILinearVelocitySensors.
Definition at line 542 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the linear velocity sensor as x y z.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfLinearVelocitySensors()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in meters/second. |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::ILinearVelocitySensors.
Definition at line 550 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::ILinearVelocitySensors.
Definition at line 535 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::ILinearVelocitySensors.
Definition at line 529 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of linear velocity sensors exposed by this device.
Implements yarp::dev::ILinearVelocitySensors.
Definition at line 524 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of orientation sensors exposed by this device.
Implements yarp::dev::IOrientationSensors.
Definition at line 407 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of position sensors exposed by this device.
Implements yarp::dev::IPositionSensors.
Definition at line 468 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of three axis angular accelerometers exposed by this device.
Implements yarp::dev::IThreeAxisAngularAccelerometers.
Definition at line 346 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of three axis gyroscopes exposed by this sensor.
Implements yarp::dev::IThreeAxisGyroscopes.
Definition at line 232 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the number of three axis linear accelerometers exposed by this device.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 291 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 425 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the orientation sensor as roll pitch yaw.
If
with
,
and
where
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfOrientationSensors()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in degrees . |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::IOrientationSensors.
Definition at line 433 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 418 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 412 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IPositionSensors.
Definition at line 486 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the position sensor as x y z.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfPositionSensors()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in meters. |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::IPositionSensors.
Definition at line 494 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IPositionSensors.
Definition at line 479 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IPositionSensors.
Definition at line 473 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IThreeAxisAngularAccelerometers.
Definition at line 364 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the specified sensor.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisAngularAccelerometers()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in degrees^2/seconds. |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::IThreeAxisAngularAccelerometers.
Definition at line 372 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IThreeAxisAngularAccelerometers.
Definition at line 357 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IThreeAxisAngularAccelerometers.
Definition at line 351 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1). |
Implements yarp::dev::IThreeAxisGyroscopes.
Definition at line 250 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the gyroscope.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in degrees/seconds. |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::IThreeAxisGyroscopes.
Definition at line 257 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1). |
Implements yarp::dev::IThreeAxisGyroscopes.
Definition at line 243 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1). |
Implements yarp::dev::IThreeAxisGyroscopes.
Definition at line 237 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 309 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the last reading of the specified sensor.
[in] | sens_index | The index of the specified sensor (should be between 0 and getNrOfThreeAxisLinearAccelerometers()-1). |
[out] | out | The requested measure. The vector should be 3-dimensional. The measure is expressed in meters^2/seconds. |
[out] | timestamp | The timestamp of the requested measure, expressed in seconds. |
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 316 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 302 of file realsense2Tracking.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 296 of file realsense2Tracking.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device). |
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 189 of file realsense2Tracking.cpp.
|
protected |
Definition at line 121 of file realsense2Tracking.h.
|
protected |
Definition at line 127 of file realsense2Tracking.h.
|
protected |
Definition at line 132 of file realsense2Tracking.h.
|
protected |
Definition at line 122 of file realsense2Tracking.h.
|
protected |
Definition at line 126 of file realsense2Tracking.h.
|
protected |
Definition at line 120 of file realsense2Tracking.h.
|
mutableprotected |
Definition at line 116 of file realsense2Tracking.h.
|
mutableprotected |
Definition at line 115 of file realsense2Tracking.h.
|
mutableprotected |
Definition at line 117 of file realsense2Tracking.h.
|
mutableprotected |
Definition at line 136 of file realsense2Tracking.h.
|
mutableprotected |
Definition at line 133 of file realsense2Tracking.h.
|
protected |
Definition at line 123 of file realsense2Tracking.h.
|
protected |
Definition at line 128 of file realsense2Tracking.h.
|
protected |
Definition at line 134 of file realsense2Tracking.h.
|
protected |
Definition at line 125 of file realsense2Tracking.h.
|
protected |
Definition at line 130 of file realsense2Tracking.h.
|
protected |
Definition at line 124 of file realsense2Tracking.h.
|
protected |
Definition at line 129 of file realsense2Tracking.h.
|
protected |
Definition at line 135 of file realsense2Tracking.h.
|
protected |
Definition at line 138 of file realsense2Tracking.h.