YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches

IMU_nwc_ros2: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu. More...

#include </home/runner/work/yarp-documentation/yarp-documentation/yarp/opt-modules/yarp-devices-ros2/src/devices/multipleAnalogSensors_nwc_ros2/Imu_nwc_ros2.h>

+ Inheritance diagram for Imu_nwc_ros2:

Public Member Functions

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 &timestamp) const override
 Get the last reading of the specified sensor.
 
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 &timestamp) const override
 Get the last reading of the gyroscope.
 
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 &timestamp) const override
 Get the last reading of the orientation sensor as roll pitch yaw.
 
- Public Member Functions inherited from GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >
 GenericSensor_nwc_ros2 ()
 
virtual ~GenericSensor_nwc_ros2 ()
 
bool open (yarp::os::Searchable &params) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (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 DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others.
 
- Public Member Functions inherited from yarp::dev::IThreeAxisLinearAccelerometers
virtual ~IThreeAxisLinearAccelerometers ()
 
- Public Member Functions inherited from yarp::dev::IThreeAxisGyroscopes
virtual ~IThreeAxisGyroscopes ()
 
- Public Member Functions inherited from yarp::dev::IOrientationSensors
virtual ~IOrientationSensors ()
 

Protected Member Functions

void subscription_callback (const std::shared_ptr< sensor_msgs::msg::Imu > msg) override
 
- Protected Member Functions inherited from GenericSensor_nwc_ros2_ParamsParser
 GenericSensor_nwc_ros2_ParamsParser ()
 
 ~GenericSensor_nwc_ros2_ParamsParser () override=default
 
bool parseParams (const yarp::os::Searchable &config) override
 Parse the DeviceDriver parameters.
 
std::string getDeviceClassName () const override
 Get the name of the DeviceDriver class.
 
std::string getDeviceName () const override
 Get the name of the device (i.e.
 
std::string getDocumentationOfDeviceParams () const override
 Get the documentation of the DeviceDriver's parameters.
 
std::vector< std::string > getListOfParams () const override
 Return a list of all params used by the device.
 
- Protected Member Functions inherited from yarp::dev::IDeviceDriverParams
virtual ~IDeviceDriverParams ()
 

Additional Inherited Members

- Protected Attributes inherited from GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >
double m_periodInS
 
double m_timestamp
 
std::string m_framename
 
Ros2Spinnerm_spinner
 
const size_t m_sens_index
 
std::mutex m_dataMutex
 
yarp::dev::MAS_status m_internalStatus
 
rclcpp::Node::SharedPtr m_node
 
rclcpp::Subscription< sensor_msgs::msg::Imu >::SharedPtr m_subscription
 
- Protected Attributes inherited from GenericSensor_nwc_ros2_ParamsParser
const std::string m_device_classname = {"GenericSensor_nwc_ros2"}
 
const std::string m_device_name = {"genericSensor_nwc_ros2"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
const std::string m_node_name_defaultValue = {""}
 
const std::string m_topic_name_defaultValue = {""}
 
const std::string m_sensor_name_defaultValue = {""}
 
std::string m_node_name = {}
 
std::string m_topic_name = {}
 
std::string m_sensor_name = {}
 

Detailed Description

IMU_nwc_ros2: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu.

YARP device name
Imu_nwc_ros2

The parameters accepted by this device are shown in class: GenericSensor_nwc_ros2_ParamsParser

Definition at line 26 of file Imu_nwc_ros2.h.

Member Function Documentation

◆ getNrOfOrientationSensors()

size_t Imu_nwc_ros2::getNrOfOrientationSensors ( ) const
overridevirtual

Get the number of orientation sensors exposed by this device.

Implements yarp::dev::IOrientationSensors.

Definition at line 196 of file Imu_nwc_ros2.cpp.

◆ getNrOfThreeAxisGyroscopes()

size_t Imu_nwc_ros2::getNrOfThreeAxisGyroscopes ( ) const
overridevirtual

Get the number of three axis gyroscopes exposed by this sensor.

Implements yarp::dev::IThreeAxisGyroscopes.

Definition at line 130 of file Imu_nwc_ros2.cpp.

◆ getNrOfThreeAxisLinearAccelerometers()

size_t Imu_nwc_ros2::getNrOfThreeAxisLinearAccelerometers ( ) const
overridevirtual

Get the number of three axis linear accelerometers exposed by this device.

Implements yarp::dev::IThreeAxisLinearAccelerometers.

Definition at line 73 of file Imu_nwc_ros2.cpp.

◆ getOrientationSensorFrameName()

bool Imu_nwc_ros2::getOrientationSensorFrameName ( size_t  sens_index,
std::string &  frameName 
) const
overridevirtual

Get the name of the frame of the specified sensor.

Note
This is an implementation specific method, that may return the name of the sensor frame in a scenegraph
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IOrientationSensors.

Definition at line 181 of file Imu_nwc_ros2.cpp.

◆ getOrientationSensorMeasureAsRollPitchYaw()

bool Imu_nwc_ros2::getOrientationSensorMeasureAsRollPitchYaw ( size_t  sens_index,
yarp::sig::Vector rpy,
double &  timestamp 
) const
overridevirtual

Get the last reading of the orientation sensor as roll pitch yaw.

If $ f $ is the lab or surface fixed frame, and $ s $ is the sensor-fixed frame, this methods returns the angles $ r \in [-180, 180] , p \in [-90, 90], y \in [-180, 180]$ such that

\[
{}^f R_s = RotZ\left(\frac{\pi}{180}y\right)*RotY\left(\frac{\pi}{180}p\right)*RotX\left(\frac{\pi}{180}r\right)
\]

with

\[
RotZ(\theta)
 =
 \begin{bmatrix}
     \cos(\theta)      & -\sin(\theta) & 0              \\
     \sin(\theta)      & \cos(\theta)  & 0              \\
     0                 & 0             & 1              \\
 \end{bmatrix}
\]

,

\[
RotY(\theta)
=
 \begin{bmatrix}
     \cos(\theta)      & 0             & \sin(\theta)   \\
     0                 & 1             & 0              \\
     -\sin(\theta)     & 0             & \cos(\theta)   \\
 \end{bmatrix}
\]

and

\[
RotX(\theta)
=
 \begin{bmatrix}
     1 & 0             & 0              \\
     0 & \cos(\theta)  & - \sin(\theta) \\
     0 & \sin(\theta)  & \cos(\theta)   \\
 \end{bmatrix}
\]

where $ {}^f R_s \in \mathbb{R}^{3 \times 3} $ is the rotation that left-multiplied by a 3d column vector expressed in $ s $ it returns it expressed in $ f $ .

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfOrientationSensors()-1).
[out]outThe requested measure. The vector should be 3-dimensional. The measure is expressed in degrees .
[out]timestampThe timestamp of the requested measure, expressed in seconds.
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IOrientationSensors.

Definition at line 142 of file Imu_nwc_ros2.cpp.

◆ getOrientationSensorName()

bool Imu_nwc_ros2::getOrientationSensorName ( size_t  sens_index,
std::string &  name 
) const
overridevirtual

Get the name of the specified sensor.

Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IOrientationSensors.

Definition at line 173 of file Imu_nwc_ros2.cpp.

◆ getOrientationSensorStatus()

yarp::dev::MAS_status Imu_nwc_ros2::getOrientationSensorStatus ( size_t  sens_index) const
overridevirtual

Get the status of the specified sensor.

Implements yarp::dev::IOrientationSensors.

Definition at line 201 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisGyroscopeFrameName()

bool Imu_nwc_ros2::getThreeAxisGyroscopeFrameName ( size_t  sens_index,
std::string &  frameName 
) const
overridevirtual

Get the name of the frame of the specified sensor.

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1).
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisGyroscopes.

Definition at line 115 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisGyroscopeMeasure()

bool Imu_nwc_ros2::getThreeAxisGyroscopeMeasure ( size_t  sens_index,
yarp::sig::Vector out,
double &  timestamp 
) const
overridevirtual

Get the last reading of the gyroscope.

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1).
[out]outThe requested measure. The vector should be 3-dimensional. The measure is expressed in degrees/seconds.
[out]timestampThe timestamp of the requested measure, expressed in seconds.
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisGyroscopes.

Definition at line 85 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisGyroscopeName()

bool Imu_nwc_ros2::getThreeAxisGyroscopeName ( size_t  sens_index,
std::string &  name 
) const
overridevirtual

Get the name of the specified sensor.

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1).
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisGyroscopes.

Definition at line 107 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisGyroscopeStatus()

yarp::dev::MAS_status Imu_nwc_ros2::getThreeAxisGyroscopeStatus ( size_t  sens_index) const
overridevirtual

Get the status of the specified sensor.

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfThreeAxisGyroscopes()-1).

Implements yarp::dev::IThreeAxisGyroscopes.

Definition at line 135 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisLinearAccelerometerFrameName()

bool Imu_nwc_ros2::getThreeAxisLinearAccelerometerFrameName ( size_t  sens_index,
std::string &  frameName 
) const
overridevirtual

Get the name of the frame of the specified sensor.

Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisLinearAccelerometers.

Definition at line 58 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisLinearAccelerometerMeasure()

bool Imu_nwc_ros2::getThreeAxisLinearAccelerometerMeasure ( size_t  sens_index,
yarp::sig::Vector out,
double &  timestamp 
) const
overridevirtual

Get the last reading of the specified sensor.

Parameters
[in]sens_indexThe index of the specified sensor (should be between 0 and getNrOfThreeAxisLinearAccelerometers()-1).
[out]outThe requested measure. The vector should be 3-dimensional. The measure is expressed in meters^2/seconds.
[out]timestampThe timestamp of the requested measure, expressed in seconds.
Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisLinearAccelerometers.

Definition at line 28 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisLinearAccelerometerName()

bool Imu_nwc_ros2::getThreeAxisLinearAccelerometerName ( size_t  sens_index,
std::string &  name 
) const
overridevirtual

Get the name of the specified sensor.

Returns
false if an error occurred, true otherwise.

Implements yarp::dev::IThreeAxisLinearAccelerometers.

Definition at line 50 of file Imu_nwc_ros2.cpp.

◆ getThreeAxisLinearAccelerometerStatus()

yarp::dev::MAS_status Imu_nwc_ros2::getThreeAxisLinearAccelerometerStatus ( size_t  sens_index) const
overridevirtual

Get the status of the specified sensor.

Implements yarp::dev::IThreeAxisLinearAccelerometers.

Definition at line 78 of file Imu_nwc_ros2.cpp.

◆ subscription_callback()

void Imu_nwc_ros2::subscription_callback ( const std::shared_ptr< sensor_msgs::msg::Imu >  msg)
overrideprotectedvirtual

Implements GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >.

Definition at line 20 of file Imu_nwc_ros2.cpp.


The documentation for this class was generated from the following files: