YARP
Yet Another Robot Platform
PoseStampedRosPublisher.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 
7 #include <yarp/sig/Matrix.h>
8 #include <yarp/math/Math.h>
9 
10 #ifndef M_PI
11 #define M_PI (3.14159265358979323846)
12 #endif
13 
14 YARP_LOG_COMPONENT(GENERICSENSORROSPUBLISHER, "yarp.device.PoseStampedRosPublisher")
15 
16 bool PoseStampedRosPublisher::viewInterfaces()
17 {
18  // View all the interfaces
19  bool ok = true;
20  ok &= m_poly->view(m_iOrientationSensors);
21  ok &= m_poly->view(m_iPositionSensors);
22  m_iPositionSensors->getPositionSensorFrameName(m_sens_index, m_framename);
23  return ok;
24 }
25 
27 {
28  if (m_publisher.asPort().isOpen())
29  {
30  yarp::sig::Vector vecpos(3);
31  yarp::sig::Vector vecrpy(3);
33  m_iPositionSensors->getPositionSensorMeasure(m_sens_index, vecpos, m_timestamp);
35  pose_data.clear();
36  pose_data.header.frame_id = m_framename;
37  pose_data.header.seq = m_msg_counter++;
38  pose_data.header.stamp = m_timestamp;
39  pose_data.pose.position.x = vecpos[0];
40  pose_data.pose.position.y = vecpos[1];
41  pose_data.pose.position.z = vecpos[2];
42  vecrpy[0] = vecrpy[0] * M_PI / 180.0;
43  vecrpy[1] = vecrpy[1] * M_PI / 180.0;
44  vecrpy[2] = vecrpy[2] * M_PI / 180.0;
45  yarp::sig::Matrix matrix = yarp::math::rpy2dcm(vecrpy);
47  pose_data.pose.orientation.x = q.x();
48  pose_data.pose.orientation.y = q.y();
49  pose_data.pose.orientation.z = q.z();
50  pose_data.pose.orientation.w = q.w();
51  //imu_ros_data.orientation_covariance = 0;
52  m_publisher.write();
53  }
54  }
contains the definition of a Matrix type
const yarp::os::LogComponent & GENERICSENSORROSPUBLISHER()
#define M_PI
yarp::os::Publisher< yarp::rosmsg::geometry_msgs::PoseStamped > m_publisher
PoseStampedRosPublisher: This wrapper connects to a device and publishes a ROS topic of type geometry...
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 getPositionSensorMeasure(size_t sens_index, yarp::sig::Vector &xyz, double &timestamp) const =0
Get the last reading of the position sensor as x y z.
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
Definition: Quaternion.cpp:162
double x() const
Definition: Quaternion.cpp:81
double z() const
Definition: Quaternion.cpp:91
double w() const
Definition: Quaternion.cpp:76
double y() const
Definition: Quaternion.cpp:86
yarp::conf::float64_t y
Definition: Point.h:33
yarp::conf::float64_t x
Definition: Point.h:32
yarp::conf::float64_t z
Definition: Point.h:34
yarp::rosmsg::geometry_msgs::Pose pose
Definition: PoseStamped.h:34
yarp::rosmsg::std_msgs::Header header
Definition: PoseStamped.h:33
yarp::rosmsg::geometry_msgs::Point position
Definition: Pose.h:33
yarp::rosmsg::geometry_msgs::Quaternion orientation
Definition: Pose.h:34
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
A class for a Matrix.
Definition: Matrix.h:43
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:77
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
Definition: math.cpp:847