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

Creating a bag file out of a image sequence

asked 2011-10-13 04:20:59 -0600

updated 2014-01-28 17:10:34 -0600

ngrennan gravatar image

Let's say I have a series of images and want to create a bag file out of them to use as input for the camera calibration.

Is it even necessary to create the bag for the calibration or is there another way to use the images?

If not, can a bag file be created from an image sequence? I guess using some python-fu it should be possible. Would that be a good idea?

UPDATE: Using the bag file for calibration seems not feasible as the standard calibration app insists on talking back to the camera. So to use that one will need to hack the script. The other possibility that might be working (testing atm) is a not documented script "tarfile_calibration.py" which can read a tar file containing the image sequence. Simply create a tar file with numbered images in format "left%d.png" and "right%d.png" and you're good to go:

rosrun camera_calibration tarfile_calibration.py MyImages.tar --square 0.108 --size 8x6
edit retag flag offensive close merge delete

Comments

None of the above code worked

ujur gravatar image ujur  ( 2018-09-24 04:53:15 -0600 )edit
1

@ujur: your post is not an answer, so I converted it to a comment.

This is your second post that does not include any details whatsoever, so we cannot help you with it.

Please refrain from posting content like this, as it doesn't help others, and we cannot help you.

gvdhoorn gravatar image gvdhoorn  ( 2018-09-24 10:17:13 -0600 )edit

5 Answers

Sort by ยป oldest newest most voted
6

answered 2011-10-16 21:21:48 -0600

updated 2011-10-16 21:23:10 -0600

Ok, found this out myself. I haven't had the chance to test my bag files with the calibration yet, but they do play fine, so I'm assuming it should work. For anyone interested here's the script you can use to create a bag file from an image sequence (supports mono and stereo):

import time, sys, os
from ros import rosbag
import roslib
roslib.load_manifest('sensor_msgs')
from sensor_msgs.msg import Image

import ImageFile

def GetFilesFromDir(dir):
    '''Generates a list of files from the directory'''
    print( "Searching directory %s" % dir )
    all = []
    left_files = []
    right_files = []
    if os.path.exists(dir):
        for path, names, files in os.walk(dir):
            for f in files:
                if os.path.splitext(f)[1] in ['.bmp', '.png', '.jpg']:
                    if 'left' in f or 'left' in path:
                        left_files.append( os.path.join( path, f ) )
                    elif 'right' in f or 'right' in path:
                        right_files.append( os.path.join( path, f ) )
                    all.append( os.path.join( path, f ) )
    return all, left_files, right_files

def CreateStereoBag(left_imgs, right_imgs, bagname):
    '''Creates a bag file containing stereo image pairs'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(left_imgs)):
            print("Adding %s" % left_imgs[i])
            fp_left = open( left_imgs[i], "r" )
            p_left = ImageFile.Parser()

            while 1:
                s = fp_left.read(1024)
                if not s:
                    break
                p_left.feed(s)

            im_left = p_left.close()

            fp_right = open( right_imgs[i], "r" )
            print("Adding %s" % right_imgs[i])
            p_right = ImageFile.Parser()

            while 1:
                s = fp_right.read(1024)
                if not s:
                    break
                p_right.feed(s)

            im_right = p_right.close()

            Stamp = roslib.rostime.Time.from_sec(time.time())

            Img_left = Image()
            Img_left.header.stamp = Stamp
            Img_left.width = im_left.size[0]
            Img_left.height = im_left.size[1]
            Img_left.encoding = "rgb8"
            Img_left.header.frame_id = "camera/left"
            Img_left_data = [pix for pixdata in im_left.getdata() for pix in pixdata]
            Img_left.data = Img_left_data
            Img_right = Image()
            Img_right.header.stamp = Stamp
            Img_right.width = im_right.size[0]
            Img_right.height = im_right.size[1]
            Img_right.encoding = "rgb8"
            Img_right.header.frame_id = "camera/right"
            Img_right_data = [pix for pixdata in im_right.getdata() for pix in pixdata]
            Img_right.data = Img_right_data

            bag.write('camera/left/image_raw', Img_left, Stamp)
            bag.write('camera/right/image_raw', Img_right, Stamp)
    finally:
        bag.close()

def CreateMonoBag(imgs):
    '''Creates a bag file with camera images'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(imgs)):
            print("Adding %s" % imgs[i])
            fp = open( imgs[i], "r" )
            p = ImageFile.Parser()

            while 1:
                s = fp.read(1024)
                if not s:
                    break
                p.feed(s)

            im = p.close()

            Stamp = roslib.rostime.Time.from_sec(time.time())

            Img = Image()
            Img.header.stamp = Stamp
            Img.width = im_left.size[0]
            Img.height = im_left.size[1]
            Img.encoding = "rgb8"
            Img.header.frame_id = "camera"
            Img_data = [pix for pixdata in im.getdata() for pix in pixdata]
            Img_.data = Img_data

            bag.write('camera/image_raw', Img, Stamp)
    finally:
        bag.close()       


def CreateBag(args):
    '''Creates the actual bag file by successively adding images'''
    all_imgs, left_imgs, right_imgs = GetFilesFromDir(args[0])
    if len(all_imgs) <= 0:
        print("No images found in %s" % args[0])
        exit()

    if len(left_imgs) > 0 and len(right_imgs) > 0:
        # create bagfile with stereo camera image pairs
        CreateStereoBag(left_imgs, right_imgs, args[1 ...
(more)
edit flag offensive delete link more

Comments

Hi, I have an error running this script:
Img_data = [pix for pixdata in im.getdata() for pix in pixdata] TypeError: 'int' object is not iterable

Any idea? Thx.

fins gravatar image fins  ( 2013-04-03 05:33:22 -0600 )edit

Make sure your image is RGB and not mono.

Simon Leonard gravatar image Simon Leonard  ( 2014-03-09 16:35:14 -0600 )edit

So just to clarify, I know this code was written for the purpose of calibration, but can I take a series of images taken from a prior video stream, and patch them together again so the final .bag file is a video?

Thalaiva gravatar image Thalaiva  ( 2015-07-15 09:05:00 -0600 )edit

I use this code with gray images via "python test.py imagesFolder test.bag" on ubuntu terminal.

 line 106, in CreateMonoBag
    Img_data = [pix for pixdata in im.getdata() for pix in pixdata]
TypeError: 'int' object is not iterable
jossy gravatar image jossy  ( 2016-01-09 02:34:07 -0600 )edit

Sorry, I am wrong. This code runs with rgb images. It works now!

jossy gravatar image jossy  ( 2016-01-09 03:02:07 -0600 )edit

so how can i make a StereoBag using this script? Seems it automatically run the monoBag part

flaver gravatar image flaver  ( 2020-11-16 20:22:56 -0600 )edit

how do i add imu data to a rosbag?

quantum guy 123 gravatar image quantum guy 123  ( 2021-09-20 12:58:11 -0600 )edit

what format does it need to be in?

quantum guy 123 gravatar image quantum guy 123  ( 2021-09-20 12:58:21 -0600 )edit
1

answered 2017-02-21 09:15:01 -0600

julos gravatar image

Hi, here are some suggestions to improve:

In my case images are unordered. To sort images in numerical order, a new function can be defined:

def CompSortFileNamesNr(f):
    g = os.path.splitext(os.path.split(f)[1])[0]
    numbertext = ''.join(c for c in g if c.isdigit())
    return int(numbertext)

And in GetFilesFromDir, change line

            for f in files:

to

            for f in sorted(files, key=CompSortFileNamesNr):

In order to process a sequence of grey-level images, the code may be modified as follow:

Change "rgb8" encoding to "mono8", and "[pix for pixdata in im.getdata() for pix in pixdata]" to "[pix for pixdata in [im.getdata()] for pix in pixdata]"

Bye

edit flag offensive delete link more

Comments

I am trying to save an image that has bitdepth of 2 I set im.step = im.size[0] * 1 im.encoding = "mono16" but i'm getting an error from msg.serialize(self._buffer) in bag.py: genpy.message.SerializationError: field data[] exceeds specified width [uint8] field_val 1574 maxval 256

Avner gravatar image Avner  ( 2019-01-18 17:48:05 -0600 )edit
1

answered 2014-06-15 06:10:44 -0600

Sahand gravatar image

updated 2014-06-15 06:19:50 -0600

Your CreateMonoBag had some problems, I made some modifications:

import time, sys, os
from ros import rosbag
import roslib
import rospy
roslib.load_manifest('sensor_msgs')
from sensor_msgs.msg import Image

import ImageFile

def GetFilesFromDir(dir):
    '''Generates a list of files from the directory'''
    print( "Searching directory %s" % dir )
    all = []
    left_files = []
    right_files = []
    if os.path.exists(dir):
        for path, names, files in os.walk(dir):
            for f in files:
                if os.path.splitext(f)[1] in ['.bmp', '.png', '.jpg', '.ppm']:
                    if 'left' in f or 'left' in path:
                        left_files.append( os.path.join( path, f ) )
                    elif 'right' in f or 'right' in path:
                        right_files.append( os.path.join( path, f ) )
                    all.append( os.path.join( path, f ) )
    return all, left_files, right_files

def CreateStereoBag(left_imgs, right_imgs, bagname):
    '''Creates a bag file containing stereo image pairs'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(left_imgs)):
            print("Adding %s" % left_imgs[i])
            fp_left = open( left_imgs[i], "r" )
            p_left = ImageFile.Parser()

            while 1:
                s = fp_left.read(1024)
                if not s:
                    break
                p_left.feed(s)

            im_left = p_left.close()

            fp_right = open( right_imgs[i], "r" )
            print("Adding %s" % right_imgs[i])
            p_right = ImageFile.Parser()

            while 1:
                s = fp_right.read(1024)
                if not s:
                    break
                p_right.feed(s)

            im_right = p_right.close()

            Stamp = roslib.rostime.Time.from_sec(time.time())

            Img_left = Image()
            Img_left.header.stamp = Stamp
            Img_left.width = im_left.size[0]
            Img_left.height = im_left.size[1]
            Img_left.encoding = "rgb8"
            Img_left.header.frame_id = "camera/left"
            Img_left_data = [pix for pixdata in im_left.getdata() for pix in pixdata]
            Img_left.data = Img_left_data
            Img_right = Image()
            Img_right.header.stamp = Stamp
            Img_right.width = im_right.size[0]
            Img_right.height = im_right.size[1]
            Img_right.encoding = "rgb8"
            Img_right.header.frame_id = "camera/right"
            Img_right_data = [pix for pixdata in im_right.getdata() for pix in pixdata]
            Img_right.data = Img_right_data

            bag.write('camera/left/image_raw', Img_left, Stamp)
            bag.write('camera/right/image_raw', Img_right, Stamp)
    finally:
        bag.close()

def CreateMonoBag(imgs,bagname):
    '''Creates a bag file with camera images'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(imgs)):
            print("Adding %s" % imgs[i])
            fp = open( imgs[i], "r" )
            p = ImageFile.Parser()

            while 1:
                s = fp.read(1024)
                if not s:
                    break
                p.feed(s)

            im = p.close()

            Stamp = rospy.rostime.Time.from_sec(time.time())
            Img = Image()
            Img.header.stamp = Stamp
            Img.width = im.size[0]
            Img.height = im.size[1]
            Img.encoding = "rgb8"
            Img.header.frame_id = "camera"
            Img_data = [pix for pixdata in im.getdata() for pix in pixdata]
            Img.data = Img_data

            bag.write('camera/image_raw', Img, Stamp)
    finally:
        bag.close()       


def CreateBag(args):
    '''Creates the actual bag file by successively adding images'''
    all_imgs, left_imgs, right_imgs = GetFilesFromDir(args[0])
    if len(all_imgs) <= 0:
        print("No images found in %s" % args[0])
        exit()

    if len(left_imgs) > 0 and len(right_imgs) > 0:
        # create bagfile with stereo camera image pairs
        CreateStereoBag(left_imgs, right_imgs, args[1])
    else:
        # create bagfile with mono camera image stream
        CreateMonoBag(all_imgs, args[1])        

if __name__ == "__main__":
    if len( sys.argv ) == 3:
        CreateBag( sys.argv[1:])
    else:
        print( "Usage: img2bag imagedir bagfilename")
edit flag offensive delete link more

Comments

1

I get this error with createMonoBag:

[ERROR] [1435157178.426668947]: Unable to convert 'bgr8' image to bgr8: 'Image is wrongly formed: step < width * byte_depth * num_channels  or  0 != 648 * 1 * 3'

The package runs. I get the error when trying to view the bag with image_view. Any idea why? Thx

538amado gravatar image 538amado  ( 2015-06-24 10:42:06 -0600 )edit

Are you using RGB images or mono?

Thalaiva gravatar image Thalaiva  ( 2015-07-15 09:03:53 -0600 )edit
1

I had the same issue with rgb8 images and fixed it by adding the line:

Img.step = Img.width * 3

where 3 is the number of channels. (in this case it's asking for a byte_depth of 1... I thought it should be byte_depth=8 but that doesn't work and I'm not sure why)

antonella gravatar image antonella  ( 2016-02-16 20:06:09 -0600 )edit
1

answered 2015-03-30 18:51:06 -0600

Tiago Giacomelli gravatar image

For me, the line ("Stamp = roslib.rostime.Time.from_sec(time.time())") found a problem.

I saw in this page ( http://docs.ros.org/diamondback/api/r... ) an alternative: Stamp = rospy.Time.from_sec(time.time())

Good job!

edit flag offensive delete link more
0

answered 2020-09-17 01:29:01 -0600

edward0im gravatar image

updated 2020-09-17 03:53:14 -0600

My case, below code is working faster and no errors. It's using cv_bridge package to make it faster.

import time, sys, os
from ros import rosbag
import roslib
import rospy
roslib.load_manifest('sensor_msgs')
from sensor_msgs.msg import Image
from cv_bridge import CvBridge

from PIL import ImageFile

import cv2

def GetFilesFromDir(dir):
    '''Generates a list of files from the directory'''
    print( "Searching directory %s" % dir )
    all = []
    left_files = []
    right_files = []
    if os.path.exists(dir):
        for path, names, files in os.walk(dir):
            for f in sorted(files):
                if os.path.splitext(f)[1] in ['.bmp', '.png', '.jpg', '.ppm']:
                    if 'left' in f or 'left' in path:
                        left_files.append( os.path.join( path, f ) )
                    elif 'right' in f or 'right' in path:
                        right_files.append( os.path.join( path, f ) )
                    all.append( os.path.join( path, f ) )
    return all, left_files, right_files


def CreateStereoBag(left_imgs, right_imgs, bagname):
    '''Creates a bag file containing stereo image pairs'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(left_imgs)):
            print("Adding %s" % left_imgs[i])
            img_left = cv2.imread(left_imgs[i])
            img_right = cv2.imread(right_imgs[i])

            bridge = CvBridge()

            Stamp = roslib.rostime.Time.from_sec(time.time())

            img_msg_left = Image()
            img_msg_left = bridge.cv2_to_imgmsg(img_left, "bgr8")
            img_msg_left.header.seq = i
            img_msg_left.header.stamp = Stamp
            img_msg_left.header.frame_id = "camera/left"

            img_msg_right = Image()
            img_msg_right = bridge.cv2_to_imgmsg(img_right, "bgr8")
            img_msg_right.header.seq = i
            img_msg_right.header.stamp = Stamp
            img_msg_right.header.frame_id = "camera/right"

            bag.write('camera/left/image_raw', img_msg_left, Stamp)
            bag.write('camera/right/image_raw', img_msg_right, Stamp)
    finally:
        bag.close()


def CreateMonoBag(imgs, bagname):
    '''Creates a bag file with camera images'''
    bag =rosbag.Bag(bagname, 'w')

    try:
        for i in range(len(imgs)):
            print("Adding %s" % imgs[i])
            img = cv2.imread(imgs[i])
            bridge = CvBridge()

            Stamp = rospy.rostime.Time.from_sec(time.time())
            img_msg = Image()
            img_msg = bridge.cv2_to_imgmsg(img, "bgr8")
            img_msg.header.seq = i
            img_msg.header.stamp = Stamp
            img_msg.header.frame_id = "camera"

            bag.write('camera/image_raw', img_msg, Stamp)
    finally:
        bag.close()       


def CreateBag(args):
    '''Creates the actual bag file by successively adding images'''
    all_imgs, left_imgs, right_imgs = GetFilesFromDir(args[0])
    if len(all_imgs) <= 0:
        print("No images found in %s" % args[0])
        exit()

    if len(left_imgs) > 0 and len(right_imgs) > 0:
        # create bagfile with stereo camera image pairs
        CreateStereoBag(left_imgs, right_imgs, args[1])
    else:
        # create bagfile with mono camera image stream
        CreateMonoBag(all_imgs, args[1])        

if __name__ == "__main__":
    if len( sys.argv ) == 3:
        CreateBag( sys.argv[1:])
    else:
        print( "Usage: img2bag imagedir bagfilename")
edit flag offensive delete link more

Comments

Hi there! I try to use your code but there is something that bother me: I have 9Go of input images and an 160Go output bag!! Did you observe something similar?

jcharpentier gravatar image jcharpentier  ( 2021-06-24 08:21:44 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-10-13 04:20:59 -0600

Seen: 12,293 times

Last updated: Sep 17 '20