YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Imu_nwc_ros2.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_DEV_IMU_NWC_ROS2_H
7#define YARP_DEV_IMU_NWC_ROS2_H
8
10#include <sensor_msgs/msg/imu.hpp>
11#include <tf2/LinearMath/Quaternion.h>
12#include <tf2/LinearMath/Matrix3x3.h>
13
26class Imu_nwc_ros2 : public GenericSensor_nwc_ros2<sensor_msgs::msg::Imu>,
30{
31private:
32 sensor_msgs::msg::Imu m_currentData;
33
34public:
35 using GenericSensor_nwc_ros2<sensor_msgs::msg::Imu>::GenericSensor_nwc_ros2;
36
37 using GenericSensor_nwc_ros2<sensor_msgs::msg::Imu>::open;
38 using GenericSensor_nwc_ros2<sensor_msgs::msg::Imu>::close;
39
40protected:
41 void subscription_callback(const std::shared_ptr<sensor_msgs::msg::Imu> msg) override;
42public:
43 /* IThreeAxisLinearAccelerometers methods */
44 size_t getNrOfThreeAxisLinearAccelerometers() const override;
45 yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override;
46 bool getThreeAxisLinearAccelerometerName(size_t sens_index, std::string &name) const override;
47 bool getThreeAxisLinearAccelerometerFrameName(size_t sens_index, std::string &frameName) const override;
48 bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
49
50 /* IThreeAxisGyroscopes methods */
51 size_t getNrOfThreeAxisGyroscopes() const override;
52 yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override;
53 bool getThreeAxisGyroscopeName(size_t sens_index, std::string &name) const override;
54 bool getThreeAxisGyroscopeFrameName(size_t sens_index, std::string &frameName) const override;
55 bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector& out, double& timestamp) const override;
56
57 /* IOrientationSensors methods */
58 size_t getNrOfOrientationSensors() const override;
59 yarp::dev::MAS_status getOrientationSensorStatus(size_t sens_index) const override;
60 bool getOrientationSensorName(size_t sens_index, std::string &name) const override;
61 bool getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override;
62 bool getOrientationSensorMeasureAsRollPitchYaw(size_t sens_index, yarp::sig::Vector& rpy, double& timestamp) const override;
63};
64
65#endif // YARP_DEV_IMU_NWC_ROS2_H
This abstract template needs to be specialized in a ROS2 subscription, for a specific ROS2 message/se...
bool open(yarp::os::Searchable &params) override
IMU_nwc_ros2: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu.
yarp::dev::MAS_status getOrientationSensorStatus(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.
void subscription_callback(const std::shared_ptr< sensor_msgs::msg::Imu > msg) override
yarp::dev::MAS_status getThreeAxisGyroscopeStatus(size_t sens_index) const override
Get the status 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.
bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) 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.
bool getOrientationSensorName(size_t sens_index, std::string &name) const override
Get the name of the specified sensor.
bool getThreeAxisLinearAccelerometerName(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.
size_t getNrOfThreeAxisGyroscopes() const override
Get the number of three axis gyroscopes exposed by this sensor.
yarp::dev::MAS_status getThreeAxisLinearAccelerometerStatus(size_t sens_index) const override
Get the status 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 getOrientationSensorFrameName(size_t sens_index, std::string &frameName) const override
Get the name of the frame of the specified sensor.
size_t getNrOfThreeAxisLinearAccelerometers() const override
Get the number of three axis linear accelerometers exposed by this device.
bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const override
Get the last reading of the gyroscope.
Device interface to one or multiple orientation sensors, such as IMUs with on board estimation algori...
Device interface to one or multiple three axis gyroscopes.
Device interface to one or multiple three axis linear accelerometers.
MAS_status
Status of a given analog sensor exposed by a multiple analog sensors interface.