CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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