-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcal_gui.py
385 lines (315 loc) · 13.6 KB
/
cal_gui.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
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
"""
cal_gui.py - Calibration GUI for FreeIMU boards
Copyright (C) 2012 Fabio Varesano <fabio at varesano dot net>
Development of this code has been supported by the Department of Computer Science,
Universita' degli Studi di Torino, Italy within the Piemonte Project
http://www.piemonte.di.unito.it/
This program is free software: you can redistribute it and/or modify
it under the terms of the version 3 GNU General Public License as
published by the Free Software Foundation.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Modification made by Nathan Fourniol to adapt the code to ROS
"""
import sys, os
from PyQt4.QtGui import QApplication, QDialog, QMainWindow, QCursor, QFileDialog
from ui_freeimu_cal import Ui_FreeIMUCal
from PyQt4.QtCore import Qt, QObject, pyqtSlot, QThread, QSettings, SIGNAL, QTimer
import numpy as np
import time
from struct import unpack, pack
from binascii import unhexlify
from subprocess import call
import pyqtgraph.opengl as gl
import cal_lib, numpy
import rospy
from sensor_msgs.msg import Imu
from sensor_msgs.msg import MagneticField
acc_file_name = "acc.txt"
magn_file_name = "magn.txt"
print(acc_file_name, magn_file_name)
calibration_h_file_name = "calibration.json"
acc_range = 25000
magn_range = 1002
class FreeIMUCal(QMainWindow, Ui_FreeIMUCal):
def __init__(self):
QMainWindow.__init__(self)
# Set up the user interface from Designer.
self.setupUi(self)
# load user settings
self.settings = QSettings("FreeIMU Calibration Application", "Fabio Varesano")
# Connect up the buttons to their functions
self.connectButton.clicked.connect(self.ros_connect)
self.samplingToggleButton.clicked.connect(self.sampling_start)
#Setup for storing data
self.rate = rospy.Rate(4)
self.imu = Imu()
self.imu_mag = MagneticField()
self.imu_sub = None
self.magn_sub = None
self.accfile = None
self.magfile = None
self.timer = QTimer()
self.timer.timeout.connect(self.acquire)
self.timer.setInterval(10)
# data storages
self.acc_data = [[], [], []]
self.magn_data = [[], [], []]
# setup graphs
self.accXY.setXRange(-acc_range, acc_range)
self.accXY.setYRange(-acc_range, acc_range)
self.accYZ.setXRange(-acc_range, acc_range)
self.accYZ.setYRange(-acc_range, acc_range)
self.accZX.setXRange(-acc_range, acc_range)
self.accZX.setYRange(-acc_range, acc_range)
self.accXY.setAspectLocked()
self.accYZ.setAspectLocked()
self.accZX.setAspectLocked()
self.magnXY.setXRange(-magn_range, magn_range)
self.magnXY.setYRange(-magn_range, magn_range)
self.magnYZ.setXRange(-magn_range, magn_range)
self.magnYZ.setYRange(-magn_range, magn_range)
self.magnZX.setXRange(-magn_range, magn_range)
self.magnZX.setYRange(-magn_range, magn_range)
self.magnXY.setAspectLocked()
self.magnYZ.setAspectLocked()
self.magnZX.setAspectLocked()
self.accXY_cal.setXRange(-1.5, 1.5)
self.accXY_cal.setYRange(-1.5, 1.5)
self.accYZ_cal.setXRange(-1.5, 1.5)
self.accYZ_cal.setYRange(-1.5, 1.5)
self.accZX_cal.setXRange(-1.5, 1.5)
self.accZX_cal.setYRange(-1.5, 1.5)
self.accXY_cal.setAspectLocked()
self.accYZ_cal.setAspectLocked()
self.accZX_cal.setAspectLocked()
self.magnXY_cal.setXRange(-1.5, 1.5)
self.magnXY_cal.setYRange(-1.5, 1.5)
self.magnYZ_cal.setXRange(-1.5, 1.5)
self.magnYZ_cal.setYRange(-1.5, 1.5)
self.magnZX_cal.setXRange(-1.5, 1.5)
self.magnZX_cal.setYRange(-1.5, 1.5)
self.magnXY_cal.setAspectLocked()
self.magnYZ_cal.setAspectLocked()
self.magnZX_cal.setAspectLocked()
self.acc3D.opts['distance'] = 30000
self.acc3D.show()
self.magn3D.opts['distance'] = 2000
self.magn3D.show()
ax = gl.GLAxisItem()
ax.setSize(x=20000, y=20000, z=20000)
self.acc3D.addItem(ax)
mx = gl.GLAxisItem()
mx.setSize(x=1000, y=1000, z=1000)
self.magn3D.addItem(ax)
self.acc3D_sp = gl.GLScatterPlotItem()
self.acc3D.addItem(self.acc3D_sp)
self.magn3D_sp = gl.GLScatterPlotItem()
self.magn3D.addItem(self.magn3D_sp)
# axis for the cal 3D graph
g_a = gl.GLAxisItem()
g_a.setSize(x=10000, y=10000, z=10000)
self.acc3D_cal.addItem(g_a)
g_m = gl.GLAxisItem()
g_m.setSize(x=1000, y=1000, z=1000)
self.magn3D_cal.addItem(g_m)
def ros_connect(self):
self.imuTopic = str(self.imuTopicEdit.text())
self.magnTopic = str(self.magnTopicEdit.text())
self.connectButton.setEnabled(False)
# waiting mouse cursor
QApplication.setOverrideCursor(QCursor(Qt.WaitCursor))
try :
self.imu_sub = rospy.Subscriber(self.imuTopic, Imu, self._callback_imu)
self.magn_sub = rospy.Subscriber(self.magnTopic, MagneticField, self._callback_magn)
self.imuTopicEdit.setEnabled(False)
self.magnTopicEdit.setEnabled(False)
self.connectButton.setText("Disconnect")
self.connectButton.clicked.disconnect(self.ros_connect)
self.connectButton.clicked.connect(self.ros_disconnect)
self.samplingToggleButton.setEnabled(True)
except :
print('Subscribing to {} or {} failed'.format(self.imuTopic, self.magnTopic))
self.imuTopicEdit.setEnabled(True)
self.magnTopicEdit.setEnabled(True)
self.connectButton.setText("Connect")
self.connectButton.clicked.disconnect(self.ros_disconnect)
self.connectButton.clicked.connect(self.ros_connect)
self.samplingToggleButton.setEnabled(False)
# restore mouse cursor
QApplication.restoreOverrideCursor()
self.connectButton.setEnabled(True)
def ros_disconnect(self):
self.imu_sub.unregister()
self.magn_sub.unregister()
self.sampling_end()
self.calibrateButton.setEnabled(False)
self.calAlgorithmComboBox.setEnabled(False)
self.calibrateButton.clicked.disconnect(self.calibrate)
self.imuTopicEdit.setEnabled(True)
self.magnTopicEdit.setEnabled(True)
self.connectButton.setText("Connect")
self.connectButton.clicked.disconnect(self.ros_disconnect)
self.connectButton.clicked.connect(self.ros_connect)
self.samplingToggleButton.setEnabled(False)
def _callback_imu(self, msg):
"""
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[9] orientation_covariance
geometry_msgs/Vector3 angular_velocity
float64 x
float64 y
float64 z
float64[9] angular_velocity_covariance
geometry_msgs/Vector3 linear_acceleration
float64 x
float64 y
float64 z
float64[9] linear_acceleration_covariance
"""
self.imu = msg
def _callback_magn(self, msg):
"""
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Vector3 magnetic_field
float64 x
float64 y
float64 z
float64[9] magnetic_field_covariance
"""
self.imu_mag = msg
def acquire(self):
scale = 1e3
reading = [self.imu.linear_acceleration.x*scale,
self.imu.linear_acceleration.y*scale,
self.imu.linear_acceleration.z*scale,
self.imu_mag.magnetic_field.x*scale,
self.imu_mag.magnetic_field.y*scale,
self.imu_mag.magnetic_field.z*scale]
self.accfile.write("{} {} {}\n".format(reading[0], reading[1], reading[2]))
self.magfile.write("{} {} {}\n".format(reading[3], reading[4], reading[5]))
print("reading : {}".format(reading))
self.newData(reading)
def sampling_start(self):
self.samplingToggleButton.setText("Stop Sampling")
self.accfile = open(acc_file_name, "w")
self.magfile = open(magn_file_name, "w")
self.timer.start()
self.samplingToggleButton.clicked.disconnect(self.sampling_start)
self.samplingToggleButton.clicked.connect(self.sampling_end)
def sampling_end(self):
self.samplingToggleButton.setText("Start Sampling")
try :
self.samplingToggleButton.clicked.disconnect(self.sampling_end)
self.samplingToggleButton.clicked.connect(self.sampling_start)
self.accfile.close()
self.magfile.close()
self.timer.stop()
except Exception as e:
print('Error : {}'.format(e))
self.calibrateButton.setEnabled(True)
self.calAlgorithmComboBox.setEnabled(True)
self.calibrateButton.clicked.connect(self.calibrate)
def calibrate(self):
# read file and run calibration algorithm
(self.acc_offset, self.acc_scale) = cal_lib.calibrate_from_file(acc_file_name)
(self.magn_offset, self.magn_scale) = cal_lib.calibrate_from_file(magn_file_name)
# map floats into integers
self.acc_offset = map(int, self.acc_offset)
self.magn_offset = map(int, self.magn_offset)
# show calibrated tab
self.tabWidget.setCurrentIndex(1)
#populate acc calibration output on gui
self.calRes_acc_OSx.setText(str(self.acc_offset[0]))
self.calRes_acc_OSy.setText(str(self.acc_offset[1]))
self.calRes_acc_OSz.setText(str(self.acc_offset[2]))
self.calRes_acc_SCx.setText(str(self.acc_scale[0]))
self.calRes_acc_SCy.setText(str(self.acc_scale[1]))
self.calRes_acc_SCz.setText(str(self.acc_scale[2]))
#populate acc calibration output on gui
self.calRes_magn_OSx.setText(str(self.magn_offset[0]))
self.calRes_magn_OSy.setText(str(self.magn_offset[1]))
self.calRes_magn_OSz.setText(str(self.magn_offset[2]))
self.calRes_magn_SCx.setText(str(self.magn_scale[0]))
self.calRes_magn_SCy.setText(str(self.magn_scale[1]))
self.calRes_magn_SCz.setText(str(self.magn_scale[2]))
# compute calibrated data
self.acc_cal_data = cal_lib.compute_calibrate_data(self.acc_data, self.acc_offset, self.acc_scale)
self.magn_cal_data = cal_lib.compute_calibrate_data(self.magn_data, self.magn_offset, self.magn_scale)
# populate 2D graphs with calibrated data
self.accXY_cal.plot(x = self.acc_cal_data[0], y = self.acc_cal_data[1], clear = True, pen='r')
self.accYZ_cal.plot(x = self.acc_cal_data[1], y = self.acc_cal_data[2], clear = True, pen='g')
self.accZX_cal.plot(x = self.acc_cal_data[2], y = self.acc_cal_data[0], clear = True, pen='b')
self.magnXY_cal.plot(x = self.magn_cal_data[0], y = self.magn_cal_data[1], clear = True, pen='r')
self.magnYZ_cal.plot(x = self.magn_cal_data[1], y = self.magn_cal_data[2], clear = True, pen='g')
self.magnZX_cal.plot(x = self.magn_cal_data[2], y = self.magn_cal_data[0], clear = True, pen='b')
# populate 3D graphs with calibrated data
acc3D_cal_data = np.array(self.acc_cal_data).transpose()
magn3D_cal_data = np.array(self.magn_cal_data).transpose()
sp = gl.GLScatterPlotItem(pos=acc3D_cal_data, color = (1, 1, 1, 1), size=2)
self.acc3D_cal.addItem(sp)
sp = gl.GLScatterPlotItem(pos=magn3D_cal_data, color = (1, 1, 1, 1), size=2)
self.magn3D_cal.addItem(sp)
#enable calibration buttons to activate calibration storing functions
self.saveCalibrationHeaderButton.setEnabled(True)
self.saveCalibrationHeaderButton.clicked.connect(self.save_calibration_header)
def save_calibration_header(self):
# **_off_** : int, *_scale_* : float
text = """{
"acc_off_x" : %d,
"acc_off_y" : %d,
"acc_off_z" : %d,
"acc_scale_x" : %f,
"acc_scale_y" : %f,
"acc_scale_z" : %f,
"magn_off_x" : %d,
"magn_off_y" : %d,
"magn_off_z" : %d,
"magn_scale_x" : %f,
"magn_scale_y" : %f,
"magn_scale_z" : %f,
}
"""
calibration_h_text = text % (self.acc_offset[0], self.acc_offset[1], self.acc_offset[2], self.acc_scale[0], self.acc_scale[1], self.acc_scale[2], self.magn_offset[0], self.magn_offset[1], self.magn_offset[2], self.magn_scale[0], self.magn_scale[1], self.magn_scale[2])
calibration_h_folder = QFileDialog.getExistingDirectory(self, "Select the Folder to which save the calibration.h file")
calibration_h_file = open(os.path.join(str(calibration_h_folder), calibration_h_file_name), "w")
calibration_h_file.write(calibration_h_text)
calibration_h_file.close()
def newData(self, reading):
# only display last reading in burst
self.acc_data[0].append(reading[0])
self.acc_data[1].append(reading[1])
self.acc_data[2].append(reading[2])
self.magn_data[0].append(reading[3])
self.magn_data[1].append(reading[4])
self.magn_data[2].append(reading[5])
self.accXY.plot(x = self.acc_data[0], y = self.acc_data[1], clear = True, pen='r')
self.accYZ.plot(x = self.acc_data[1], y = self.acc_data[2], clear = True, pen='g')
self.accZX.plot(x = self.acc_data[2], y = self.acc_data[0], clear = True, pen='b')
self.magnXY.plot(x = self.magn_data[0], y = self.magn_data[1], clear = True, pen='r')
self.magnYZ.plot(x = self.magn_data[1], y = self.magn_data[2], clear = True, pen='g')
self.magnZX.plot(x = self.magn_data[2], y = self.magn_data[0], clear = True, pen='b')
acc_pos = numpy.array([self.acc_data[0],self.acc_data[1],self.acc_data[2]]).transpose()
self.acc3D_sp.setData(pos=acc_pos, color = (1, 1, 1, 1), size=2)
magn_pos = numpy.array([self.magn_data[0],self.magn_data[1],self.magn_data[2]]).transpose()
self.magn3D_sp.setData(pos=magn_pos, color = (1, 1, 1, 1), size=2)
app = QApplication(sys.argv)
rospy.init_node('FreeIMU', anonymous=True)
window = FreeIMUCal()
window.show()
sys.exit(app.exec_())