YARP
Yet Another Robot Platform
IMURosPublisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #include "IMURosPublisher.h"
10 
11 #ifndef M_PI
12 #define M_PI (3.14159265358979323846)
13 #endif
14 
15 YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.IMURosPublisher")
16 
17 bool IMURosPublisher::viewInterfaces()
18 {
19  // View all the interfaces
20  bool ok = true;
21  ok &= m_poly->view(m_iThreeAxisGyroscopes);
22  ok &= m_poly->view(m_iThreeAxisLinearAccelerometers);
23  ok &= m_poly->view(m_iThreeAxisMagnetometers);
24  ok &= m_poly->view(m_iOrientationSensors);
25  if (m_iThreeAxisGyroscopes) m_iThreeAxisGyroscopes->getThreeAxisGyroscopeFrameName(m_sens_index, m_framename);
26  return ok;
27 }
28 
30 {
31  if (m_publisher.asPort().isOpen())
32  {
33  yarp::sig::Vector vecgyr(3);
34  yarp::sig::Vector vecacc(3);
35  yarp::sig::Vector vecrpy(3);
37  m_iThreeAxisGyroscopes->getThreeAxisGyroscopeMeasure(m_sens_index, vecgyr, m_timestamp);
38  m_iThreeAxisLinearAccelerometers->getThreeAxisLinearAccelerometerMeasure(m_sens_index, vecacc, m_timestamp);
40  imu_ros_data.clear();
41  imu_ros_data.header.frame_id = m_framename;
42  imu_ros_data.header.seq = m_msg_counter++;
43  imu_ros_data.header.stamp = m_timestamp;
44  imu_ros_data.angular_velocity.x = vecgyr[0] * M_PI / 180.0;
45  imu_ros_data.angular_velocity.y = vecgyr[1] * M_PI / 180.0;
46  imu_ros_data.angular_velocity.z = vecgyr[2] * M_PI / 180.0;
47  imu_ros_data.linear_acceleration.x = vecacc[0];
48  imu_ros_data.linear_acceleration.y = vecacc[1];
49  imu_ros_data.linear_acceleration.z = vecacc[2];
50  imu_ros_data.orientation.x = vecrpy[0] * M_PI / 180.0;
51  imu_ros_data.orientation.y = vecrpy[1] * M_PI / 180.0;
52  imu_ros_data.orientation.z = vecrpy[2] * M_PI / 180.0;
53  //imu_ros_data.orientation_covariance = 0;
55  }
56  }
yarp::rosmsg::geometry_msgs::Quaternion::y
yarp::conf::float64_t y
Definition: Quaternion.h:38
yarp::rosmsg::geometry_msgs::Vector3::z
yarp::conf::float64_t z
Definition: Vector3.h:42
GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >::m_framename
std::string m_framename
Definition: GenericSensorRosPublisher.h:60
GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >::m_publisher
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::Imu > m_publisher
Definition: GenericSensorRosPublisher.h:56
yarp::dev::IThreeAxisGyroscopes::getThreeAxisGyroscopeMeasure
virtual bool getThreeAxisGyroscopeMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the gyroscope.
IMURosPublisher.h
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::rosmsg::geometry_msgs::Vector3::y
yarp::conf::float64_t y
Definition: Vector3.h:41
yarp::rosmsg::std_msgs::Header::frame_id
std::string frame_id
Definition: Header.h:49
yarp::rosmsg::sensor_msgs::Imu::orientation
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Imu.h:59
yarp::rosmsg::geometry_msgs::Vector3::x
yarp::conf::float64_t x
Definition: Vector3.h:40
yarp::rosmsg::geometry_msgs::Quaternion::x
yarp::conf::float64_t x
Definition: Quaternion.h:37
yarp::dev::DeviceDriver::view
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:77
yarp::rosmsg::sensor_msgs::Imu::angular_velocity
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
Definition: Imu.h:61
yarp::rosmsg::sensor_msgs::Imu::clear
void clear()
Definition: Imu.h:80
yarp::sig::VectorOf< double >
yarp::rosmsg::std_msgs::Header::seq
std::uint32_t seq
Definition: Header.h:47
GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >::m_sens_index
const size_t m_sens_index
Definition: GenericSensorRosPublisher.h:61
yarp::os::Publisher::write
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:152
GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >::m_timestamp
double m_timestamp
Definition: GenericSensorRosPublisher.h:59
M_PI
#define M_PI
Definition: IMURosPublisher.cpp:12
yarp::rosmsg::sensor_msgs::Imu
Definition: Imu.h:56
yarp::rosmsg::sensor_msgs::Imu::linear_acceleration
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
Definition: Imu.h:63
yarp::os::Publisher::asPort
Port & asPort() override
Get the concrete Port being used for communication.
Definition: Publisher.h:172
yarp::dev::IOrientationSensors::getOrientationSensorMeasureAsRollPitchYaw
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.
yarp::rosmsg::geometry_msgs::Quaternion::z
yarp::conf::float64_t z
Definition: Quaternion.h:39
IMURosPublisher
IMURosPublisher: This wrapper connects to a device and publishes a ROS topic of type sensor_msgs::Imu...
Definition: IMURosPublisher.h:35
IMURosPublisher::run
void run() override
Loop function.
Definition: IMURosPublisher.cpp:29
yarp::rosmsg::sensor_msgs::Imu::header
yarp::rosmsg::std_msgs::Header header
Definition: Imu.h:58
yarp::dev::IThreeAxisLinearAccelerometers::getThreeAxisLinearAccelerometerMeasure
virtual bool getThreeAxisLinearAccelerometerMeasure(size_t sens_index, yarp::sig::Vector &out, double &timestamp) const =0
Get the last reading of the specified sensor.
yarp::rosmsg::std_msgs::Header::stamp
yarp::rosmsg::TickTime stamp
Definition: Header.h:48
GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >::m_msg_counter
size_t m_msg_counter
Definition: GenericSensorRosPublisher.h:58
yarp::os::Publisher::prepare
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:127
GENERICSENSORROSPUBLISHER
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
Definition: IMURosPublisher.cpp:15
yarp::os::Port::isOpen
bool isOpen() const
Check if the port has been opened.
Definition: Port.cpp:671