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

How do I convert an ROS image into a numpy array?

asked 2013-06-04 12:17:01 -0500

Albatross gravatar image

updated 2014-01-28 17:16:46 -0500

ngrennan gravatar image

Hi All,

I'm trying to read ROS images published from a video camera (from MORSE) into a numpy array in my python script, but I don't know what is the correct way to do this, and everything I have tried hasn't worked.

Does anyone know how to do this?

Here is a snippet of what I have tried so far:

import numpy 
import rospy 
from sensor_msgs.msg import Image

def vis_callback( data ):
  im = numpy.array( data.data, dtype=numpy.uint8 )
  doSomething( im )
rospy.init_node('bla',anonymous=True)
sub_vis = rospy.Subscriber('navbot/camera/image',Image,vis_callback)

rospy.spin()

I get an error that looks like this:

[ERROR] [WallTime: 1370383204.000265] bad callback: <function vis_callback at 0x32e2398>
Traceback (most recent call last):
  File "/opt/ros/fuerte/lib/python2.7/dist-packages/ros_comm-1.8.15-py2.7.egg/rospy/topics.py", line 678, in _invoke_callback
    cb(msg)
  File "ros_simulate.py", line 55, in vis_callback
    im = numpy.array(data.data,dtype=numpy.uint8)
ValueError: invalid literal for long() with base 10: "':\x0f\xff';\x10\xff+A\x12\xff7Q\x16\xffB`\x18\xffGg\x18\xffDa\x15\xff=W\x12\xff2H\r\xff*<\x0b\xff&8\n\xff$6\t\xff%6\t\xff'9\n\xff*>\n\xff0G\x0b\xff8S\x0b\xff;Y\n\xff:X\t\xff8V\x07\xff6T\x06\xff2N\x04\xff-F\x04\xff+B\x03\xff&<\x03\xff(?\x05\xff#8\x07\xff\x1e0\x07\xff\x19)\x07\xff\x19(\x08\xff\x1b+\t\xff\x1e0\x0b\xff\x1e0\x0b\xff 3\x0c\xff\x1e1\x0b\xff\x1e1\x0b\xff\x1d/\n\xff\x1c-\t\xff\x1c,\t\xff\x1a*\x08\xff\x1d.\x08\xff(>\x0b\xff-F\x0c\xff<[\x0f\xffJo\x12\xffJp\x12\xffKr\x12\xffLs\x12\xffMt\x13\xffMu\x13\xff"

I noticed that the Image object has a deserialize_numpy() method, I couldn't find any documentation on how to use it, so I crossed my fingers and tried it out:

def vis_callback( data ):
  im = numpy.array(data.deserialize_numpy(data.data, numpy ), dtype=numpy.uint8)
  doSomething( im )

and got more errors:

[ERROR] [WallTime: 1370383699.289428] bad callback: <function vis_callback at 0x34b5410>
Traceback (most recent call last):
  File "/opt/ros/fuerte/lib/python2.7/dist-packages/ros_comm-1.8.15-py2.7.egg/rospy/topics.py", line 678, in _invoke_callback
    cb(msg)
  File "ros_simulate.py", line 53, in vis_callback
    im = numpy.array(data.deserialize_numpy(data.data, numpy ), dtype=numpy.uint8)
  File "/opt/ros/fuerte/lib/python2.7/dist-packages/sensor_msgs/msg/_Image.py", line 282, in deserialize_numpy
    raise genpy.DeserializationError(e) #most likely buffer underfill
DeserializationError: unpack requires a string argument of length 8
edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
10

answered 2013-06-04 12:38:35 -0500

updated 2013-06-04 12:39:49 -0500

You need to deserialize the message data with cv_bridge first (python tutorial). Once you have the image as a cv.Mat, you can just call numpy.asarray on it.

edit flag offensive delete link more

Comments

Thanks! That worked perfectly for me

Albatross gravatar image Albatross  ( 2013-06-05 08:35:55 -0500 )edit
5

answered 2016-02-27 00:28:08 -0500

updated 2016-02-27 03:57:02 -0500

gvdhoorn gravatar image

I've thrown together a package that tries to solve the "How can I convert ROS's <X> into a numpy array" class of problems: ros_numpy. Using this, the solution becomes:

arr = ros_numpy.numpify(img_msg)
edit flag offensive delete link more

Comments

That sounds quite useful! Can you provide a link to source code or documentation for your package?

ahendrix gravatar image ahendrix  ( 2016-02-27 00:54:18 -0500 )edit

@ahendrix: The package name above is a link to the github repo, containing both of those things

eric-wieser gravatar image eric-wieser  ( 2016-02-27 01:16:28 -0500 )edit

excellent!

ahendrix gravatar image ahendrix  ( 2016-02-27 02:09:27 -0500 )edit

This package is now published!

eric-wieser gravatar image eric-wieser  ( 2016-04-11 21:17:15 -0500 )edit
5

answered 2018-05-23 10:59:10 -0500

matwilso gravatar image

This will do what you want, assuming you have an RGB image. If not, you can check the data.encoding and add some extra logic.

import numpy as np
import rospy 
from sensor_msgs.msg import Image
from rospy.numpy_msg import numpy_msg

def vis_callback( data ):
  im = np.frombuffer(data.data, dtype=np.uint8).reshape(data.height, data.width, -1)
  doSomething(im)

rospy.init_node('bla', anonymous=True)
sub_vis = rospy.Subscriber('navbot/camera/image', numpy_msg(Image), vis_callback)

rospy.spin()
edit flag offensive delete link more
0

answered 2013-08-29 01:38:57 -0500

Achim gravatar image

The more general way (i.e. for all type of messages), which also avoids the detour over cv.Mat, and should work fine for opencv today, as opencv now uses numpy arrays in the new cv2 interface is described here:

http://www.ros.org/wiki/rospy_tutorials/Tutorials/numpy

You basically tell ros to use the serialize/deserialize_numpy methods by adding numpy_msg() around the message type. Which means your subscription should look like:

[code] from rospy.numpy_msg import numpy_msg ... sub_vis = rospy.Subscriber('navbot/camera/image',numpy_msg(Image),vis_callback)[/code]

and then data.data should be an numpy.array.

edit flag offensive delete link more

Comments

But data.data will still be a 1d array of bytes, not a 3d image array of the right type

eric-wieser gravatar image eric-wieser  ( 2016-02-27 00:27:29 -0500 )edit

Question Tools

Stats

Asked: 2013-06-04 12:17:01 -0500

Seen: 19,015 times

Last updated: May 23 '18