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

Subscribing to compressed Images from rosbag

asked 2018-04-28 07:25:12 -0500

ARM gravatar image

Hello,

I have a rosbag file with compressed images recorded. The rosbag file is publishing the topic:

 "/xxxx/image_raw/compressed" of type "sensor_msgs/CompressedImage".

I want to write the subscriber in python.

I saw the following example from ROS wiki for subscribing the normal messages from chatter topic.

#!/usr/bin/env python

import rospy
from std_msgs.msg import String

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

def listener():

    rospy.init_node('listener', anonymous=True)

    rospy.Subscriber('chatter', String, callback)

    rospy.spin()

if __name__ == '__main__':
    listener()

I have changed it as:

#!/usr/bin/env python

import rospy
from sensor_msgs.msg import CompressedImage

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

def listener():

    rospy.init_node('image_subscriber', anonymous=True)

    rospy.Subscriber('/xxxx/image_raw/compressed', CompressedImage, callback)

    rospy.spin()

if __name__ == '__main__':
    listener()

Where should I make more changes so that it will subscribe to the topic /xxxx/image_raw/compressed and save images to the disk.

Please, provide me some guidelines.

Thanks!

ARM

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-05-17 05:32:20 -0500

ARM gravatar image

Execution: $ rosrun package_name file_name.py directory_name_to_store_information

#! /usr/bin/python

import os
import sys
import cv2
import csv
import rospy, rosbag
import numpy as np
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError

# Verifying output directory where Images and metadata(csv) will be stored

if len(sys.argv) == 2:
    out_dir = sys.argv[1]
    if not os.path.exists(sys.argv[1]):
        os.makedirs(out_dir)

    else:
        print sys.argv[1], 'already exists'
        sys.exit()

else:
    print 'specify output directory'
    sys.exit()

bridge = CvBridge()

def main():

    # Topic name 
    topicName0 = '/topic/image_raw/compressed'

    # Bag file 
    inbag_name ='/Path/2018-05-15-16-42-43.bag'

    bag = rosbag.Bag(inbag_name)

    for topic, msg, t in bag.read_messages():

        if(topic == topicName0 ):
            try:
                # Convert compressed image to RAW
                img = bridge.compressed_imgmsg_to_cv2(msg)

            except CvBridgeError, e:
                print(e)

            else:
                # Writing image to the directory mentioned while executing script
                cv2.imwrite(sys.argv[1]+'/frame_' + str(msg.header.stamp) + '.jpeg', img)

                # Saving metadata information as per requirement
                with open(sys.argv[1]+'/metadata.csv','ab') as f:
                    thewriter = csv.writer(f)
                    thewriter.writerow([str(msg.header.seq),str(msg.header.stamp),os.getcwd()+'/'+sys.argv[1]+'/', 'frame_'+ str(msg.header.stamp) + '.jpeg'])

    bag.close()
    rospy.spin()

if __name__ == "__main__":
    main()
edit flag offensive delete link more
0

answered 2018-04-28 12:43:17 -0500

robotchicken gravatar image

updated 2018-04-28 16:43:55 -0500

To convert from compressed image to raw image, run the republish node.(Ref)

rosrun image_transport republish compressed in:=/xxxx/image_raw/compressed raw out:=/xxxx/image_raw/raw

Now in your node, you can subscribe to the raw topic, convert to cv2 image and save to disk.(Ref).

EDIT: You can directly convert the compressed ROS image to opencv matrix by using compressed_imgmsg_to_cv2(cmprs_img_msg). (Ref).

edit flag offensive delete link more

Comments

It means that when I execute rosrun image_transport command this will republish images into /xxxx/image_raw/raw.

And in subscriber node --> image_topic = "/xxxx/image_raw/raw"

Therefore the first step is to republish then execute subscriber node.

Please, clarify if I said something wrong!

ARM gravatar image ARM  ( 2018-04-28 16:00:18 -0500 )edit

Yes you are right, we republish as raw format first. Then in the subscriber node you subscribe to the republished raw topic and save the cv2 image onto disk. Please check the links for more details.

robotchicken gravatar image robotchicken  ( 2018-04-28 16:38:13 -0500 )edit

Check my edit, you don't have to use the republish node. My bad.

robotchicken gravatar image robotchicken  ( 2018-04-28 16:44:35 -0500 )edit

Please mark as resolved if this works out for you.

robotchicken gravatar image robotchicken  ( 2018-04-29 22:41:58 -0500 )edit

Thanks for your update! I am on it. Will update soon after successful execution.

ARM gravatar image ARM  ( 2018-04-30 03:37:35 -0500 )edit

Hi. When I execute my subscriber file, it shows nothing. I think I am missing something in my code. Please review. Thanks

ARM gravatar image ARM  ( 2018-04-30 05:40:31 -0500 )edit

Any update please!

ARM gravatar image ARM  ( 2018-05-02 02:56:04 -0500 )edit

Is there any message actually being published to the topic "/xxxx/image_raw/compressed"??? Do a "rostopic echo /xxxx/image_raw/compressed" and check if you receive any message. if you dont receive any, check your setup.

robotchicken gravatar image robotchicken  ( 2018-05-19 11:59:54 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-04-28 07:25:12 -0500

Seen: 5,141 times

Last updated: May 17 '18