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

Creating a Subscriber in python

asked 2016-01-10 23:18:23 -0500

G212 gravatar image

Hi!

I’m trying to create a subscriber using python for this package, following the tutorials that ros provide. The package already contains a subscriber in c++. It uses geometry_msgs/Twist.h

I just want to publish in terminal the values from x, y, width and height. However when I run the code I receive nothing.

This is the code that Im using

 #!/usr/bin/env python
 import rospy
 from geometry_msgs.msg import Twist

 def callback(data):
   rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)

 def listener():

# In ROS, nodes are uniquely named. If two nodes with the same
# node are launched, the previous one is kicked off. The
# anonymous=True flag means that rospy will choose a unique
# name for our 'listener' node so that multiple listeners can
# run simultaneously.
    rospy.init_node('listener', anonymous=True)

    rospy.Subscriber("commands", Twist, callback)

  # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

 if __name__ == '__main__':
      listener()

Hope you could give me a hand thanks

edit retag flag offensive close merge delete

Comments

Check the format of the commands topic - is it a Twist message

nickw gravatar image nickw  ( 2016-01-11 00:07:37 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2016-01-11 17:00:29 -0500

ngoldfarb gravatar image

The Twist message as no field named data. I know that you took this example from the python tutorial on subscribers. That tutorial use a String.msg as you can see this as a field named data. The Twist.msg as two data fields, linear and angular. which are Vector3.msg which contain 3 float64 numbers. So to clear it up to get the 'X' value, you would do the following.

data.linear.x
edit flag offensive delete link more

Comments

thanks a lot, it really helped me

s.vaichu gravatar image s.vaichu  ( 2019-05-14 12:31:51 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-01-10 23:18:23 -0500

Seen: 2,521 times

Last updated: Jan 11 '16