@@ -25,14 +25,14 @@ def generate_rectify_map(cam_model):
25
25
26
26
27
27
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 )
30
30
# try to rectify image if camera info is already available
31
31
try :
32
32
cv_image_rectified = cv .remap (cv_image , rectify_maps [topic ], None , cv .INTER_CUBIC )
33
33
except KeyError :
34
34
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 " )
36
36
out .header = msg_image .header
37
37
return out
38
38
@@ -72,6 +72,9 @@ def debayer_blur_and_rectify_image(msg_image, topic):
72
72
bar = progressbar .ProgressBar (input_bag .get_message_count ())
73
73
for m in bar (input_bag .read_messages (return_connection_header = True )):
74
74
75
+ # copy connection header
76
+ connection_header = m .connection_header
77
+
75
78
# calculate the relative time delta between current and first message
76
79
if record_stamp_of_first_msg is None :
77
80
record_stamp_of_first_msg = m .timestamp
@@ -81,21 +84,22 @@ def debayer_blur_and_rectify_image(msg_image, topic):
81
84
if m .topic in topic_whitelist :
82
85
83
86
# 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 :
85
88
model = PinholeCameraModel ()
86
89
model .fromCameraInfo (m .message )
87
90
rectify_maps [m .topic .replace ("/camera_info" , "" )] = generate_rectify_map (model )
88
91
89
92
# 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 (
91
94
'image_raw' ):
92
95
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
94
98
else :
95
99
msg = m .message
96
100
topic = m .topic
97
101
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' :
99
103
# latched message before start; save and insert it later
100
104
latched_messages_before_start .append (m )
101
105
elif t_rel >= start and (t_rel < end or end < 0 ):
@@ -106,4 +110,4 @@ def debayer_blur_and_rectify_image(msg_image, topic):
106
110
connection_header = m_latched .connection_header ) # using timestamp of m to avoid gap
107
111
108
112
# 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