-
Notifications
You must be signed in to change notification settings - Fork 4
/
my_convert.py
216 lines (180 loc) · 8.13 KB
/
my_convert.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
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
import rosbag
import rospy
from std_msgs.msg import Int32, String
from sensor_msgs.msg import LaserScan
from geometry_msgs.msg import TransformStamped
import math
import tf
from tf2_msgs.msg import TFMessage
import numpy as np
def convert_carmen(fpath, out_name):
bag = rosbag.Bag('src/sparse_gslam/bags/%s.bag' % out_name, 'w')
with open(fpath, "r") as f:
message = []
for line in f.readlines():
if line.startswith("FLASER"):
line = line.split(" ")[1:]
laser_scan = LaserScan()
laser_scan.header.frame_id = "base_link"
laser_scan.angle_min = math.radians(-90)
laser_scan.angle_max = math.radians(90)
laser_scan.range_min = 0.0
laser_scan.range_max = 4.0
num_readings = int(line[0])
laser_scan.angle_increment = math.pi / num_readings
for i in range(1, num_readings + 1):
f = float(line[i])
if f >= 10:
laser_scan.ranges.append(float('nan'))
else:
laser_scan.ranges.append(f)
i += 1
trans = TransformStamped()
trans.header.frame_id = "odom"
trans.child_frame_id = "base_link"
trans.transform.translation.x = float(line[i+3])
trans.transform.translation.y = float(line[i+4])
trans.transform.translation.z = 0
quat = tf.transformations.quaternion_from_euler(0.0, 0.0, float(line[i+5]))
trans.transform.rotation.x = quat[0]
trans.transform.rotation.y = quat[1]
trans.transform.rotation.z = quat[2]
trans.transform.rotation.w = quat[3]
timestamp = float(line[i+6])
trans.header.stamp = laser_scan.header.stamp = rospy.Time(timestamp)
tf_msg = TFMessage()
tf_msg.transforms.append(trans)
message.append((timestamp, tf_msg, laser_scan))
message.sort(key=lambda x: x[0])
print(len(message))
for i, (_, tf_msg, laser_scan) in enumerate(message):
tf_msg.transforms[0].header.seq = i
laser_scan.header.seq = i
bag.write("tf", tf_msg, laser_scan.header.stamp)
bag.write("scan", laser_scan, laser_scan.header.stamp)
bag.close()
def convert_carmen_bspline(fpath, out_name):
with open(fpath, "r") as f:
with open(out_name, 'w') as f2:
for line in f.readlines():
if line.startswith("FLASER"):
line = line.split(" ")[1:]
message = []
timestamp = line[-1].strip()
num_readings = int(line[0])
laser_scan = []
for i in range(1, num_readings + 1):
laser_tmp = line[i]
laser_scan.append(laser_tmp)
i += 1
odomx = line[i+3]
odomy = line[i+4]
odomt = line[i+5]
message.append(timestamp)
message.append(odomx)
message.append(odomy)
message.append(odomt)
message.extend(laser_scan)
message = " ".join(message)
message = message + "\n"
f2.write(message)
def convert_radish(fpath, out_name):
bag = rosbag.Bag('src/sparse_gslam/bags/%s.bag' % out_name, 'w')
with open(fpath, "r") as f:
seq = 0
for line in f.readlines():
if line.startswith("position"):
line = line.split(" ")[3:]
last_x = float(line[0])
last_y = float(line[1])
last_theta = float(line[2])
elif line.startswith("laser"):
line = line.split(" ")
tstamp = float(line[2])
line = line[3:-1]
laser_scan = LaserScan()
laser_scan.header.frame_id = "base_link"
laser_scan.angle_min = math.radians(-90)
laser_scan.angle_max = math.radians(90)
laser_scan.angle_increment = math.radians(1)
laser_scan.range_min = 0.0
laser_scan.range_max = 4.0
num_readings = 181
for i in range(num_readings):
laser_scan.ranges.append(float(line[3 * i]))
trans = TransformStamped()
trans.header.frame_id = "odom"
trans.child_frame_id = "base_link"
trans.transform.translation.x = last_x
trans.transform.translation.y = last_y
trans.transform.translation.z = 0
quat = tf.transformations.quaternion_from_euler(0.0, 0.0, last_theta)
trans.transform.rotation.x = quat[0]
trans.transform.rotation.y = quat[1]
trans.transform.rotation.z = quat[2]
trans.transform.rotation.w = quat[3]
trans.header.stamp = laser_scan.header.stamp = rospy.Time(tstamp)
trans.header.seq = laser_scan.header.seq = seq
tf_msg = TFMessage()
tf_msg.transforms.append(trans)
bag.write("tf", tf_msg, trans.header.stamp)
bag.write("scan", laser_scan, trans.header.stamp)
seq += 1
bag.close()
def convert_stanford_gates(fpath, out_name):
bag = rosbag.Bag('src/sparse_gslam/bags/%s.bag' % out_name, 'w')
with open(fpath, "r") as f:
seq = 0
last_x = -1e10
for line in f.readlines():
if line.startswith("#"):
continue
line = line.split()[3:]
if line[0] == "position":
line = line[3:]
last_x = float(line[0])
last_y = float(line[1])
last_theta = float(line[2])
elif line[0] == "laser":
if last_x == -1e10:
continue
tstamp = float(line[2])
line = line[7:]
# print(len(line), line[-1])
# break
laser_scan = LaserScan()
laser_scan.header.frame_id = "base_link"
laser_scan.angle_min = math.radians(-90)
laser_scan.angle_max = math.radians(90)
laser_scan.angle_increment = math.radians(1)
laser_scan.range_min = 0.0
laser_scan.range_max = 4.0
num_readings = 181
for i in range(num_readings):
laser_scan.ranges.append(float(line[2 * i]))
trans = TransformStamped()
trans.header.frame_id = "odom"
trans.child_frame_id = "base_link"
trans.transform.translation.x = last_x
trans.transform.translation.y = last_y
trans.transform.translation.z = 0
quat = tf.transformations.quaternion_from_euler(0.0, 0.0, last_theta)
trans.transform.rotation.x = quat[0]
trans.transform.rotation.y = quat[1]
trans.transform.rotation.z = quat[2]
trans.transform.rotation.w = quat[3]
trans.header.stamp = laser_scan.header.stamp = rospy.Time(tstamp)
trans.header.seq = laser_scan.header.seq = seq
tf_msg = TFMessage()
tf_msg.transforms.append(trans)
bag.write("tf", tf_msg, trans.header.stamp)
bag.write("scan", laser_scan, trans.header.stamp)
seq += 1
last_x = -1e10
bag.close()
if __name__ == "__main__":
# convert_radish("run02.log", "usc-sal200-021120")
# convert_stanford_gates("stanford-gates1.log", "stanford-gates1")
convert_carmen("fr079.txt", "fr079")
# convert_carmen_bspline("fr079.txt", "fr079-spline.log")
# convert_carmen("mit-csail.clf", "mit-csail")