Skip to content

Commit 868d699

Browse files
committed
Modify make_minimal_rosbag.py to save images in compressed format
1 parent 8106c0b commit 868d699

File tree

1 file changed

+12
-8
lines changed

1 file changed

+12
-8
lines changed

scripts/make_minimal_rosbag.py

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,14 @@ def generate_rectify_map(cam_model):
2525

2626

2727
def debayer_blur_and_rectify_image(msg_image, topic):
28-
cv_image = open_cv_bridge.imgmsg_to_cv2(msg_image, desired_encoding='rgb8')
29-
cv_image = cv.GaussianBlur(cv_image, (41, 41), 0)
28+
cv_image = open_cv_bridge.imgmsg_to_cv2(msg_image, desired_encoding='bgr8')
29+
cv_image = cv.GaussianBlur(cv_image, (21, 21), 0)
3030
# try to rectify image if camera info is already available
3131
try:
3232
cv_image_rectified = cv.remap(cv_image, rectify_maps[topic], None, cv.INTER_CUBIC)
3333
except KeyError:
3434
cv_image_rectified = cv_image
35-
out = open_cv_bridge.cv2_to_imgmsg(cv_image_rectified, encoding="rgb8")
35+
out = open_cv_bridge.cv2_to_compressed_imgmsg(cv_image_rectified, "jpg")
3636
out.header = msg_image.header
3737
return out
3838

@@ -72,6 +72,9 @@ def debayer_blur_and_rectify_image(msg_image, topic):
7272
bar = progressbar.ProgressBar(input_bag.get_message_count())
7373
for m in bar(input_bag.read_messages(return_connection_header=True)):
7474

75+
# copy connection header
76+
connection_header = m.connection_header
77+
7578
# calculate the relative time delta between current and first message
7679
if record_stamp_of_first_msg is None:
7780
record_stamp_of_first_msg = m.timestamp
@@ -81,21 +84,22 @@ def debayer_blur_and_rectify_image(msg_image, topic):
8184
if m.topic in topic_whitelist:
8285

8386
# generate rectify map from camera info in order to be able to rectify the raw image later
84-
if args.blur_image and m.connection_header['type'] == b'sensor_msgs/CameraInfo' and m.topic not in rectify_maps:
87+
if args.blur_image and connection_header['type'] == b'sensor_msgs/CameraInfo' and m.topic not in rectify_maps:
8588
model = PinholeCameraModel()
8689
model.fromCameraInfo(m.message)
8790
rectify_maps[m.topic.replace("/camera_info", "")] = generate_rectify_map(model)
8891

8992
# check if image and whether it should be blurred
90-
if args.blur_image and m.connection_header['type'] == b'sensor_msgs/Image' and m.topic.endswith(
93+
if args.blur_image and connection_header['type'] == b'sensor_msgs/Image' and m.topic.endswith(
9194
'image_raw'):
9295
msg = debayer_blur_and_rectify_image(m.message, m.topic.replace("/image_raw", ""))
93-
topic = m.topic[:-9] + "image_rect_color"
96+
topic = m.topic[:-9] + "image_rect_color/compressed"
97+
connection_header = None # generate new connection header as message type has changed
9498
else:
9599
msg = m.message
96100
topic = m.topic
97101

98-
if t_rel < start and 'latching' in m.connection_header and m.connection_header['latching'] == b'1':
102+
if t_rel < start and 'latching' in connection_header and connection_header['latching'] == b'1':
99103
# latched message before start; save and insert it later
100104
latched_messages_before_start.append(m)
101105
elif t_rel >= start and (t_rel < end or end < 0):
@@ -106,4 +110,4 @@ def debayer_blur_and_rectify_image(msg_image, topic):
106110
connection_header=m_latched.connection_header) # using timestamp of m to avoid gap
107111

108112
# write message
109-
output_bag.write(topic, msg, m.timestamp, connection_header=m.connection_header)
113+
output_bag.write(topic, msg, m.timestamp, connection_header=connection_header)

0 commit comments

Comments
 (0)