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 
12 YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.IMURosPublisher")
13 
14 bool IMURosPublisher::viewInterfaces()
15 {
16  // View all the interfaces
17  bool ok = true;
18  ok &= m_poly->view(m_iThreeAxisGyroscopes);
19  ok &= m_poly->view(m_iThreeAxisLinearAccelerometers);
20  ok &= m_poly->view(m_iThreeAxisMagnetometers);
21  ok &= m_poly->view(m_iOrientationSensors);
22  if (m_iThreeAxisGyroscopes) {
23  m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
24  }
25  return ok;
26 }
27 
29 {
30  if (m_publisher.asPort().isOpen())
31  {
32  yarp::sig::Vector vecgyr(3);
33  yarp::sig::Vector vecacc(3);
34  yarp::sig::Vector vecrpy(3);
36  m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp);
37  m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp);
39  imu_ros_data.clear();
40  imu_ros_data.header.frame_id = m_framename;
41  imu_ros_data.header.seq = m_msg_counter++;
42  imu_ros_data.header.stamp = m_timestamp;
43  imu_ros_data.angular_velocity.x = vecgyr[0] * M_PI / 180.0;
44  imu_ros_data.angular_velocity.y = vecgyr[1] * M_PI / 180.0;
45  imu_ros_data.angular_velocity.z = vecgyr[2] * M_PI / 180.0;
46  imu_ros_data.linear_acceleration.x = vecacc[0];
47  imu_ros_data.linear_acceleration.y = vecacc[1];
48  imu_ros_data.linear_acceleration.z = vecacc[2];
49  imu_ros_data.orientation.x = vecrpy[0] * M_PI / 180.0;
50  imu_ros_data.orientation.y = vecrpy[1] * M_PI / 180.0;
51  imu_ros_data.orientation.z = vecrpy[2] * M_PI / 180.0;
52  //imu_ros_data.orientation_covariance = 0;
54  }
55  }
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:74
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:668
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:124
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
Port & asPort() override
Get the concrete Port being used for communication.
Definition: Publisher.h:170
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 YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77