Quaternion to RPY angles with melodic

asked 2020-03-15 10:24:44 -0500

Marcus Barnet gravatar image

updated 2020-03-15 14:35:51 -0500

Following my previous question, I'm trying to write a c++ odom node for my robot and I would like to retrieve roll, pitch and yaw from a quaternion because I need to calculate the yaw angle to compute the Twist message.

    #include <ros/ros.h>
    #include <tf/transform_broadcaster.h>
    #include <nav_msgs/Odometry.h>
    #include "std_msgs/String.h"
    #include "marvelmind_nav/hedge_pos.h"
    #include "marvelmind_nav/hedge_pos_a.h"
    #include "marvelmind_nav/hedge_pos_ang.h"
    #include "marvelmind_nav/hedge_imu_fusion.h"
    #include <tf/transform_datatypes.h>
    #include <tf/LinearMath/Matrix3x3.h>


double x = 0.0;
double y = 0.0;
double z = 0.0;
double vx = 0.0;
double vy = 0.0;
double vth = 0.0;
float orientation_qx= 0.0;
float orientation_qy= 0.0;
float orientation_qz= 0.0;
float orientation_qw= 1.0;

     int main(int argc, char** argv){
      ros::init(argc, argv, "odometry_publisher");

      ros::NodeHandle n;
      ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
      tf::TransformBroadcaster odom_broadcaster;

      ros::Subscriber subHedgeWithAngle = n.subscribe(HEDGE_POSITION_WITH_ANGLE_TOPIC_NAME, 1000, hedgePosAngCallback);
      ros::Subscriber subIMUFusion = n.subscribe(HEDGE_IMU_FUSION_TOPIC_NAME, 1000, IMUFusionCallback);

      ros::Time current_time, last_time;
      current_time = ros::Time::now();
      last_time = ros::Time::now();

      ros::Rate r(1.0);
      while(n.ok()){

        ros::spinOnce();               // check for incoming messages
        current_time = ros::Time::now();

        //compute odometry in a typical way given the velocities of the robot
        double dt = (current_time - last_time).toSec();


        geometry_msgs::Quaternion odom_quat;
        odom_quat.x = orientation_qx;
        odom_quat.y = orientation_qy;
        odom_quat.z = orientation_qz;
        odom_quat.w = orientation_qw;
        double roll, pitch, yaw;
        tf::Matrix3x3(odom_quat).getRPY(roll, pitch, yaw);
 geometry_msgs::TransformStamped odom_trans;
    odom_trans.header.stamp = current_time;
    odom_trans.header.frame_id = "odom";
    odom_trans.child_frame_id = "base_link";

    odom_trans.transform.translation.x = x;
    odom_trans.transform.translation.y = y;
    odom_trans.transform.translation.z = z;
    odom_trans.transform.rotation = odom_quat;

    //send the transform
    odom_broadcaster.sendTransform(odom_trans);

    //next, we'll publish the odometry message over ROS
    nav_msgs::Odometry odom;
    odom.header.stamp = current_time;
    odom.header.frame_id = "odom";

    //set the position
    odom.pose.pose.position.x = x;
    odom.pose.pose.position.y = y;
    odom.pose.pose.position.z = 0.0;
    odom.pose.pose.orientation = odom_quat;

    //set the velocity
    odom.child_frame_id = "base_link";
    odom.twist.twist.linear.x = vx;
    odom.twist.twist.linear.y = vy;
    odom.twist.twist.angular.z = vth;

...
    }

I get this error from the compiler:

   In function ‘int main(int, char**)’:
    /home/isola/catkin_ws/src/beginner_tutorials/src/odom.cpp:88:29: error: no matching function for call to ‘tf::Matrix3x3::Matrix3x3(geometry_msgs::Quaternion*)’
         tf::Matrix3x3(&odom_quat).getRPY(roll, pitch, yaw);
                                 ^
    In file included from /opt/ros/melodic/include/tf/LinearMath/Transform.h:21:0,
                     from /opt/ros/melodic/include/tf/transform_datatypes.h:41,
                     from /opt/ros/melodic/include/tf/time_cache.h:38,
                     from /opt/ros/melodic/include/tf/tf.h:44,
                     from /opt/ros/melodic/include/tf/transform_broadcaster.h:36,
                     from /home/isola/catkin_ws/src/beginner_tutorials/src/odom.cpp:2:
    /opt/ros/melodic/include/tf/LinearMath/Matrix3x3.h:61:22: note: candidate: tf::Matrix3x3::Matrix3x3(const tf::Matrix3x3&)
      TFSIMD_FORCE_INLINE Matrix3x3 (const Matrix3x3& other)
                          ^~~~~~~~~
    /opt/ros/melodic/include/tf/LinearMath/Matrix3x3.h:61:22: note:   no known conversion for argument 1 from ‘geometry_msgs::Quaternion* {aka geometry_msgs::Quaternion_<std::allocator<void> >*}’ to ‘const tf ...
(more)
edit retag flag offensive close merge delete

Comments

1

because I need to calculate the yaw angle to compute the Twist message.

If this is connected to #q346720, please mention that.

Also: I believe this is an xy-problem. From #q346720, it would appear you already have a full pose (translation + orientation in the form of a quaternion). Wouldn't that be fairly straightforward to put into a nav_msgs/Odometry and TF frame?

Please provide sufficient information on what it is you're actually trying to do (ie: publishing the Marvel Mind data in more standard ROS messages).

gvdhoorn gravatar image gvdhoorn  ( 2020-03-15 10:47:31 -0500 )edit

I'm already able to publish a nav_msgs/Odometry odom node with x,y and orientation plus the TF, but I would like to add also velocities just to have a more useful node for future needs. I would like to calculate the yaw angle by using the quaternion. The problem is that I'm getting that error from the compiler and I can't understand the reason.

Marcus Barnet gravatar image Marcus Barnet  ( 2020-03-15 10:52:12 -0500 )edit

I solved the problem by directly using a math formula and I reported it in my main topic.

Marcus Barnet gravatar image Marcus Barnet  ( 2020-03-15 14:35:17 -0500 )edit