ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

The following example can help you understand how to use the conversion from quaternions provided by an Odometry message to Euler angles Roll, Pitch and Yaw.

In the following example, you can see that the program subscribes to the odometry topic to get the orientation of a Turtlebot3 robot. Then it uses the tf.transformation functions to obtain the yaw value (the actual 'z' value or orientation of the odometry).

Then the program uses the roll, pitch and yaw to convert them back into a quaternion.

#!/usr/bin/env python
import rospy
from nav_msgs.msg import Odometry
from tf.transformations import euler_from_quaternion, quaternion_from_euler

roll = pitch = yaw = 0.0

def get_rotation (msg):
    global roll, pitch, yaw
    orientation_q = msg.pose.pose.orientation
    orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
    (roll, pitch, yaw) = euler_from_quaternion (orientation_list)
    print yaw

rospy.init_node('my_quaternion_to_euler')

sub = rospy.Subscriber ('/odom', Odometry, get_rotation)

r = rospy.Rate(1)
while not rospy.is_shutdown():    
    quat = quaternion_from_euler (roll, pitch,yaw)
    print quat
    r.sleep()

I have created a video that shows how I applied this code to a Turtlebot 3 robot to get its odometry and then convert it to Euler using that code.