Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/mavproxy_modules/sitl_calibration.py
9644 views
1
# Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
2
#
3
# This file is free software: you can redistribute it and/or modify it
4
# under the terms of the GNU General Public License as published by the
5
# Free Software Foundation, either version 3 of the License, or
6
# (at your option) any later version.
7
#
8
# This file is distributed in the hope that it will be useful, but
9
# WITHOUT ANY WARRANTY; without even the implied warranty of
10
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
11
# See the GNU General Public License for more details.
12
#
13
# You should have received a copy of the GNU General Public License along
14
# with this program. If not, see <http://www.gnu.org/licenses/>.
15
16
# flake8: noqa
17
18
'''calibration simulation command handling'''
19
20
import math
21
from pymavlink import quaternion
22
import random
23
import time
24
25
from MAVProxy.modules.lib import mp_module
26
27
class CalController(object):
28
def __init__(self, mpstate):
29
self.mpstate = mpstate
30
self.active = False
31
self.reset()
32
33
def reset(self):
34
self.desired_quaternion = None
35
self.general_state = 'idle'
36
self.attitude_callback = None
37
self.desired_quaternion_close_count = 0
38
39
def start(self):
40
self.active = True
41
42
def stop(self):
43
self.reset()
44
self.mpstate.functions.process_stdin('servo set 5 1000')
45
self.active = False
46
47
def normalize_attitude_angle(self, angle):
48
if angle < 0:
49
angle = 2 * math.pi + angle % (-2 * math.pi)
50
angle %= 2 * math.pi
51
if angle > math.pi:
52
return angle % -math.pi
53
return angle
54
55
def set_attitute(self, roll, pitch, yaw, callback=None):
56
roll = self.normalize_attitude_angle(roll)
57
pitch = self.normalize_attitude_angle(pitch)
58
yaw = self.normalize_attitude_angle(yaw)
59
60
self.desired_quaternion = quaternion.Quaternion((roll, pitch, yaw))
61
self.desired_quaternion.normalize()
62
63
scale = 500.0 / math.pi
64
65
roll_pwm = 1500 + int(roll * scale)
66
pitch_pwm = 1500 + int(pitch * scale)
67
yaw_pwm = 1500 + int(yaw * scale)
68
69
self.mpstate.functions.process_stdin('servo set 5 1150')
70
self.mpstate.functions.process_stdin('servo set 6 %d' % roll_pwm)
71
self.mpstate.functions.process_stdin('servo set 7 %d' % pitch_pwm)
72
self.mpstate.functions.process_stdin('servo set 8 %d' % yaw_pwm)
73
74
self.general_state = 'attitude'
75
self.desired_quaternion_close_count = 0
76
77
if callback:
78
self.attitude_callback = callback
79
80
def angvel(self, x, y, z, theta):
81
m = max(abs(x), abs(y), abs(z))
82
if not m:
83
x_pwm = y_pwm = z_pwm = 1500
84
else:
85
x_pwm = 1500 + round((x / m) * 500)
86
y_pwm = 1500 + round((y / m) * 500)
87
z_pwm = 1500 + round((z / m) * 500)
88
89
max_theta = 2 * math.pi
90
if theta < 0:
91
theta = 0
92
elif theta > max_theta:
93
theta = max_theta
94
theta_pwm = 1300 + round((theta / max_theta) * 700)
95
96
self.mpstate.functions.process_stdin('servo set 5 %d' % theta_pwm)
97
self.mpstate.functions.process_stdin('servo set 6 %d' % x_pwm)
98
self.mpstate.functions.process_stdin('servo set 7 %d' % y_pwm)
99
self.mpstate.functions.process_stdin('servo set 8 %d' % z_pwm)
100
101
self.general_state = 'angvel'
102
103
def autonomous_magcal(self):
104
self.mpstate.functions.process_stdin('servo set 5 1250')
105
106
def handle_simstate(self, m):
107
if self.general_state == 'attitude':
108
q = quaternion.Quaternion((m.roll, m.pitch, m.yaw))
109
q.normalize()
110
d1 = abs(self.desired_quaternion.q - q.q)
111
d2 = abs(self.desired_quaternion.q + q.q)
112
if (d1 <= 1e-2).all() or (d2 <= 1e-2).all():
113
self.desired_quaternion_close_count += 1
114
else:
115
self.desired_quaternion_close_count = 0
116
117
if self.desired_quaternion_close_count == 5:
118
self.general_state = 'idle'
119
if callable(self.attitude_callback):
120
self.attitude_callback()
121
self.attitude_callback = None
122
123
def mavlink_packet(self, m):
124
if not self.active:
125
return
126
if m.get_type() == 'SIMSTATE':
127
self.handle_simstate(m)
128
129
130
class AccelcalController(CalController):
131
state_data = {
132
'level': dict(
133
name='Level',
134
attitude=(0, 0, 0),
135
),
136
'LEFT': dict(
137
name='Left side',
138
attitude=(-math.pi / 2, 0, 0),
139
),
140
'RIGHT': dict(
141
name='Right side',
142
attitude=(math.pi / 2, 0, 0),
143
),
144
'DOWN': dict(
145
name='Nose down',
146
attitude=(0, -math.pi / 2, 0),
147
),
148
'UP': dict(
149
name='Nose up',
150
attitude=(0, math.pi / 2, 0),
151
),
152
'BACK': dict(
153
name='Back',
154
attitude=(math.pi, 0, 0),
155
),
156
}
157
158
def __init__(self, mpstate):
159
super(AccelcalController, self).__init__(mpstate)
160
self.state = None
161
162
def reset(self):
163
super(AccelcalController, self).reset()
164
165
def start(self):
166
super(AccelcalController, self).start()
167
if self.state:
168
self.set_side_state(self.state)
169
170
def side_from_msg(self, m):
171
text = str(m.text)
172
if text.startswith('Place '):
173
for side in self.state_data:
174
if side in text:
175
return side
176
return None
177
178
def report_from_msg(self, m):
179
'''Return true if successful, false if failed, None if unknown'''
180
text = str(m.text)
181
if 'Calibration successful' in text:
182
return True
183
elif 'Calibration FAILED' in text:
184
return False
185
return None
186
187
def set_side_state(self, side):
188
self.state = side
189
190
if not self.active:
191
return
192
193
data = self.state_data[side]
194
195
def callback():
196
self.mpstate.console.set_status(
197
name='sitl_accelcal',
198
text='sitl_accelcal: %s ready - Waiting for user input' % data['name'],
199
row=4,
200
fg='blue',
201
)
202
self.mpstate.console.writeln('sitl_accelcal: attitude detected, please press any key..')
203
204
self.mpstate.console.writeln('sitl_accelcal: sending attitude, please wait..')
205
206
roll, pitch, yaw = data['attitude']
207
self.set_attitute(roll, pitch, yaw, callback=callback)
208
209
self.mpstate.console.set_status(
210
name='sitl_accelcal',
211
text='sitl_accelcal: %s - Waiting for attitude' % data['name'],
212
row=4,
213
fg='orange',
214
)
215
216
def mavlink_packet(self, m):
217
super(AccelcalController, self).mavlink_packet(m)
218
219
if m.get_type() != 'STATUSTEXT':
220
return
221
222
side = self.side_from_msg(m)
223
if side:
224
self.set_side_state(side)
225
else:
226
success = self.report_from_msg(m)
227
if success is None:
228
return
229
230
self.state = None
231
if success:
232
self.mpstate.console.set_status(
233
name='sitl_accelcal',
234
text='sitl_accelcal: Calibration successful',
235
row=4,
236
fg='blue',
237
)
238
else:
239
self.mpstate.console.set_status(
240
name='sitl_accelcal',
241
text='sitl_accelcal: Calibration failed',
242
row=4,
243
fg='red',
244
)
245
246
247
class MagcalController(CalController):
248
yaw_increment = math.radians(45)
249
yaw_noise_range = math.radians(5)
250
251
rotation_angspeed = math.pi / 4
252
'''rotation angular speed in rad/s'''
253
rotation_angspeed_noise = math.radians(2)
254
rotation_axes = (
255
(1, 0, 0),
256
(0, 1, 0),
257
(1, 1, 0),
258
)
259
260
full_turn_time = 2 * math.pi / rotation_angspeed
261
262
max_full_turns = 3
263
'''maximum number of full turns to be performed for each initial attitude'''
264
265
def reset(self):
266
super(MagcalController, self).reset()
267
self.yaw = 0
268
self.rotation_start_time = 0
269
self.last_progress = {}
270
self.rotation_axis_idx = 0
271
272
def start(self):
273
super(MagcalController, self).start()
274
self.set_attitute(0, 0, 0, callback=self.next_rot_att_callback)
275
276
def next_rot_att_callback(self):
277
x, y, z = self.rotation_axes[self.rotation_axis_idx]
278
angspeed = self.rotation_angspeed
279
angspeed += random.uniform(-1, 1) * self.rotation_angspeed_noise
280
self.angvel(x, y, z, angspeed)
281
self.rotation_start_time = time.time()
282
283
def next_rotation(self):
284
self.rotation_axis_idx += 1
285
self.rotation_axis_idx %= len(self.rotation_axes)
286
287
if self.rotation_axis_idx == 0:
288
yaw_inc = self.yaw_increment
289
yaw_inc += random.uniform(-1, 1) * self.yaw_noise_range
290
self.yaw = (self.yaw + yaw_inc) % (2 * math.pi)
291
292
self.rotation_start_time = 0
293
self.last_progress = {}
294
self.set_attitute(0, 0, self.yaw, callback=self.next_rot_att_callback)
295
296
def mavlink_packet(self, m):
297
super(MagcalController, self).mavlink_packet(m)
298
299
if not self.active:
300
return
301
302
if m.get_type() == 'MAG_CAL_REPORT':
303
# NOTE: This may be not the ideal way to handle it
304
if m.compass_id in self.last_progress:
305
# this is set to None so we can ensure we don't get
306
# progress reports for completed compasses.
307
self.last_progress[m.compass_id] = None
308
if len(self.last_progress.values()) and all(progress is None for progress in self.last_progress.values()):
309
self.stop()
310
return
311
312
if m.get_type() != 'MAG_CAL_PROGRESS':
313
return
314
315
if not self.rotation_start_time:
316
return
317
318
t = time.time()
319
m.time = t
320
321
if m.compass_id not in self.last_progress:
322
self.last_progress[m.compass_id] = m
323
m.stuck = False
324
return
325
326
last = self.last_progress[m.compass_id]
327
if last is None:
328
raise Exception("Received progress message for completed compass")
329
330
dt = t - self.rotation_start_time
331
if dt > self.max_full_turns * self.full_turn_time:
332
self.next_rotation()
333
return
334
335
if m.completion_pct == last.completion_pct:
336
if m.time - last.time > self.full_turn_time / 2:
337
last.stuck = True
338
else:
339
self.last_progress[m.compass_id] = m
340
m.stuck = False
341
342
for p in self.last_progress.values():
343
if p is not None and not p.stuck:
344
break
345
else:
346
self.next_rotation()
347
348
349
class SitlCalibrationModule(mp_module.MPModule):
350
def __init__(self, mpstate):
351
super(SitlCalibrationModule, self).__init__(mpstate, "sitl_calibration")
352
self.add_command(
353
'sitl_attitude',
354
self.cmd_sitl_attitude,
355
'set the vehicle at the inclination given by ROLL, PITCH and YAW' +
356
' in degrees',
357
)
358
self.add_command(
359
'sitl_angvel',
360
self.cmd_angvel,
361
'apply angular velocity on the vehicle with a rotation axis and a '+
362
'magnitude in degrees/s',
363
)
364
self.add_command(
365
'sitl_accelcal',
366
self.cmd_sitl_accelcal,
367
'actuate on the simulator vehicle for accelerometer calibration',
368
)
369
self.add_command(
370
'sitl_magcal',
371
self.cmd_sitl_magcal,
372
'actuate on the simulator vehicle for magnetometer calibration',
373
)
374
self.add_command(
375
'sitl_autonomous_magcal',
376
self.cmd_sitl_autonomous_magcal,
377
'let the simulating program do the rotations for magnetometer ' +
378
'calibration - basically, continuous rotations over six ' +
379
'calibration poses',
380
)
381
self.add_command(
382
'sitl_stop',
383
self.cmd_sitl_stop,
384
'stop the current calibration control',
385
)
386
387
self.controllers = dict(
388
generic_controller=CalController(mpstate),
389
accelcal_controller=AccelcalController(mpstate),
390
magcal_controller=MagcalController(mpstate),
391
)
392
393
self.current_controller = None
394
395
def set_controller(self, controller):
396
if self.current_controller:
397
self.current_controller.stop()
398
399
controller = self.controllers.get(controller, None)
400
if controller:
401
controller.start()
402
self.current_controller = controller
403
404
def cmd_sitl_attitude(self, args):
405
if len(args) != 3:
406
print('Usage: sitl_attitude <ROLL> <PITCH> <YAW>')
407
return
408
409
try:
410
roll, pitch, yaw = args
411
roll = math.radians(float(roll))
412
pitch = math.radians(float(pitch))
413
yaw = math.radians(float(yaw))
414
except ValueError:
415
print('Invalid arguments')
416
417
self.set_controller('generic_controller')
418
self.current_controller.set_attitute(roll, pitch, yaw)
419
420
def cmd_angvel(self, args):
421
if len(args) != 4:
422
print('Usage: sitl_angvel <AXIS_X> <AXIS_Y> <AXIS_Z> <THETA>')
423
return
424
425
try:
426
x, y, z, theta = args
427
x = float(x)
428
y = float(y)
429
z = float(z)
430
theta = math.radians(float(theta))
431
except ValueError:
432
print('Invalid arguments')
433
434
self.set_controller('generic_controller')
435
self.current_controller.angvel(x, y, z, theta)
436
437
def cmd_sitl_stop(self, args):
438
self.set_controller('generic_controller')
439
440
def cmd_sitl_accelcal(self, args):
441
self.set_controller('accelcal_controller')
442
443
def cmd_sitl_magcal(self, args):
444
self.set_controller('magcal_controller')
445
446
def cmd_sitl_autonomous_magcal(self, args):
447
self.set_controller('generic_controller')
448
self.current_controller.autonomous_magcal()
449
450
def mavlink_packet(self, m):
451
for c in self.controllers.values():
452
c.mavlink_packet(m)
453
454
def init(mpstate):
455
'''initialise module'''
456
return SitlCalibrationModule(mpstate)
457
458