-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcreate_rosbag.py
executable file
·156 lines (116 loc) · 5 KB
/
create_rosbag.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
import glob
import numpy as np
import cv2
import rospy
import rosbag
from cv_bridge import CvBridge, CvBridgeError
from sensor_msgs.msg import PointCloud2, PointField
from sensor_msgs.msg import Image
def get_bin_points(bin_file):
points = np.fromfile(bin_file, dtype=np.float32).reshape(-1, 4)
return points
def get_txt_points(txt_file):
points = np.loadtxt(txt_file, dtype=np.float32)
return points
def get_img(img_file):
img = cv2.imread(img_file)
#img = cv2.cvtColor(img, cv2.COLOR_BGR2RGB)
return img
def arr_to_pc2(np_pc, timestamp=None, frame_id='map'):
'''
Create a sensor_msgs.PointCloud2 from an array of points.
'''
rviz_points = np.copy(np_pc)
msg = PointCloud2()
if timestamp is not None:
msg.header.stamp = timestamp
else:
msg.header.stamp = rospy.Time.now()
msg.header.frame_id = frame_id
msg.height = 1
msg.width = len(rviz_points)
if np_pc.shape[1]==3:
msg.fields = [
PointField('x', 0, PointField.FLOAT32, 1),
PointField('y', 4, PointField.FLOAT32, 1),
PointField('z', 8, PointField.FLOAT32, 1)]
msg.is_bigendian = False
msg.point_step = 12
msg.row_step = 12*rviz_points.shape[0]
elif np_pc.shape[1]==4:
msg.fields = [
PointField('x', 0, PointField.FLOAT32, 1),
PointField('y', 4, PointField.FLOAT32, 1),
PointField('z', 8, PointField.FLOAT32, 1),
PointField('intensity', 12, PointField.FLOAT32, 1)]
msg.is_bigendian = False
msg.point_step = 16
msg.row_step = 16*rviz_points.shape[0]
elif np_pc.shape[1]==6:
msg.fields = [
PointField('x', 0, PointField.FLOAT32, 1),
PointField('y', 4, PointField.FLOAT32, 1),
PointField('z', 8, PointField.FLOAT32, 1),
PointField('r', 12, PointField.FLOAT32, 1),
PointField('g', 16, PointField.FLOAT32, 1),
PointField('b', 20, PointField.FLOAT32, 1)
]
msg.is_bigendian = False
msg.point_step = 24
msg.row_step = 24 * rviz_points.shape[0]
else:
None
msg.is_dense = int(np.isfinite(rviz_points).all())
msg.data = np.asarray(rviz_points, np.float32).tostring()
return msg
if __name__=='__main__':
pc_raw_xyzi_dir = '/root/data/SOSLAB/ML/210618/original/raw/lidar/lidar'
pc_raw_xyzrgb_dir = '/root/data/SOSLAB/ML/210618/Yun/xyzrgb_txt/raw/txt'
pc_xyzi_dir = '/root/data/SOSLAB/ML/210618/original/result/lidar/lidar'
pc_xyzrgb_dir = '/root/data/SOSLAB/ML/210618/Yun/xyzrgb_txt/result/txt'
img_dir = '/root/data/SOSLAB/ML/210618/Yun/xyzrgb_txt/result/png'
rospy.init_node('create_rosbag')
bridge = CvBridge()
save_path = '/root/data/SOSLAB/ML/210618/ml.bag'
write_rosbag = rosbag.Bag(save_path, 'w')
list_bin_pc_raw_xyzi = sorted(glob.glob(pc_raw_xyzi_dir+'/*.bin'))
list_txt_pc_raw_xyzrgb = sorted(glob.glob(pc_raw_xyzrgb_dir+'/*.txt'))
list_bin_pc_xyzi = sorted(glob.glob(pc_xyzi_dir+'/*.bin'))
list_txt_pc_xyzrgb = sorted(glob.glob(pc_xyzrgb_dir+'/*.txt'))
list_img = sorted(glob.glob(img_dir+'/*.png'))
print(len(list_bin_pc_raw_xyzi))
print(len(list_txt_pc_raw_xyzrgb))
print(len(list_bin_pc_xyzi))
print(len(list_txt_pc_xyzrgb))
print(len(list_img))
frame_rate = 0.1 # 10hz = 0.1s
start_time = rospy.get_time()
for idx in range(len(list_img)):
print(idx)
print(list_bin_pc_raw_xyzi[idx])
print(list_txt_pc_raw_xyzrgb[idx])
print(list_bin_pc_xyzi[idx])
print(list_txt_pc_xyzrgb[idx])
print(list_img[idx])
print('-----------------------------------')
# get points
pc_raw_xyzi = get_bin_points(list_bin_pc_raw_xyzi[idx])
pc_raw_xyzrgb = get_txt_points(list_txt_pc_raw_xyzrgb[idx])
pc_raw_xyzrgb[:,3:6] = pc_raw_xyzrgb[:,3:6]/255.0
pc_xyzi = get_bin_points(list_bin_pc_xyzi[idx])
pc_xyzrgb = get_txt_points(list_txt_pc_xyzrgb[idx])
pc_xyzrgb[:,3:6] = pc_xyzrgb[:,3:6]/255.0
# get image
img = get_img(list_img[idx])
cur_time = rospy.Time.from_sec(start_time + frame_rate*idx)
msg_pc_raw_xyzi = arr_to_pc2(pc_raw_xyzi)
msg_pc_raw_xyzrgb = arr_to_pc2(pc_raw_xyzrgb)
msg_pc_xyzi = arr_to_pc2(pc_xyzi)
msg_pc_xyzrgb = arr_to_pc2(pc_xyzrgb)
msg_img = bridge.cv2_to_imgmsg((img))
write_rosbag.write(topic='/soslab_ml/pc_raw_xyzi', msg=msg_pc_raw_xyzi, t=cur_time)
write_rosbag.write(topic='/soslab_ml/pc_raw_xyzrgb', msg=msg_pc_raw_xyzrgb, t=cur_time)
write_rosbag.write(topic='/soslab_ml/pc_xyzi', msg=msg_pc_xyzi, t=cur_time)
write_rosbag.write(topic='/soslab_ml/pc_xyzrgb', msg=msg_pc_xyzrgb, t=cur_time)
write_rosbag.write(topic='/soslab_ml/img_ambient', msg=msg_img, t=cur_time)
write_rosbag.close()