IMU_nwc_ros2
: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu.
More...
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 ×tamp) 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 ×tamp) 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 ×tamp) 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 ¶ms) 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 | |
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. | |
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 |
Ros2Spinner * | m_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 = {} |
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.
|
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.
|
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.
|
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.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 181 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the last reading of the orientation sensor as roll pitch yaw.
If is the lab or surface fixed frame, and is the sensor-fixed frame, this methods returns the angles such that
with
,
and
where is the rotation that left-multiplied by a 3d column vector expressed in it returns it expressed in .
[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 142 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 173 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IOrientationSensors.
Definition at line 201 of file Imu_nwc_ros2.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 115 of file Imu_nwc_ros2.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 85 of file Imu_nwc_ros2.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 107 of file Imu_nwc_ros2.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 135 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the name of the frame of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 58 of file Imu_nwc_ros2.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 28 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the name of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 50 of file Imu_nwc_ros2.cpp.
|
overridevirtual |
Get the status of the specified sensor.
Implements yarp::dev::IThreeAxisLinearAccelerometers.
Definition at line 78 of file Imu_nwc_ros2.cpp.
|
overrideprotectedvirtual |
Implements GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >.
Definition at line 20 of file Imu_nwc_ros2.cpp.