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/autotest/ardusub.py
Views: 1798
1
'''
2
Dive ArduSub in SITL
3
4
Depth of water is 50m, the ground is flat
5
Parameters are in-code defaults plus default_params/sub.parm
6
7
AP_FLAKE8_CLEAN
8
'''
9
10
from __future__ import print_function
11
import os
12
import sys
13
14
from pymavlink import mavutil
15
16
import vehicle_test_suite
17
from vehicle_test_suite import NotAchievedException
18
from vehicle_test_suite import AutoTestTimeoutException
19
from vehicle_test_suite import PreconditionFailedException
20
21
if sys.version_info[0] < 3:
22
ConnectionResetError = AutoTestTimeoutException
23
24
# get location of scripts
25
testdir = os.path.dirname(os.path.realpath(__file__))
26
27
SITL_START_LOCATION = mavutil.location(33.810313, -118.393867, 0, 185)
28
29
30
class Joystick():
31
Pitch = 1
32
Roll = 2
33
Throttle = 3
34
Yaw = 4
35
Forward = 5
36
Lateral = 6
37
38
39
# Values for EK3_MAG_CAL
40
class MagCal():
41
WHEN_FLYING = 0
42
WHEN_MANOEUVRING = 1
43
NEVER = 2
44
AFTER_FIRST_CLIMB = 3
45
ALWAYS = 4
46
47
48
# Values for XKFS.MAG_FUSION
49
class MagFuseSel():
50
NOT_FUSING = 0
51
FUSE_YAW = 1
52
FUSE_MAG = 2
53
54
55
class AutoTestSub(vehicle_test_suite.TestSuite):
56
@staticmethod
57
def get_not_armable_mode_list():
58
return []
59
60
@staticmethod
61
def get_not_disarmed_settable_modes_list():
62
return []
63
64
@staticmethod
65
def get_no_position_not_settable_modes_list():
66
return ["AUTO", "GUIDED", "CIRCLE", "POSHOLD"]
67
68
@staticmethod
69
def get_position_armable_modes_list():
70
return []
71
72
@staticmethod
73
def get_normal_armable_modes_list():
74
return ["ACRO", "ALT_HOLD", "MANUAL", "STABILIZE", "SURFACE"]
75
76
def log_name(self):
77
return "ArduSub"
78
79
def default_speedup(self):
80
'''Sub seems to be race-free'''
81
return 100
82
83
def test_filepath(self):
84
return os.path.realpath(__file__)
85
86
def set_current_test_name(self, name):
87
self.current_test_name_directory = "ArduSub_Tests/" + name + "/"
88
89
def default_mode(self):
90
return 'MANUAL'
91
92
def sitl_start_location(self):
93
return SITL_START_LOCATION
94
95
def default_frame(self):
96
return 'vectored'
97
98
def is_sub(self):
99
return True
100
101
def watch_altitude_maintained(self, delta=0.3, timeout=5.0):
102
"""Watch and wait for the actual altitude to be maintained
103
104
Keyword Arguments:
105
delta {float} -- Maximum altitude range to be allowed from actual point (default: {0.5})
106
timeout {float} -- Timeout time in simulation seconds (default: {5.0})
107
108
Raises:
109
NotAchievedException: Exception when altitude fails to hold inside the time and
110
altitude range
111
"""
112
tstart = self.get_sim_time_cached()
113
previous_altitude = self.mav.recv_match(type='VFR_HUD', blocking=True).alt
114
self.progress('Altitude to be watched: %f' % (previous_altitude))
115
while True:
116
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
117
if self.get_sim_time_cached() - tstart > timeout:
118
self.progress('Altitude hold done: %f' % (previous_altitude))
119
return
120
if abs(m.alt - previous_altitude) > delta:
121
raise NotAchievedException(
122
"Altitude not maintained: want %.2f (+/- %.2f) got=%.2f" %
123
(previous_altitude, delta, m.alt))
124
125
def AltitudeHold(self):
126
"""Test ALT_HOLD mode"""
127
self.wait_ready_to_arm()
128
self.arm_vehicle()
129
self.change_mode('ALT_HOLD')
130
131
msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=5)
132
if msg is None:
133
raise NotAchievedException("Did not get GLOBAL_POSITION_INT")
134
pwm = 1300
135
if msg.relative_alt/1000.0 < -6.0:
136
# need to go up, not down!
137
pwm = 1700
138
self.set_rc(Joystick.Throttle, pwm)
139
self.wait_altitude(altitude_min=-6, altitude_max=-5)
140
self.set_rc(Joystick.Throttle, 1500)
141
142
# let the vehicle settle (momentum / stopping point shenanigans....)
143
self.delay_sim_time(1)
144
145
self.watch_altitude_maintained()
146
147
self.set_rc(Joystick.Throttle, 1000)
148
self.wait_altitude(altitude_min=-20, altitude_max=-19)
149
self.set_rc(Joystick.Throttle, 1500)
150
151
# let the vehicle settle (momentum / stopping point shenanigans....)
152
self.delay_sim_time(1)
153
154
self.watch_altitude_maintained()
155
156
self.set_rc(Joystick.Throttle, 1900)
157
self.wait_altitude(altitude_min=-14, altitude_max=-13)
158
self.set_rc(Joystick.Throttle, 1500)
159
160
# let the vehicle settle (momentum / stopping point shenanigans....)
161
self.delay_sim_time(1)
162
163
self.watch_altitude_maintained()
164
165
self.set_rc(Joystick.Throttle, 1900)
166
self.wait_altitude(altitude_min=-5, altitude_max=-4)
167
self.set_rc(Joystick.Throttle, 1500)
168
169
# let the vehicle settle (momentum / stopping point shenanigans....)
170
self.delay_sim_time(1)
171
self.watch_altitude_maintained()
172
173
# Make sure the code can handle buoyancy changes
174
self.set_parameter("SIM_BUOYANCY", 10)
175
self.watch_altitude_maintained()
176
self.set_parameter("SIM_BUOYANCY", -10)
177
self.watch_altitude_maintained()
178
179
# Make sure that the ROV will dive with a small input down even if there is a 10N buoyancy force upwards
180
self.set_parameter("SIM_BUOYANCY", 10)
181
self.set_rc(Joystick.Throttle, 1350)
182
self.wait_altitude(altitude_min=-6, altitude_max=-5.5)
183
184
self.set_rc(Joystick.Throttle, 1500)
185
self.watch_altitude_maintained()
186
self.disarm_vehicle()
187
188
def RngfndQuality(self):
189
"""Check lua Range Finder quality information flow"""
190
self.context_push()
191
self.context_collect('STATUSTEXT')
192
193
ex = None
194
try:
195
self.set_parameters({
196
"SCR_ENABLE": 1,
197
"RNGFND1_TYPE": 36,
198
"RNGFND1_ORIENT": 25,
199
"RNGFND1_MIN_CM": 10,
200
"RNGFND1_MAX_CM": 5000,
201
})
202
203
self.install_example_script_context("rangefinder_quality_test.lua")
204
205
# These string must match those sent by the lua test script.
206
complete_str = "#complete#"
207
failure_str = "!!failure!!"
208
209
self.reboot_sitl()
210
211
self.wait_statustext(complete_str, timeout=20, check_context=True)
212
found_failure = self.statustext_in_collections(failure_str)
213
214
if found_failure is not None:
215
raise NotAchievedException("RngfndQuality test failed: " + found_failure.text)
216
217
except Exception as e:
218
self.print_exception_caught(e)
219
ex = e
220
221
self.context_pop()
222
223
# restart SITL RF driver
224
self.reboot_sitl()
225
226
if ex:
227
raise ex
228
229
def watch_distance_maintained(self, delta=0.3, timeout=5.0):
230
"""Watch and wait for the rangefinder reading to be maintained"""
231
tstart = self.get_sim_time_cached()
232
previous_distance = self.mav.recv_match(type='RANGEFINDER', blocking=True).distance
233
self.progress('Distance to be watched: %.2f' % previous_distance)
234
while True:
235
m = self.mav.recv_match(type='RANGEFINDER', blocking=True)
236
if self.get_sim_time_cached() - tstart > timeout:
237
self.progress('Distance hold done: %f' % previous_distance)
238
return
239
if abs(m.distance - previous_distance) > delta:
240
raise NotAchievedException(
241
"Distance not maintained: want %.2f (+/- %.2f) got=%.2f" %
242
(previous_distance, delta, m.distance))
243
244
def Surftrak(self):
245
"""Test SURFTRAK mode"""
246
247
if self.get_parameter('RNGFND1_MAX_CM') != 3000.0:
248
raise PreconditionFailedException("RNGFND1_MAX_CM is not %g" % 3000.0)
249
250
# Something closer to Bar30 noise
251
self.context_push()
252
self.set_parameter("SIM_BARO_RND", 0.01)
253
254
self.wait_ready_to_arm()
255
self.arm_vehicle()
256
self.change_mode('MANUAL')
257
258
# Dive to -5m, outside of rangefinder range, will act like ALT_HOLD
259
pwm = 1300 if self.get_altitude(relative=True) > -6 else 1700
260
self.set_rc(Joystick.Throttle, pwm)
261
self.wait_altitude(altitude_min=-6, altitude_max=-5, relative=False, timeout=60)
262
self.set_rc(Joystick.Throttle, 1500)
263
self.delay_sim_time(1)
264
self.context_collect('STATUSTEXT')
265
self.change_mode(21)
266
self.wait_statustext('waiting for a rangefinder reading', check_context=True)
267
self.context_clear_collection('STATUSTEXT')
268
self.watch_altitude_maintained()
269
270
# Move into range, should set a rangefinder target and maintain it
271
self.set_rc(Joystick.Throttle, 1300)
272
self.wait_altitude(altitude_min=-26, altitude_max=-25, relative=False, timeout=60)
273
self.set_rc(Joystick.Throttle, 1500)
274
self.delay_sim_time(4)
275
self.wait_statustext('rangefinder target is', check_context=True)
276
self.context_clear_collection('STATUSTEXT')
277
self.watch_distance_maintained()
278
279
# Move a few meters, should apply a delta and maintain the new rangefinder target
280
self.set_rc(Joystick.Throttle, 1300)
281
self.wait_altitude(altitude_min=-31, altitude_max=-30, relative=False, timeout=60)
282
self.set_rc(Joystick.Throttle, 1500)
283
self.delay_sim_time(4)
284
self.wait_statustext('rangefinder target is', check_context=True)
285
self.watch_distance_maintained()
286
287
self.disarm_vehicle()
288
self.context_pop()
289
290
def prepare_synthetic_seafloor_test(self, sea_floor_depth, rf_target):
291
self.set_parameters({
292
"SCR_ENABLE": 1,
293
"RNGFND1_TYPE": 36,
294
"RNGFND1_ORIENT": 25,
295
"RNGFND1_MIN_CM": 10,
296
"RNGFND1_MAX_CM": 3000,
297
"SCR_USER1": 2, # Configuration bundle
298
"SCR_USER2": sea_floor_depth, # Depth in meters
299
"SCR_USER3": 101, # Output log records
300
"SCR_USER4": rf_target, # Rangefinder target in meters
301
})
302
303
self.install_example_script_context("sub_test_synthetic_seafloor.lua")
304
305
# Reboot to enable scripting.
306
self.reboot_sitl()
307
self.set_rc_default()
308
self.wait_ready_to_arm()
309
310
def watch_true_distance_maintained(self, match_distance, delta=0.3, timeout=5.0, final_waypoint=0):
311
"""Watch and wait for the rangefinder reading to be maintained"""
312
313
def get_true_distance():
314
"""Return the True distance from the simulated range finder"""
315
m_true = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=3.0)
316
if m_true is None:
317
return m_true
318
idx_tr = m_true.text.find('#TR#')
319
if idx_tr < 0:
320
return None
321
return float(m_true.text[(idx_tr+4):(idx_tr+12)])
322
323
tstart = self.get_sim_time_cached()
324
self.progress('Distance to be watched: %.2f (+/- %.2f)' % (match_distance, delta))
325
max_delta = 0.0
326
327
while True:
328
timed_out = self.get_sim_time_cached() - tstart > timeout
329
# If final_waypoint>0 then timeout is failure, otherwise success
330
if timed_out and final_waypoint > 0:
331
raise NotAchievedException(
332
"Mission not complete: want waypoint %i, only made it to waypoint %i" %
333
(final_waypoint, self.mav.waypoint_current()))
334
if timed_out:
335
self.progress('Distance hold done. Max delta:%.2fm' % max_delta)
336
return
337
338
true_distance = get_true_distance()
339
if true_distance is None:
340
continue
341
match_delta = abs(true_distance - match_distance)
342
if match_delta > max_delta:
343
max_delta = match_delta
344
if match_delta > delta:
345
raise NotAchievedException(
346
"Distance not maintained: want %.2f (+/- %.2f) got=%.2f (%.2f)" %
347
(match_distance, delta, true_distance, match_delta))
348
if final_waypoint > 0:
349
if self.mav.waypoint_current() >= final_waypoint:
350
self.progress('Distance hold during mission done. Max delta:%.2fm' % max_delta)
351
return
352
353
def SimTerrainSurftrak(self):
354
"""Move at a constant height above synthetic sea floor"""
355
356
sea_floor_depth = 50 # Depth of sea floor at location of test
357
match_distance = 15 # Desired sub distance from sea floor
358
start_altitude = -sea_floor_depth+match_distance
359
end_altitude = start_altitude - 10
360
validation_delta = 1.5 # Largest allowed distance between sub height and desired height
361
362
self.context_push()
363
self.prepare_synthetic_seafloor_test(sea_floor_depth, match_distance)
364
self.change_mode('MANUAL')
365
self.arm_vehicle()
366
367
# Dive to match_distance off the bottom in preparation for the mission
368
pwm = 1300 if self.get_altitude(relative=True) > start_altitude else 1700
369
self.set_rc(Joystick.Throttle, pwm)
370
self.wait_altitude(altitude_min=start_altitude-1, altitude_max=start_altitude, relative=False, timeout=120)
371
self.set_rc(Joystick.Throttle, 1500)
372
self.delay_sim_time(1)
373
374
# Turn on surftrak and move around
375
self.change_mode(21)
376
377
# Go south over the ridge.
378
self.reach_heading_manual(180)
379
self.set_rc(Joystick.Forward, 1650)
380
self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=60)
381
self.set_rc(Joystick.Forward, 1500)
382
383
# Shift west a bit
384
self.reach_heading_manual(270)
385
self.set_rc(Joystick.Forward, 1650)
386
self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=5)
387
self.set_rc(Joystick.Forward, 1500)
388
389
# Go south over the plateau
390
self.reach_heading_manual(180)
391
self.set_rc(Joystick.Forward, 1650)
392
self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=60)
393
394
# The mission ends at end_altitude. Do a check to ensure that the sub is at this altitude
395
self.wait_altitude(altitude_min=end_altitude-validation_delta/2, altitude_max=end_altitude+validation_delta/2,
396
relative=False, timeout=1)
397
398
self.set_rc(Joystick.Forward, 1500)
399
400
self.disarm_vehicle()
401
self.context_pop()
402
self.reboot_sitl() # e.g. revert rangefinder configuration
403
404
def SimTerrainMission(self):
405
"""Mission at a constant height above synthetic sea floor"""
406
407
sea_floor_depth = 50 # Depth of sea floor at location of test
408
match_distance = 15 # Desired sub distance from sea floor
409
start_altitude = -sea_floor_depth+match_distance
410
end_altitude = start_altitude - 10
411
validation_delta = 1.5 # Largest allowed distance between sub height and desired height
412
413
self.context_push()
414
self.prepare_synthetic_seafloor_test(sea_floor_depth, match_distance)
415
416
# The synthetic seafloor has an east-west ridge south of the sub.
417
# The mission contained in terrain_mission.txt instructs the sub
418
# to remain at 15m above the seafloor and travel south over the
419
# ridge. Then the sub moves west and travels north over the ridge.
420
filename = "terrain_mission.txt"
421
self.load_mission(filename)
422
423
self.change_mode('MANUAL')
424
self.arm_vehicle()
425
426
# Dive to match_distance off the bottom in preparation for the mission
427
pwm = 1300 if self.get_altitude(relative=True) > start_altitude else 1700
428
self.set_rc(Joystick.Throttle, pwm)
429
self.wait_altitude(altitude_min=start_altitude-1, altitude_max=start_altitude, relative=False, timeout=120)
430
self.set_rc(Joystick.Throttle, 1500)
431
self.delay_sim_time(1)
432
433
self.change_mode('AUTO')
434
self.watch_true_distance_maintained(match_distance, delta=validation_delta, timeout=500.0, final_waypoint=4)
435
436
# The mission ends at end_altitude. Do a check to ensure that the sub is at this altitude.
437
self.wait_altitude(altitude_min=end_altitude-validation_delta/2, altitude_max=end_altitude+validation_delta/2,
438
relative=False, timeout=1)
439
440
self.disarm_vehicle()
441
self.context_pop()
442
self.reboot_sitl() # e.g. revert rangefinder configuration
443
444
def ModeChanges(self, delta=0.2):
445
"""Check if alternating between ALTHOLD, STABILIZE, POSHOLD and SURFTRAK (mode 21) affects altitude"""
446
self.wait_ready_to_arm()
447
self.arm_vehicle()
448
# zero buoyancy and no baro noise
449
self.set_parameter("SIM_BUOYANCY", 0)
450
self.set_parameter("SIM_BARO_RND", 0)
451
# dive a bit to make sure we are not surfaced
452
self.change_mode('STABILIZE')
453
self.set_rc(Joystick.Throttle, 1350)
454
self.delay_sim_time(10)
455
self.set_rc(Joystick.Throttle, 1500)
456
self.delay_sim_time(3)
457
# start the test itself, go through some modes and check if anything changes
458
previous_altitude = self.mav.recv_match(type='VFR_HUD', blocking=True).alt
459
self.change_mode('ALT_HOLD')
460
self.delay_sim_time(2)
461
self.change_mode('POSHOLD')
462
self.delay_sim_time(2)
463
self.change_mode('STABILIZE')
464
self.delay_sim_time(2)
465
self.change_mode(21)
466
self.delay_sim_time(2)
467
self.change_mode('ALT_HOLD')
468
self.delay_sim_time(2)
469
self.change_mode('STABILIZE')
470
self.delay_sim_time(2)
471
self.change_mode('ALT_HOLD')
472
self.delay_sim_time(2)
473
self.change_mode(21)
474
self.delay_sim_time(2)
475
self.change_mode('MANUAL')
476
self.disarm_vehicle()
477
final_altitude = self.mav.recv_match(type='VFR_HUD', blocking=True).alt
478
if abs(previous_altitude - final_altitude) > delta:
479
raise NotAchievedException(
480
"Changing modes affected depth with no throttle input!, started at {}, ended at {}"
481
.format(previous_altitude, final_altitude)
482
)
483
484
def PositionHold(self):
485
"""Test POSHOLD mode"""
486
self.wait_ready_to_arm()
487
self.arm_vehicle()
488
# point North
489
self.reach_heading_manual(0)
490
self.change_mode('POSHOLD')
491
492
# dive a little
493
self.set_rc(Joystick.Throttle, 1300)
494
self.delay_sim_time(3)
495
self.set_rc(Joystick.Throttle, 1500)
496
self.delay_sim_time(2)
497
498
# Save starting point
499
msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=5)
500
if msg is None:
501
raise NotAchievedException("Did not get GLOBAL_POSITION_INT")
502
start_pos = self.mav.location()
503
# Hold in perfect conditions
504
self.progress("Testing position hold in perfect conditions")
505
self.delay_sim_time(10)
506
distance_m = self.get_distance(start_pos, self.mav.location())
507
if distance_m > 1:
508
raise NotAchievedException("Position Hold was unable to keep position in calm waters within 1 meter after 10 seconds, drifted {} meters".format(distance_m)) # noqa
509
510
# Hold in 1 m/s current
511
self.progress("Testing position hold in current")
512
self.set_parameter("SIM_WIND_SPD", 1)
513
self.set_parameter("SIM_WIND_T", 1)
514
self.delay_sim_time(10)
515
distance_m = self.get_distance(start_pos, self.mav.location())
516
if distance_m > 1:
517
raise NotAchievedException("Position Hold was unable to keep position in 1m/s current within 1 meter after 10 seconds, drifted {} meters".format(distance_m)) # noqa
518
519
# Move forward slowly in 1 m/s current
520
start_pos = self.mav.location()
521
self.progress("Testing moving forward in position hold in 1m/s current")
522
self.set_rc(Joystick.Forward, 1600)
523
self.delay_sim_time(10)
524
distance_m = self.get_distance(start_pos, self.mav.location())
525
bearing = self.get_bearing(start_pos, self.mav.location())
526
if distance_m < 2 or (bearing > 30 and bearing < 330):
527
raise NotAchievedException("Position Hold was unable to move north 2 meters, moved {} at {} degrees instead".format(distance_m, bearing)) # noqa
528
self.disarm_vehicle()
529
530
def MotorThrustHoverParameterIgnore(self):
531
"""Test if we are ignoring MOT_THST_HOVER parameter"""
532
533
# Test default parameter value
534
mot_thst_hover_value = self.get_parameter("MOT_THST_HOVER")
535
if mot_thst_hover_value != 0.5:
536
raise NotAchievedException("Unexpected default MOT_THST_HOVER parameter value {}".format(mot_thst_hover_value))
537
538
# Test if parameter is being ignored
539
for value in [0.25, 0.75]:
540
self.set_parameter("MOT_THST_HOVER", value)
541
self.AltitudeHold()
542
543
def DiveManual(self):
544
'''Dive manual'''
545
self.wait_ready_to_arm()
546
self.arm_vehicle()
547
548
self.set_rc(Joystick.Throttle, 1600)
549
self.set_rc(Joystick.Forward, 1600)
550
self.set_rc(Joystick.Lateral, 1550)
551
552
self.wait_distance(50, accuracy=7, timeout=200)
553
self.set_rc(Joystick.Yaw, 1550)
554
555
self.wait_heading(0)
556
self.set_rc(Joystick.Yaw, 1500)
557
558
self.wait_distance(50, accuracy=7, timeout=100)
559
self.set_rc(Joystick.Yaw, 1550)
560
561
self.wait_heading(0)
562
self.set_rc(Joystick.Yaw, 1500)
563
self.set_rc(Joystick.Forward, 1500)
564
self.set_rc(Joystick.Lateral, 1100)
565
566
self.wait_distance(75, accuracy=7, timeout=100)
567
self.set_rc_default()
568
569
self.disarm_vehicle()
570
self.progress("Manual dive OK")
571
572
m = self.assert_receive_message('SCALED_PRESSURE3')
573
574
# Note this temperature matches the output of the Atmospheric Model for Air currently
575
# And should be within 1 deg C of 40 degC
576
if (m.temperature < 3900) or (4100 < m.temperature):
577
raise NotAchievedException("Did not get correct TSYS01 temperature: Got %f" % m.temperature)
578
579
def DiveMission(self):
580
'''Dive mission'''
581
filename = "sub_mission.txt"
582
self.progress("Executing mission %s" % filename)
583
self.load_mission(filename)
584
self.set_rc_default()
585
586
self.arm_vehicle()
587
588
self.change_mode('AUTO')
589
590
self.wait_waypoint(1, 5, max_dist=5)
591
592
self.disarm_vehicle()
593
594
self.progress("Mission OK")
595
596
def GripperMission(self):
597
'''Test gripper mission items'''
598
self.load_mission("sub-gripper-mission.txt")
599
self.wait_ready_to_arm()
600
self.arm_vehicle()
601
self.change_mode('AUTO')
602
self.wait_waypoint(1, 2, max_dist=5)
603
self.wait_statustext("Gripper Grabbed", timeout=60)
604
self.wait_waypoint(1, 4, max_dist=5)
605
self.wait_statustext("Gripper Released", timeout=60)
606
self.wait_waypoint(1, 6, max_dist=5)
607
self.disarm_vehicle()
608
609
def SET_POSITION_TARGET_GLOBAL_INT(self):
610
'''Move vehicle using SET_POSITION_TARGET_GLOBAL_INT'''
611
self.change_mode('GUIDED')
612
self.wait_ready_to_arm()
613
self.arm_vehicle()
614
615
startpos = self.mav.recv_match(type='GLOBAL_POSITION_INT',
616
blocking=True)
617
618
lat = 5
619
lon = 5
620
alt = -10
621
622
# send a position-control command
623
self.mav.mav.set_position_target_global_int_send(
624
0, # timestamp
625
1, # target system_id
626
1, # target component id
627
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
628
0b1111111111111000, # mask specifying use-only-lat-lon-alt
629
lat, # lat
630
lon, # lon
631
alt, # alt
632
0, # vx
633
0, # vy
634
0, # vz
635
0, # afx
636
0, # afy
637
0, # afz
638
0, # yaw
639
0, # yawrate
640
)
641
642
tstart = self.get_sim_time()
643
while True:
644
if self.get_sim_time_cached() - tstart > 200:
645
raise NotAchievedException("Did not move far enough")
646
pos = self.mav.recv_match(type='GLOBAL_POSITION_INT',
647
blocking=True)
648
delta = self.get_distance_int(startpos, pos)
649
self.progress("delta=%f (want >10)" % delta)
650
if delta > 10:
651
break
652
self.change_mode('MANUAL')
653
self.disarm_vehicle()
654
655
def DoubleCircle(self):
656
'''Test entering circle twice'''
657
self.change_mode('CIRCLE')
658
self.wait_ready_to_arm()
659
self.arm_vehicle()
660
self.change_mode('STABILIZE')
661
self.change_mode('CIRCLE')
662
self.disarm_vehicle()
663
664
def default_parameter_list(self):
665
ret = super(AutoTestSub, self).default_parameter_list()
666
ret["FS_GCS_ENABLE"] = 0 # FIXME
667
return ret
668
669
def MAV_CMD_NAV_LOITER_UNLIM(self):
670
'''test handling of MAV_CMD_NAV_LOITER_UNLIM received via mavlink'''
671
for cmd in self.run_cmd, self.run_cmd_int:
672
self.change_mode('CIRCLE')
673
cmd(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM)
674
self.assert_mode('POSHOLD')
675
676
def MAV_CMD_NAV_LAND(self):
677
'''test handling of MAV_CMD_NAV_LAND received via mavlink'''
678
for cmd in self.run_cmd, self.run_cmd_int:
679
self.change_mode('CIRCLE')
680
cmd(mavutil.mavlink.MAV_CMD_NAV_LAND)
681
self.assert_mode('SURFACE')
682
683
def MAV_CMD_MISSION_START(self):
684
'''test handling of MAV_CMD_MISSION_START received via mavlink'''
685
self.upload_simple_relhome_mission([
686
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),
687
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
688
])
689
690
self.wait_ready_to_arm()
691
self.arm_vehicle()
692
for cmd in self.run_cmd, self.run_cmd_int:
693
self.change_mode('CIRCLE')
694
cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
695
self.assert_mode('AUTO')
696
self.disarm_vehicle()
697
698
def MAV_CMD_DO_CHANGE_SPEED(self):
699
'''ensure vehicle changes speeds when DO_CHANGE_SPEED received'''
700
items = [
701
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, -3), # Dive so we have constant drag
702
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, -1),
703
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
704
]
705
self.upload_simple_relhome_mission(items)
706
self.wait_ready_to_arm()
707
self.arm_vehicle()
708
self.run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
709
self.progress("SENT MISSION START")
710
self.wait_mode('AUTO')
711
self.wait_current_waypoint(2) # wait after we finish diving to 3m
712
for run_cmd in self.run_cmd, self.run_cmd_int:
713
for speed in [1, 1.5, 0.5]:
714
run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)
715
self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=2, timeout=60)
716
self.disarm_vehicle()
717
718
def _MAV_CMD_CONDITION_YAW(self, run_cmd):
719
self.arm_vehicle()
720
self.change_mode('GUIDED')
721
for angle in 5, 30, 60, 10:
722
angular_rate = 10
723
direction = 1
724
relative_or_absolute = 0
725
run_cmd(
726
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
727
p1=angle,
728
p2=angular_rate,
729
p3=direction,
730
p4=relative_or_absolute, # 1 for relative, 0 for absolute
731
)
732
self.wait_heading(angle, minimum_duration=2)
733
734
self.start_subtest('Relative angle')
735
run_cmd(
736
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
737
p1=0,
738
p2=10,
739
p3=1,
740
p4=0, # 1 for relative, 0 for absolute
741
)
742
self.wait_heading(0, minimum_duration=2)
743
run_cmd(
744
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
745
p1=20,
746
p2=10,
747
p3=1,
748
p4=1, # 1 for relative, 0 for absolute
749
)
750
self.wait_heading(20, minimum_duration=2)
751
752
self.disarm_vehicle()
753
754
def MAV_CMD_CONDITION_YAW(self):
755
'''ensure vehicle yaws according to GCS command'''
756
self._MAV_CMD_CONDITION_YAW(self.run_cmd)
757
self._MAV_CMD_CONDITION_YAW(self.run_cmd_int)
758
759
def MAV_CMD_DO_REPOSITION(self):
760
"""Move vehicle using MAV_CMD_DO_REPOSITION"""
761
self.wait_ready_to_arm()
762
self.arm_vehicle()
763
764
# Dive so that rangefinder is in range, required for MAV_FRAME_GLOBAL_TERRAIN_ALT
765
start_altitude = -25
766
pwm = 1300 if self.get_altitude(relative=True) > start_altitude else 1700
767
self.set_rc(Joystick.Throttle, pwm)
768
self.wait_altitude(altitude_min=start_altitude-1, altitude_max=start_altitude, relative=False, timeout=120)
769
self.set_rc(Joystick.Throttle, 1500)
770
self.change_mode('GUIDED')
771
772
loc = self.mav.location()
773
774
# Reposition, alt relative to surface
775
loc = self.offset_location_ne(loc, 10, 10)
776
loc.alt = start_altitude
777
self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT)
778
self.wait_location(loc, timeout=120)
779
780
# Reposition, alt relative to seafloor
781
loc = self.offset_location_ne(loc, 10, 10)
782
loc.alt = -start_altitude
783
self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
784
self.wait_location(loc, timeout=120)
785
786
self.disarm_vehicle()
787
788
def TerrainMission(self):
789
"""Mission using surface tracking"""
790
791
if self.get_parameter('RNGFND1_MAX_CM') != 3000.0:
792
raise PreconditionFailedException("RNGFND1_MAX_CM is not %g" % 3000.0)
793
794
filename = "terrain_mission.txt"
795
self.progress("Executing mission %s" % filename)
796
self.load_mission(filename)
797
self.set_rc_default()
798
self.arm_vehicle()
799
self.change_mode('AUTO')
800
self.wait_waypoint(1, 4, max_dist=5)
801
self.delay_sim_time(3)
802
803
# Expect sub to hover at final altitude
804
self.assert_altitude(-36.0)
805
806
self.disarm_vehicle()
807
self.progress("Mission OK")
808
809
def wait_ekf_happy_const_pos(self, timeout=45):
810
# All of these must be set for arming to happen in constant position mode:
811
required_value = (mavutil.mavlink.EKF_ATTITUDE |
812
mavutil.mavlink.EKF_VELOCITY_HORIZ |
813
mavutil.mavlink.EKF_VELOCITY_VERT |
814
mavutil.mavlink.EKF_POS_VERT_ABS |
815
mavutil.mavlink.EKF_CONST_POS_MODE)
816
817
# None of these bits must be set for arming to happen:
818
error_bits = mavutil.mavlink.EKF_UNINITIALIZED
819
820
self.wait_ekf_flags(required_value, error_bits, timeout=timeout)
821
822
def wait_ready_to_arm_const_pos(self, timeout=120):
823
self.progress("Waiting for ready to arm (constant position mode)")
824
start = self.get_sim_time()
825
self.wait_ekf_happy_const_pos(timeout=timeout)
826
armable_time = self.get_sim_time() - start
827
self.progress("Took %u seconds to become armable" % armable_time)
828
self.total_waiting_to_arm_time += armable_time
829
self.waiting_to_arm_count += 1
830
831
def collected_msgs(self, msg_type):
832
c = self.context_get()
833
if msg_type not in c.collections:
834
raise NotAchievedException("Not collecting (%s)" % str(msg_type))
835
return c.collections[msg_type]
836
837
def SetGlobalOrigin(self):
838
"""Test SET_GPS_GLOBAL_ORIGIN mav msg"""
839
self.context_push()
840
self.set_parameters({
841
'GPS1_TYPE': 0, # Disable the GPS
842
'EK3_SRC1_POSXY': 0, # Make sure EK3_SRC parameters do not refer to a GPS
843
})
844
self.reboot_sitl()
845
846
# Wait for the EKF to be happy in constant position mode
847
self.wait_ready_to_arm_const_pos()
848
849
if self.current_onboard_log_contains_message('ORGN'):
850
raise NotAchievedException("Found unexpected ORGN message")
851
852
self.context_collect('GPS_GLOBAL_ORIGIN')
853
854
# This should set the EKF origin, write an ORGN msg to df and a GPS_GLOBAL_ORIGIN msg to MAVLink
855
self.mav.mav.set_gps_global_origin_send(1, int(47.607584 * 1e7), int(-122.343911 * 1e7), 0)
856
self.delay_sim_time(1)
857
858
if not self.current_onboard_log_contains_message('ORGN'):
859
raise NotAchievedException("Did not find expected ORGN message")
860
861
num_mavlink_origin_msgs = len(self.collected_msgs('GPS_GLOBAL_ORIGIN'))
862
if num_mavlink_origin_msgs != 1:
863
raise NotAchievedException("Expected 1 GPS_GLOBAL_ORIGIN message, found %d" % num_mavlink_origin_msgs)
864
865
self.context_pop()
866
867
# restart GPS driver
868
self.reboot_sitl()
869
870
def BackupOrigin(self):
871
"""Test ORIGIN_LAT and ORIGIN_LON parameters"""
872
873
self.context_push()
874
self.set_parameters({
875
'GPS1_TYPE': 0, # Disable GPS
876
'EK3_SRC1_POSXY': 0, # Make sure EK3_SRC parameters do not refer to GPS
877
'EK3_SRC1_VELXY': 0, # Make sure EK3_SRC parameters do not refer to GPS
878
'ORIGIN_LAT': 47.607584,
879
'ORIGIN_LON': -122.343911,
880
})
881
self.reboot_sitl()
882
self.context_collect('STATUSTEXT')
883
884
# Wait for the EKF to be happy in constant position mode
885
self.wait_ready_to_arm_const_pos()
886
887
if self.current_onboard_log_contains_message('ORGN'):
888
raise NotAchievedException("Found unexpected ORGN message")
889
890
# This should set the origin and write a record to ORGN
891
self.arm_vehicle()
892
893
self.wait_statustext('Using backup location', check_context=True)
894
895
if not self.current_onboard_log_contains_message('ORGN'):
896
raise NotAchievedException("Did not find expected ORGN message")
897
898
self.disarm_vehicle()
899
self.context_pop()
900
901
def assert_mag_fusion_selection(self, expect_sel):
902
"""Get the most recent XKFS message and check the MAG_FUSION value"""
903
self.progress("Expect mag fusion selection %d" % expect_sel)
904
mlog = self.dfreader_for_current_onboard_log()
905
found_sel = MagFuseSel.NOT_FUSING
906
while True:
907
m = mlog.recv_match(type='XKFS')
908
if m is None:
909
break
910
found_sel = m.MAG_FUSION
911
if found_sel != expect_sel:
912
raise NotAchievedException("Expected mag fusion selection %d, found %d" % (expect_sel, found_sel))
913
914
def FuseMag(self):
915
"""Test EK3_MAG_CAL values"""
916
917
# WHEN_FLYING: switch to FUSE_MAG after sub is armed for 5 seconds; switch to FUSE_YAW on disarm
918
self.set_parameters({'EK3_MAG_CAL': MagCal.WHEN_FLYING})
919
self.reboot_sitl()
920
self.wait_ready_to_arm()
921
self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW)
922
self.arm_vehicle()
923
self.delay_sim_time(10)
924
self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG)
925
self.disarm_vehicle()
926
self.delay_sim_time(1)
927
self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW)
928
929
# AFTER_FIRST_CLIMB: switch to FUSE_MAG after sub is armed and descends 0.5m; switch to FUSE_YAW on disarm
930
self.set_parameters({'EK3_MAG_CAL': MagCal.AFTER_FIRST_CLIMB})
931
self.reboot_sitl()
932
self.wait_ready_to_arm()
933
self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW)
934
altitude = self.get_altitude(relative=True)
935
self.arm_vehicle()
936
self.set_rc(Joystick.Throttle, 1300)
937
self.wait_altitude(altitude_min=altitude-4, altitude_max=altitude-3, relative=False, timeout=60)
938
self.set_rc(Joystick.Throttle, 1500)
939
self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG)
940
self.disarm_vehicle()
941
self.delay_sim_time(1)
942
self.assert_mag_fusion_selection(MagFuseSel.FUSE_YAW)
943
944
# ALWAYS
945
self.set_parameters({'EK3_MAG_CAL': MagCal.ALWAYS})
946
self.reboot_sitl()
947
self.wait_ready_to_arm()
948
self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG)
949
950
def INA3221(self):
951
'''test INA3221 driver'''
952
self.set_parameters({
953
"BATT2_MONITOR": 30,
954
"BATT3_MONITOR": 30,
955
"BATT4_MONITOR": 30,
956
})
957
self.reboot_sitl()
958
self.set_parameters({
959
"BATT2_I2C_ADDR": 0x42, # address defined in libraries/SITL/SIM_I2C.cpp
960
"BATT2_I2C_BUS": 1,
961
"BATT2_CHANNEL": 1,
962
963
"BATT3_I2C_ADDR": 0x42,
964
"BATT3_I2C_BUS": 1,
965
"BATT3_CHANNEL": 2,
966
967
"BATT4_I2C_ADDR": 0x42,
968
"BATT4_I2C_BUS": 1,
969
"BATT4_CHANNEL": 3,
970
})
971
self.reboot_sitl()
972
973
seen_1 = False
974
seen_3 = False
975
tstart = self.get_sim_time()
976
while not (seen_1 and seen_3):
977
m = self.assert_receive_message('BATTERY_STATUS')
978
if self.get_sim_time() - tstart > 10:
979
# expected to take under 1 simulated second, but don't hang if
980
# e.g. the driver gets stuck
981
raise NotAchievedException("INA3221 status timeout")
982
if m.id == 1:
983
self.assert_message_field_values(m, {
984
# values close to chip limits
985
"voltages[0]": int(25 * 1000), # millivolts
986
"current_battery": int(160 * 100), # centi-amps
987
}, epsilon=10) # allow rounding
988
seen_1 = True
989
# id 2 is the first simulated battery current/voltage
990
if m.id == 3:
991
self.assert_message_field_values(m, {
992
# values different from above to test channel switching
993
"voltages[0]": int(3.14159 * 1000), # millivolts
994
"current_battery": int(2.71828 * 100), # centi-amps
995
}, epsilon=10) # allow rounding
996
seen_3 = True
997
998
def tests(self):
999
'''return list of all tests'''
1000
ret = super(AutoTestSub, self).tests()
1001
1002
ret.extend([
1003
self.DiveManual,
1004
self.AltitudeHold,
1005
self.Surftrak,
1006
self.SimTerrainSurftrak,
1007
self.SimTerrainMission,
1008
self.RngfndQuality,
1009
self.PositionHold,
1010
self.ModeChanges,
1011
self.DiveMission,
1012
self.GripperMission,
1013
self.DoubleCircle,
1014
self.MotorThrustHoverParameterIgnore,
1015
self.SET_POSITION_TARGET_GLOBAL_INT,
1016
self.TestLogDownloadMAVProxy,
1017
self.TestLogDownloadMAVProxyNetwork,
1018
self.TestLogDownloadLogRestart,
1019
self.MAV_CMD_NAV_LOITER_UNLIM,
1020
self.MAV_CMD_NAV_LAND,
1021
self.MAV_CMD_MISSION_START,
1022
self.MAV_CMD_DO_CHANGE_SPEED,
1023
self.MAV_CMD_CONDITION_YAW,
1024
self.MAV_CMD_DO_REPOSITION,
1025
self.TerrainMission,
1026
self.SetGlobalOrigin,
1027
self.BackupOrigin,
1028
self.FuseMag,
1029
self.INA3221,
1030
])
1031
1032
return ret
1033
1034