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

How to subscribe to odom properly in python

asked 2011-07-22 11:36:21 -0500

Poofjunior gravatar image

updated 2011-07-25 07:42:36 -0500

mmwise gravatar image

Hello, all,

I recently wrote a simple subscriber that subscribes to the topic /odom coming from the irobot_create_2_1 driver for an iCreate. However, when I simply print the odometry data and rotate the wheels myself, the data doesn't change. At the same time, though, if I re-run the Python Script, the data will have changed to the amount I previously rotated it.

Have I made a simple mistake? Or does /odom not publish the current transformation and rotation information.

(I noticed also that the time stamp doesn't change)

Thanks so much in advance for any advice!

Here's my source code:

#!/usr/bin/env python
import roslib; roslib.load_manifest('Phoebe')
import rospy
import irobot_create_2_1

from nav_msgs.msg import Odometry
from geometry_msgs.msg import *
from tf.msg import *



counter = 0

def Position(odom_data):

    global counter
    rospy.sleep(1)
    curr_time = odom_data.header.stamp
    pose = odom_data.pose.pose #  the x,y,z pose and quaternion orientation
    counter= counter+1
    print counter, curr_time
    print
    print pose


def transformation(tf_data):
    global counter
    rospy.sleep(1)
    transform = tf_data.transform
    print transform


def begin():
    while not rospy.is_shutdown():
        rospy.init_node('oodometry', anonymous=True) #make node 
        rospy.Subscriber('odom',Odometry,Position)


if __name__ == "__main__":
    begin()
    rospy.spin() # not really necessary because we have while not rospy.is_shutdown()
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
10

answered 2011-07-22 21:02:21 -0500

fergs gravatar image

updated 2011-07-22 21:02:45 -0500

You don't want to be calling init_node and creating subscribers inside a loop. I've removed much of the non-used code below to make the code clearer:

#!/usr/bin/env python
import roslib; roslib.load_manifest('Phoebe')
import rospy

from nav_msgs.msg import Odometry

def odometryCb(msg):
    print msg.pose.pose

if __name__ == "__main__":
    rospy.init_node('oodometry', anonymous=True) #make node 
    rospy.Subscriber('odom',Odometry,odometryCb)
    rospy.spin()
edit flag offensive delete link more

Comments

1

Can you please explain what happens exactly when we run this code. This will help me in understanding the code better

Maulik_Bhatt gravatar image Maulik_Bhatt  ( 2018-08-26 02:01:30 -0500 )edit
1

In the main -- the first line initializes the node (which basically means connecting to the ROS master). The second line subscribes to the "odom" topic. The third line will sit there and process incoming messages until you kill the node. All messages are sent to the odometryCb().

fergs gravatar image fergs  ( 2018-08-27 10:26:53 -0500 )edit

Question Tools

Stats

Asked: 2011-07-22 11:36:21 -0500

Seen: 21,983 times

Last updated: Jul 25 '11