Subscribing to compressed Images from rosbag
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
Asked by ARM on 2018-04-28 07:25:12 UTC
Answers
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).
Asked by robotchicken on 2018-04-28 12:43:17 UTC
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!
Asked by ARM on 2018-04-28 16:00:18 UTC
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.
Asked by robotchicken on 2018-04-28 16:38:13 UTC
Check my edit, you don't have to use the republish node. My bad.
Asked by robotchicken on 2018-04-28 16:44:35 UTC
Please mark as resolved if this works out for you.
Asked by robotchicken on 2018-04-29 22:41:58 UTC
Thanks for your update! I am on it. Will update soon after successful execution.
Asked by ARM on 2018-04-30 03:37:35 UTC
Hi. When I execute my subscriber file, it shows nothing. I think I am missing something in my code. Please review. Thanks
Asked by ARM on 2018-04-30 05:40:31 UTC
Any update please!
Asked by ARM on 2018-05-02 02:56:04 UTC
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.
Asked by robotchicken on 2018-05-19 11:59:54 UTC
I checked it was publishing. But using the following code I directly took what I need without playing Bag file instead reading it with Python. Thanks @robotchicken
Asked by ARM on 2018-05-22 05:34:02 UTC
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()
Asked by ARM on 2018-05-17 05:32:20 UTC
Comments