Note: This tutorial assumes that you have completed the previous tutorials: rospy tutorials. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Using numpy with rospy
Description: This tutorial covers using numpy with rospy, the ROS Python client library. Numpy is a popular scientific computing package for Python. You will often want to consider using Numpy with rospy if you are working with sensor data as it has better performance and many libraries for manipulating arrays of data.Tutorial Level: BEGINNER
Contents
In this tutorial, we will go over the rospy.numpy_msg module. The rospy.numpy_msg module comes with the numpy_msg() wrapper, which allows Nodes to deserialize Messages directly into numpy arrays, where appropriate. The numpy_msg() wrapper can also be used to publish Messages that contain numpy array data.
Step 1: Create a Package
Lets create a package to house the new code that we are developing. It needs to depend on rospy_tutorials as we will be using one of its Message types.
catkin_create_pkg numpy_tutorial rospy rospy_tutorials
As we are using numpy, we also need to make sure that our package declares this, so lets edit the package.xml file to add the following line:
<build_depend>python-numpy</build_depend> <run_depend>python-numpy</run_depend>
roscreate-pkg numpy_tutorial rospy rospy_tutorials
As we are using numpy, we also need to make sure that our package declares this, so lets edit the manifest.xml file to add the following rosdep line:
<rosdep name="python-numpy" />
Step 2: Create a Listener
By now, you're probably familiar with creating listener nodes. Lets start off simple and create a standard listener node that listens to the floats Topic using the rospy_tutorials/Floats Message type.
Just for reference, here is the rospy_tutorials/Floats definition:
$ rosmsg show rospy_tutorials/Floats float32[] data
Now, lets start with this standard listener. Paste the text below into a file called numpy_listener.py.
1 #!/usr/bin/env python
2 PKG = 'numpy_tutorial'
3 import roslib; roslib.load_manifest(PKG)
4
5 import rospy
6 from rospy_tutorials.msg import Floats
7
8 def callback(data):
9 print rospy.get_name(), "I heard %s"%str(data.data)
10
11 def listener():
12 rospy.init_node('listener')
13 rospy.Subscriber("floats", Floats, callback)
14 rospy.spin()
15
16 if __name__ == '__main__':
17 listener()
Don't forget:
chmod +x numpy_listener.py
Lets make sure that this listener is working before we continue to the next step. We're going to run a roscore, your Node, and a rostopic pub to provide it with data. You'll need several windows:
Window 1:
roscore
Window 2:
rosrun numpy_tutorial numpy_listener.py
Window 3:
rostopic pub -r 1 floats rospy_tutorials/Floats "[1.1, 2.2, 3.3, 4.4, 5.5]"
You should see:
$ rosrun numpy_tutorial numpy_listener.py /listener-977-1248226102144 I heard (1.1000000238418579, 2.2000000476837158, 3.2999999523162842, 4.4000000953674316, 5.5) /listener-977-1248226102144 I heard (1.1000000238418579, 2.2000000476837158, 3.2999999523162842, 4.4000000953674316, 5.5) ... and so on
You can go ahead and stop the rosrun numpy_tutorial numpy_listener.py.
Step 3: Numpy-ize the Listener
In order to numpy-ize our listener, we only need to add two lines, one to import numpy_msg, and the other to use it:
from rospy.numpy_msg import numpy_msg ... rospy.Subscriber("floats", numpy_msg(Floats), callback)
Here are these two lines in context:
1 #!/usr/bin/env python
2 PKG = 'numpy_tutorial'
3 import roslib; roslib.load_manifest(PKG)
4
5 import rospy
6 from rospy_tutorials.msg import Floats
7 from rospy.numpy_msg import numpy_msg
8
9 def callback(data):
10 print rospy.get_name(), "I heard %s"%str(data.data)
11
12 def listener():
13 rospy.init_node('listener')
14 rospy.Subscriber("floats", numpy_msg(Floats), callback)
15 rospy.spin()
16
17 if __name__ == '__main__':
18 listener()
Now lets make sure that these are working. Just as before, lets startup a roscore, your listener, and a rostopic pub.
Window 1:
roscore
Window 2:
rosrun numpy_tutorial numpy_listener.py
Window 3:
rostopic pub -r 1 floats rospy_tutorials/Floats "[1.1, 2.2, 3.3, 4.4, 5.5]"
This time the output is slightly different, which shows that you are now receiving numpy arrays:
$ rosrun rospy_tutorials listener_numpy.py /listener-1243-1248226610835 I heard [ 1.10000002 2.20000005 3.29999995 4.4000001 5.5 ] /listener-1243-1248226610835 I heard [ 1.10000002 2.20000005 3.29999995 4.4000001 5.5 ] ... and so on
Step 4: Numpy-ize a Talker
Now that you know how to numpy-ize a listener, lets numpy-ize a standard talker node. This is very similar to what we did above, though you'll have to be much more careful: all of your array data must be initialized as numpy arrays. You are responsible for this, even for fields that you wish to be initialized with default values. You must also be careful that you specify the correct numpy data type when creating these arrays as rospy will not be able to catch this mistake.
With those warnings out of the way, let's look at a numpy-ized talker. Create a new file, numpy_talker.py, with the following:
1 #!/usr/bin/env python
2 PKG = 'numpy_tutorial'
3 import roslib; roslib.load_manifest(PKG)
4
5 import rospy
6 from rospy.numpy_msg import numpy_msg
7 from rospy_tutorials.msg import Floats
8
9 import numpy
10 def talker():
11 pub = rospy.Publisher('floats', numpy_msg(Floats),queue_size=10)
12 rospy.init_node('talker', anonymous=True)
13 r = rospy.Rate(10) # 10hz
14 while not rospy.is_shutdown():
15 a = numpy.array([1.0, 2.1, 3.2, 4.3, 5.4, 6.5], dtype=numpy.float32)
16 pub.publish(a)
17 r.sleep()
18
19 if __name__ == '__main__':
20 talker()
Don't forget:
chmod +x numpy_talker.py
Just like the listener example, there is a from rospy.numpy_msg import numpy_msg to get the numpy_msg() wrapper. You can also see that this is used when creating the Publisher instance:
pub = rospy.Publisher('floats', numpy_msg(Floats))
The new step we see with the talker example is actually creating our own numpy array. This is where we have to be careful. As was mentioned before, every numerical array in the Message must be initialized with a numpy array of the correct data type. Choosing the correct data type is fairly easy as numpy data types map directly onto ROS data types. In this example we create a simple array of numpy.float32:
a = numpy.array([1.0, 2.1, 3.2, 4.3, 5.4, 6.5], dtype=numpy.float32)
Now that we have a talker node, we don't need rostopic pub. This time we can run roscore, the listener Node, and the talker Node:
Window 1:
roscore
Window 2:
rosrun numpy_tutorial numpy_listener.py
Window 3:
rosrun numpy_tutorial numpy_talker.py
This time you'll see
$ rosrun rospy_tutorials listener_numpy.py /listener-1423-1248226794834 I heard [ 1. 2.0999999 3.20000005 4.30000019 5.4000001 6.5 ] /listener-1423-1248226794834 I heard [ 1. 2.0999999 3.20000005 4.30000019 5.4000001 6.5 ] ... and so on
That's it! That's all you need to know to use numpy with rospy.