[Python]How to know pose of turtlebot
Hello ! I want to know the pose of turtlebot (x,y,z, z rotation) respect to the point from which it started. What is the best way to do that in python?
ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
Hello ! I want to know the pose of turtlebot (x,y,z, z rotation) respect to the point from which it started. What is the best way to do that in python?
Hello!
As you suggest in your last message, the best practice for doing that is to use the odom topic. For that, you can create a simple subscriber in Python that gets the data you need, which is, position and orientation respect to an starting point. The code for a simple subscriber could be like this:
#! /usr/bin/env python
import rospy
from nav_msgs.msg import Odometry
def callback(msg):
print msg.pose.pose
rospy.init_node('check_odometry')
odom_sub = rospy.Subscriber('/odom', Odometry, callback)
rospy.spin()
This code basically subscribes to the odom topic, and prints the pose component of the message, which contains the position and orientation values. I've also created a video with a quick demonstration, which may be helpful: https://www.youtube.com/watch?v=kPsrO...
(0,0,0,1) is the identity quaternion: I'd suggest reading more about quaternions. https://answers.ros.org/question/9981...
Asked: 2017-09-27 09:54:01 -0600
Seen: 6,833 times
Last updated: Oct 05 '17
error launching turtlebot dashboard: python/wx [closed]
Do I need to know any specific computer language or framework to use ROS?
Is anybody in ROS community using PySide?
Any good examples of using dynamic_reconfigure for a python node?
Retrieving pose of an object from an image or bag file
is there a python equivalent of fromROSMsg/toROSMsg (pcl stack)
How to contributing python versions of tutorials? e.g. Tutorials for arm_navigation
How to recieve an array over Publisher and Subscriber? (Python)
What do you mean by
? Are you talking about in some reference frame like
world
ormap
? Or, are you comparing two poses (initial and final)?My robot starts from a point in the room. I would fix a reference frame in this point. Robot reaches a new point. I want to know x,y coordinates of this point in the initial fixed reference frame and it's orientation. Maybe I can use odom topic