YARP
Yet Another Robot Platform
IMURosPublisher.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
6#include "IMURosPublisher.h"
7
8#ifndef M_PI
9#define M_PI (3.14159265358979323846)
10#endif
11
12YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.IMURosPublisher")
13
14bool IMURosPublisher::viewInterfaces()
15{
16 // View all the interfaces
17 bool ok = true;
18 ok = m_poly->view(m_iThreeAxisGyroscopes);
19 if (!ok) {
20 yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisGyroscopes interface is not available";
21 return false;
22 }
23 ok = m_poly->view(m_iThreeAxisLinearAccelerometers);
24 if (!ok) {
25 yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisLinearAccelerometers interface is not available";
26 return false;
27 }
28 ok = m_poly->view(m_iThreeAxisMagnetometers);
29 if (!ok) {
30 yCError(GENERICSENSORROSPUBLISHER) << "IThreeAxisMagnetometers interface is not available";
31 return false;
32 }
33 ok = m_poly->view(m_iOrientationSensors);
34 if (!ok) {
35 yCError(GENERICSENSORROSPUBLISHER) << "IOrientationSensors interface is not available";
36 return false;
37 }
38
39 ok = m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
40 return ok;
41}
42
44{
46 {
47 yarp::sig::Vector vecgyr(3);
48 yarp::sig::Vector vecacc(3);
49 yarp::sig::Vector vecrpy(3);
51 m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp);
52 m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp);
54 imu_ros_data.clear();
55 imu_ros_data.header.frame_id = m_framename;
56 imu_ros_data.header.seq = m_msg_counter++;
57 imu_ros_data.header.stamp = m_timestamp;
58 imu_ros_data.angular_velocity.x = vecgyr[0] * M_PI / 180.0;
59 imu_ros_data.angular_velocity.y = vecgyr[1] * M_PI / 180.0;
60 imu_ros_data.angular_velocity.z = vecgyr[2] * M_PI / 180.0;
61 imu_ros_data.linear_acceleration.x = vecacc[0];
62 imu_ros_data.linear_acceleration.y = vecacc[1];
63 imu_ros_data.linear_acceleration.z = vecacc[2];
64 imu_ros_data.orientation.x = vecrpy[0] * M_PI / 180.0;
65 imu_ros_data.orientation.y = vecrpy[1] * M_PI / 180.0;
66 imu_ros_data.orientation.z = vecrpy[2] * M_PI / 180.0;
67 //imu_ros_data.orientation_covariance = 0;
69 }
70 }
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
#define M_PI
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu > m_publisher
IMURosPublisher: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu...
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:88
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 getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the gyroscope.
virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
bool isOpen() const
Check if the port has been opened.
Definition: Port.cpp:677
Port & asPort() override
Get the concrete Port being used for communication.
Definition: Publisher.h:169
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:148
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:123
yarp::conf::float64_t y
Definition: Vector3.h:38
yarp::conf::float64_t z
Definition: Vector3.h:39
yarp::conf::float64_t x
Definition: Vector3.h:37
yarp::rosmsg::std_msgs::Header header
Definition: Imu.h:55
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
Definition: Imu.h:58
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
Definition: Imu.h:60
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Imu.h:56
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
#define yCError(component,...)
Definition: LogComponent.h:213
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76