forked from MHarbi/bagedit
-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathimg2bag.py
executable file
·193 lines (170 loc) · 7.93 KB
/
img2bag.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
#!/usr/bin/env python
# Adapted from the work of Alexander Kasper at
# http://answers.ros.org/question/11537/creating-a-bag-file-out-of-a-image-sequence/?answer=173665#post-id-173665
import cv2
import datetime
import os
import sys
import time
from PIL import Image as PILImage
from distutils.util import strtobool
import numpy as np
import rosbag
import rospy
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
from tqdm import tqdm
import argparse
def LoadImage(image_name, scale, debayer=False):
"""
:returns np.ndarray containing an 8-bit RGB image
"""
with open(image_name, "rb") as rawimage:
im = PILImage.open(rawimage) # type: PILImage.Image
if debayer:
print("Attempting to debayer image")
assert (len(im.size) == 2 or im.size[2] == 1)
# imgMat = np.fromfile(rawimage, np.dtype('u2'), imsize).reshape((imrows, imcols))
img = np.array(im, dtype='u2')
img = cv2.cvtColor(img, cv2.COLOR_BayerGB2BGR) # type: np.ndarray
img = (img * (255. / img.max())).astype('uint8')
else:
img = np.array(im, dtype='uint8')
if scale != 1.:
img = cv2.resize(img, None, fx=scale, fy=scale, interpolation=cv2.INTER_CUBIC)
return img
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', '.tif', '.tiff', '.jpeg']:
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, time_format=None):
# '''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()
#
# assert time_format is None
# 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, topic_name, time_format=None, scale=1., debayer=False):
'''Creates a bag file with camera images'''
bag = rosbag.Bag(bagname, 'w', compression=rosbag.Compression.BZ2, chunk_threshold=32 * 1024 * 1024)
bridge = CvBridge()
try:
for i, image_path in enumerate(tqdm(imgs)):
# print("Adding %s" % image_path)
try:
Stamp = None
image_name = os.path.basename(image_path)
if time_format is None or time_format == "":
Stamp = rospy.rostime.Time.from_sec(1574283415 + i)
elif time_format == "name.date.time.n.ext" or time_format == "sentry503":
# format is name.date.time.n.ext where time is hours/minutes/seconds/microseconds
tokens = image_name.split('.')
bag_stamp = datetime.datetime.strptime(':'.join(tokens[1:3]), "%Y%m%d:%H%M%S%f")
Stamp = rospy.rostime.Time(secs=int(time.mktime(bag_stamp.timetuple())),
nsecs=int(bag_stamp.microsecond * 1E3))
# print(time.mktime(bag_stamp.timetuple()))
# print(bag_stamp.second, bag_stamp.microsecond*1E3)
elif time_format == "date.time.ms.n.ext" or time_format == "201504_Panama":
# format is date.time.ms.n.ext where time is hours/minutes/seconds and ms is milliseconds
tokens = image_name.split('.')
bag_stamp = datetime.datetime.strptime(':'.join(tokens[:2]), "%Y%m%d:%H%M%S")
Stamp = rospy.rostime.Time(secs=int(time.mktime(bag_stamp.timetuple())),
nsecs=int(int(tokens[2]) * 1E6))
elif time_format == "secs.nsecs.ext":
tokens = image_name.split('.')
assert len(tokens) == 3
Stamp = rospy.rostime.Time(secs=int(tokens[0]), nsecs=int(tokens[1]))
img = LoadImage(image_path, scale, debayer=debayer)
ImgMsg = bridge.cv2_to_imgmsg(img, "rgb8") # type: Image
ImgMsg.header.stamp = Stamp
ImgMsg.header.frame_id = "camera"
ImgMsg.header.seq = i
except ValueError:
print("WARNING: Failed to process file %s" % image_path)
continue
bag.write(topic_name, ImgMsg, Stamp)
finally:
bag.close()
def CreateBag(image_dir, bagname, image_topic_name, debayer=False, time_format=None, scale=1., ):
'''Creates the actual bag file by successively adding images'''
all_imgs, left_imgs, right_imgs = GetFilesFromDir(image_dir)
if len(all_imgs) <= 0:
print("No images found in %s" % image_dir)
exit()
if len(left_imgs) > 0 and len(right_imgs) > 0:
# create bagfile with stereo camera image pairs
# CreateStereoBag(left_imgs, right_imgs, bagname, time_format=time_format)
raise NotImplementedError("Disabled")
else:
# create bagfile with mono camera image stream
CreateMonoBag(all_imgs, bagname, image_topic_name, time_format=time_format, scale=float(scale), debayer=debayer)
if __name__ == "__main__":
parser = argparse.ArgumentParser(description="Convert an image directory into a ROS bag.")
parser.add_argument("image_dir", help="Input directory of bmp/png/jpg/tif images.")
parser.add_argument("output_bag", help="Output ROS bag.")
parser.add_argument("image_topic", default="camera/image_raw", help="Image topic name")
parser.add_argument("--t_start", default=0., type=float, help="Ignore messages before this time")
parser.add_argument("--time_format", default=None, type=str)
parser.add_argument("--debayer", default=False, action="store_true")
parser.add_argument("--scale", default=1.)
args = parser.parse_args()
CreateBag(args.image_dir, args.output_bag, args.image_topic, debayer=args.debayer, time_format=args.time_format, scale=args.scale)