-
Notifications
You must be signed in to change notification settings - Fork 44
/
data2rosbag.py
192 lines (152 loc) · 7.47 KB
/
data2rosbag.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
#!/usr/bin/python
import argparse
from recording_pb2 import VideoCaptureData
import os.path as osp
import os
import cv2
import csv
import rosbag
import rospy
from sensor_msgs.msg import Image
from sensor_msgs.msg import Imu
from cv_bridge import CvBridge
from pyquaternion import Quaternion
import numpy as np
import shutil
import yaml
from utils import OpenCVDumper
import time
class VideoFinishedException(Exception):
pass
bridge = CvBridge()
NSECS_IN_SEC=long(1e9)
def convert_to_bag(proto, video_path, result_path, subsample=1, compress_img=False, compress_bag=False, resize = [], raw_imu =False):
#Init rosbag
# bz2 is better compression but lz4 is 3 times faster
resolution = None
img_topic = "/cam0/image_raw/compressed" if compress_img else "/cam0/image_raw"
try:
bag = rosbag.Bag(result_path, 'w', compression='lz4' if compress_bag else 'none')
# Open video stream
try:
cap = cv2.VideoCapture(video_path)
# Generate images from video and frame data
for frame_data in proto.video_meta:
# Read video frames until we find correct number
while True:
video_frame_idx = int(cap.get(cv2.CAP_PROP_POS_FRAMES))
ret, frame = cap.read()
if not ret:
raise VideoFinishedException()
if video_frame_idx==frame_data.frame_number and (video_frame_idx % subsample) == 0:
# Correct frame and subsample index
rosimg, timestamp, resolution = img_to_rosimg(frame,
frame_data.time_ns,
compress=compress_img,
resize = resize)
bag.write(img_topic, rosimg, timestamp)
# Go to next data frame
break
elif video_frame_idx==frame_data.frame_number:
#Skipping subsample
break
elif video_frame_idx < frame_data.frame_number:
print('skipping frame {}, missing data'.format(video_frame_idx))
else:
raise NotImplementedError('Missing video frame idx is not supported and not expected. \
Video frame idx {} > frame_data.frame_number {}'.format(video_frame_idx, frame_data.frame_number))
except VideoFinishedException:
# Nothing to worry about, video stream ended.
pass
finally:
cap.release()
# Now IMU
for imu_frame in proto.imu:
if not raw_imu:
gyro_drift = getattr(imu_frame, 'gyro_drift', np.zeros(3))
accel_bias = getattr(imu_frame, 'accel_bias', np.zeros(3))
else:
gyro_drift = accel_bias = np.zeros(3)
rosimu, timestamp = imu_to_rosimu(imu_frame.time_ns, imu_frame.gyro, gyro_drift, imu_frame.accel, accel_bias)
bag.write("/imu0", rosimu, timestamp)
finally:
bag.close()
return resolution
def img_to_rosimg(img, timestamp_nsecs, compress = True, resize = []):
timestamp = rospy.Time(secs=timestamp_nsecs//NSECS_IN_SEC,
nsecs=timestamp_nsecs%NSECS_IN_SEC)
gray_img = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
if resize:
gray_img = cv2.resize(gray_img, tuple(resize), cv2.INTER_AREA)
assert gray_img.shape[0] == resize[1]
if compress:
rosimage = bridge.cv2_to_compressed_imgmsg(gray_img, dst_format='png')
else:
rosimage = bridge.cv2_to_imgmsg(gray_img, encoding="mono8")
rosimage.header.stamp = timestamp
return rosimage, timestamp, (gray_img.shape[1], gray_img.shape[0])
def imu_to_rosimu(timestamp_nsecs, omega, omega_drift, alpha, alpha_bias):
timestamp = rospy.Time(secs=timestamp_nsecs//NSECS_IN_SEC,
nsecs=timestamp_nsecs%NSECS_IN_SEC)
rosimu = Imu()
rosimu.header.stamp = timestamp
rosimu.angular_velocity.x = omega[0] - omega_drift[0]
rosimu.angular_velocity.y = omega[1] - omega_drift[1]
rosimu.angular_velocity.z = omega[2] - omega_drift[2]
rosimu.linear_acceleration.x = alpha[0] - alpha_bias[0]
rosimu.linear_acceleration.y = alpha[1] - alpha_bias[1]
rosimu.linear_acceleration.z = alpha[2] - alpha_bias[2]
return rosimu, timestamp
def adjust_calibration(input_yaml_path, output_yaml_path, resolution):
with open(input_yaml_path,'r') as f:
calib = yaml.safe_load(f)
cam0 = calib['cam0']
if cam0['resolution'][0] != resolution[0]:
sx = float(resolution[0])/cam0['resolution'][0]
cam0['intrinsics'][0] *= sx
cam0['intrinsics'][2] *= sx
cam0['resolution'][0] = resolution[0]
if cam0['resolution'][1] != resolution[1]:
sy = float(resolution[1])/cam0['resolution'][1]
cam0['intrinsics'][1] *= sy
cam0['intrinsics'][3] *= sy
cam0['resolution'][1] = resolution[1]
with open(output_yaml_path,'w') as f:
yaml.dump(calib, f, Dumper=OpenCVDumper)
def _makedir(new_dir):
try:
os.mkdir(new_dir)
except OSError:
pass
if __name__ == "__main__":
parser = argparse.ArgumentParser(description='Convert video and proto to rosbag')
parser.add_argument('data_dir', type=str, help='Path to folder with video_recording.mp4 and video_meta.pb3 or root-folder containing multiple datasets')
parser.add_argument('--result-dir', type=str, help='Path to result folder, default same as proto', default = None)
parser.add_argument('--subsample', type=int, help='Take every n-th video frame', default = 1)
parser.add_argument('--raw-image', action='store_true', help='Store raw images in rosbag')
parser.add_argument('--resize', type=int, nargs = 2, default = [], help='Resize image to this <width height>')
parser.add_argument('--raw-imu', action='store_true', help='Do not compensate for bias')
parser.add_argument('--calibration', type=str, help='YAML file with kalibr camera and IMU calibration to copy, will also adjust for difference in resolution.', default = None)
args = parser.parse_args()
for root, dirnames, filenames in os.walk(args.data_dir):
if not 'video_meta.pb3' in filenames:
continue
sub_path = '' if osp.samefile(root, args.data_dir) else osp.relpath(root,start=args.data_dir)
result_dir = osp.join(args.result_dir, sub_path) if args.result_dir else osp.join(root, 'rosbag')
_makedir(result_dir)
# Read proto
proto_path = osp.join(root, 'video_meta.pb3')
with open(proto_path,'rb') as f:
proto = VideoCaptureData.FromString(f.read())
video_path = osp.join(root, 'video_recording.mp4')
bag_path = osp.join(result_dir, 'data.bag')
resolution = convert_to_bag(proto,
video_path,
bag_path,
subsample = args.subsample,
compress_img = not args.raw_image,
resize = args.resize,
raw_imu = args.raw_imu)
if args.calibration:
out_path = osp.join(result_dir, 'calibration.yaml')
adjust_calibration(args.calibration, out_path, resolution)