Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Can't convert Images from a rosbag #2

Open
awesomebytes opened this issue May 16, 2017 · 2 comments · May be fixed by #6
Open

Can't convert Images from a rosbag #2

awesomebytes opened this issue May 16, 2017 · 2 comments · May be fixed by #6

Comments

@awesomebytes
Copy link
Contributor

If reading messages from a rosbag one gets an error like:

ValueError: Unable to convert message _sensor_msgs__Image - only supports Numpy_sensor_msgs__Image, Numpy_geometry_msgs__Transform, Numpy_nav_msgs__OccupancyGrid, Numpy_sensor_msgs__PointField[], Transform, PointField[], Image, Numpy_geometry_msgs__Quaternion, OccupancyGrid, PointCloud2, Numpy_geometry_msgs__Point, Pose, Point, Numpy_geometry_msgs__Vector3, Numpy_geometry_msgs__Pose, Numpy_sensor_msgs__PointCloud2, Vector3, Quaternion

That's because

In [1]: from sensor_msgs.msg import Image

In [2]: img = Image()

In [3]: img.__class__
Out[3]: sensor_msgs.msg._Image.Image

In [4]: from rosbag import Bag   

In [5]: b = Bag('poc_bag.bag')

In [6]: r = b.read_messages(topics=['/pepper/camera/depth/image_raw'] )

In [7]: topic, msg, time = r.next()

In [8]: msg.__class__
Out[8]: tmpldS_vh._sensor_msgs__Image

In [13]: img.__class__.__name__
Out[13]: 'Image'

In [14]: msg.__class__.__name__
Out[14]: '_sensor_msgs__Image'

From a rosbag the messages don't seem to have the proper type (I guess it has something to do with the way messages are stored).

@rarmstrong22
Copy link

rarmstrong22 commented Feb 26, 2018

I've run into this, too. Appears to be a rosbag issue, not a ros_numpy issue. Also plays havoc with pickle. I found that I could work around this by inserting the correct __class__ when loading from a rosbag. Lame, but it works for my need:

for msg in msgs:
        if msg.topic == odom_topic:
            msg.message.__class__ = nav_msgs.msg._Odometry.Odometry
            odom_msgs.append(msg.message)
        if msg.topic == scan_topic:
            msg.message.__class__ = sensor_msgs.msg._PointCloud2.PointCloud2
            scan_msgs.append(msg.message)

@manasrda
Copy link

manasrda commented Jan 3, 2023

Based on the answer by rarmstrong22.

For anyone searching for a quick working solution. In case you are sure it is a ROS Image message but it still throws this error.
This worked for me:

import ros_numpy
import sensor_msgs

def get_img_from_ros_image_msg(msg):
    """ Returns image as a numpy array. 
    Note: can be used with any topic of message type 'sensor_msgs/Image'
    """
    msg.__class__ = sensor_msgs.msg.Image
    return ros_numpy.numpify(msg)

img_array =  get_img_from_ros_image_msg(msg)

# for free to join this conversation on GitHub. Already have an account? # to comment
Labels
None yet
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants