Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/arduplane.py
9744 views
1
'''
2
Fly ArduPlane in SITL
3
4
AP_FLAKE8_CLEAN
5
'''
6
7
import copy
8
import math
9
import os
10
import signal
11
import time
12
13
from pymavlink import quaternion
14
from pymavlink import mavutil
15
16
from pymavlink.rotmat import Vector3
17
18
import vehicle_test_suite
19
20
from vehicle_test_suite import AutoTestTimeoutException
21
from vehicle_test_suite import NotAchievedException
22
from vehicle_test_suite import OldpymavlinkException
23
from vehicle_test_suite import PreconditionFailedException
24
from vehicle_test_suite import Test
25
from vehicle_test_suite import WaitModeTimeout
26
from vehicle_test_suite import MAV_POS_TARGET_TYPE_MASK
27
28
from pysim import vehicleinfo
29
from pysim import util
30
31
import operator
32
33
# get location of scripts
34
testdir = os.path.dirname(os.path.realpath(__file__))
35
SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 585, 354)
36
WIND = "0,180,0.2" # speed,direction,variance
37
38
39
class AutoTestPlane(vehicle_test_suite.TestSuite):
40
@staticmethod
41
def get_not_armable_mode_list():
42
return []
43
44
@staticmethod
45
def get_not_disarmed_settable_modes_list():
46
return ["FOLLOW"]
47
48
@staticmethod
49
def get_no_position_not_settable_modes_list():
50
return []
51
52
@staticmethod
53
def get_position_armable_modes_list():
54
return ["GUIDED", "AUTO"]
55
56
@staticmethod
57
def get_normal_armable_modes_list():
58
return ["MANUAL", "STABILIZE", "ACRO"]
59
60
def log_name(self):
61
return "ArduPlane"
62
63
def default_speedup(self):
64
return 100
65
66
def test_filepath(self):
67
return os.path.realpath(__file__)
68
69
def sitl_start_location(self):
70
return SITL_START_LOCATION
71
72
def defaults_filepath(self):
73
return os.path.join(testdir, 'default_params/plane-jsbsim.parm')
74
75
def set_current_test_name(self, name):
76
self.current_test_name_directory = "ArduPlane_Tests/" + name + "/"
77
78
def default_frame(self):
79
return "plane-elevrev"
80
81
def apply_defaultfile_parameters(self):
82
# plane passes in a defaults_filepath in place of applying
83
# parameters afterwards.
84
pass
85
86
def is_plane(self):
87
return True
88
89
def get_stick_arming_channel(self):
90
return int(self.get_parameter("RCMAP_YAW"))
91
92
def get_disarm_delay(self):
93
return int(self.get_parameter("LAND_DISARMDELAY"))
94
95
def set_autodisarm_delay(self, delay):
96
self.set_parameter("LAND_DISARMDELAY", delay)
97
98
def takeoff(self, alt=150, alt_max=None, relative=True, mode=None, timeout=None):
99
"""Takeoff to altitude."""
100
101
if mode == "TAKEOFF":
102
return self.takeoff_in_TAKEOFF(alt=alt, relative=relative, timeout=timeout)
103
104
return self.takeoff_in_FBWA(alt=alt, alt_max=alt_max, relative=relative, timeout=timeout)
105
106
def takeoff_in_TAKEOFF(self, alt=150, relative=True, mode=None, alt_epsilon=2, timeout=None):
107
if relative is not True:
108
raise ValueError("Only relative alt supported ATM")
109
self.change_mode("TAKEOFF")
110
self.context_push()
111
self.set_parameter('TKOFF_ALT', alt)
112
self.wait_ready_to_arm()
113
self.arm_vehicle()
114
self.wait_altitude(alt-alt_epsilon, alt+alt_epsilon, relative=True, timeout=timeout)
115
self.context_pop()
116
117
def takeoff_in_FBWA(self, alt=150, alt_max=None, relative=True, mode=None, timeout=30):
118
if alt_max is None:
119
alt_max = alt + 30
120
121
self.change_mode("FBWA")
122
123
self.wait_ready_to_arm()
124
self.arm_vehicle()
125
126
# some rudder to counteract the prop torque
127
self.set_rc(4, 1700)
128
129
# some up elevator to keep the tail down
130
self.set_rc(2, 1200)
131
132
# get it moving a bit first
133
self.set_rc(3, 1300)
134
self.wait_groundspeed(6, 100)
135
136
# a bit faster again, straighten rudder
137
self.set_rc_from_map({
138
3: 1600,
139
4: 1500,
140
})
141
self.wait_groundspeed(12, 100)
142
143
# hit the gas harder now, and give it some more elevator
144
self.set_rc_from_map({
145
2: 1100,
146
3: 2000,
147
})
148
149
# gain a bit of altitude
150
self.wait_altitude(alt, alt_max, timeout=timeout, relative=relative)
151
152
# level off
153
self.set_rc(2, 1500)
154
155
self.progress("TAKEOFF COMPLETE")
156
157
def fly_left_circuit(self):
158
"""Fly a left circuit, 200m on a side."""
159
self.change_mode('FBWA')
160
self.set_rc(3, 2000)
161
self.wait_level_flight()
162
163
self.progress("Flying left circuit")
164
# do 4 turns
165
for i in range(0, 4):
166
# hard left
167
self.progress("Starting turn %u" % i)
168
self.set_rc(1, 1000)
169
self.wait_heading(270 - (90*i), accuracy=10)
170
self.set_rc(1, 1500)
171
self.progress("Starting leg %u" % i)
172
self.wait_distance(100, accuracy=20)
173
self.progress("Circuit complete")
174
175
def fly_RTL(self):
176
"""Fly to home."""
177
self.progress("Flying home in RTL")
178
target_loc = self.home_position_as_mav_location()
179
target_loc.alt += 100
180
self.change_mode('RTL')
181
self.wait_location(target_loc,
182
accuracy=120,
183
height_accuracy=20,
184
timeout=180)
185
self.progress("RTL Complete")
186
187
def NeedEKFToArm(self):
188
"""Ensure the EKF must be healthy for the vehicle to arm."""
189
self.progress("Ensuring we need EKF to be healthy to arm")
190
self.set_parameter("SIM_GPS1_ENABLE", 0)
191
self.context_collect("STATUSTEXT")
192
tstart = self.get_sim_time()
193
success = False
194
for run_cmd in self.run_cmd, self.run_cmd_int:
195
while not success:
196
if self.get_sim_time_cached() - tstart > 60:
197
raise NotAchievedException("Did not get correct failure reason")
198
run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)
199
try:
200
self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True)
201
success = True
202
continue
203
except AutoTestTimeoutException:
204
pass
205
206
self.set_parameter("SIM_GPS1_ENABLE", 1)
207
self.wait_ready_to_arm()
208
209
def fly_LOITER(self, num_circles=4):
210
"""Loiter where we are."""
211
self.progress("Testing LOITER for %u turns" % num_circles)
212
self.change_mode('LOITER')
213
214
m = self.assert_receive_message('VFR_HUD')
215
initial_alt = m.alt
216
self.progress("Initial altitude %u\n" % initial_alt)
217
218
while num_circles > 0:
219
self.wait_heading(0, accuracy=10, timeout=60)
220
self.wait_heading(180, accuracy=10, timeout=60)
221
num_circles -= 1
222
self.progress("Loiter %u circles left" % num_circles)
223
224
m = self.assert_receive_message('VFR_HUD')
225
final_alt = m.alt
226
self.progress("Final altitude %u initial %u\n" %
227
(final_alt, initial_alt))
228
229
self.change_mode('FBWA')
230
231
if abs(final_alt - initial_alt) > 20:
232
raise NotAchievedException("Failed to maintain altitude")
233
234
self.progress("Completed Loiter OK")
235
236
def fly_CIRCLE(self, num_circles=1):
237
"""Circle where we are."""
238
self.progress("Testing CIRCLE for %u turns" % num_circles)
239
self.change_mode('CIRCLE')
240
241
m = self.assert_receive_message('VFR_HUD')
242
initial_alt = m.alt
243
self.progress("Initial altitude %u\n" % initial_alt)
244
245
while num_circles > 0:
246
self.wait_heading(0, accuracy=10, timeout=60)
247
self.wait_heading(180, accuracy=10, timeout=60)
248
num_circles -= 1
249
self.progress("CIRCLE %u circles left" % num_circles)
250
251
m = self.assert_receive_message('VFR_HUD')
252
final_alt = m.alt
253
self.progress("Final altitude %u initial %u\n" %
254
(final_alt, initial_alt))
255
256
self.change_mode('FBWA')
257
258
if abs(final_alt - initial_alt) > 20:
259
raise NotAchievedException("Failed to maintain altitude")
260
261
self.progress("Completed CIRCLE OK")
262
263
def wait_level_flight(self, accuracy=5, timeout=30):
264
"""Wait for level flight."""
265
tstart = self.get_sim_time()
266
self.progress("Waiting for level flight")
267
self.set_rc(1, 1500)
268
self.set_rc(2, 1500)
269
self.set_rc(4, 1500)
270
while self.get_sim_time_cached() < tstart + timeout:
271
m = self.assert_receive_message('ATTITUDE')
272
roll = math.degrees(m.roll)
273
pitch = math.degrees(m.pitch)
274
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
275
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
276
self.progress("Attained level flight")
277
return
278
raise NotAchievedException("Failed to attain level flight")
279
280
def change_altitude(self, altitude, accuracy=30, relative=False):
281
"""Get to a given altitude."""
282
if relative:
283
altitude += self.home_position_as_mav_location().alt
284
self.change_mode('FBWA')
285
alt_error = self.mav.messages['VFR_HUD'].alt - altitude
286
if alt_error > 0:
287
self.set_rc(2, 2000)
288
else:
289
self.set_rc(2, 1000)
290
self.wait_altitude(altitude-accuracy/2, altitude+accuracy/2)
291
self.set_rc(2, 1500)
292
self.progress("Reached target altitude at %u" %
293
self.mav.messages['VFR_HUD'].alt)
294
return self.wait_level_flight()
295
296
def axial_left_roll(self, count=1):
297
"""Fly a left axial roll."""
298
# full throttle!
299
self.set_rc(3, 2000)
300
self.change_altitude(300, relative=True)
301
302
# fly the roll in manual
303
self.change_mode('MANUAL')
304
305
while count > 0:
306
self.progress("Starting roll")
307
self.set_rc(1, 1000)
308
try:
309
self.wait_roll(-150, accuracy=90)
310
self.wait_roll(150, accuracy=90)
311
self.wait_roll(0, accuracy=90)
312
except Exception as e:
313
self.set_rc(1, 1500)
314
raise e
315
count -= 1
316
317
# back to FBWA
318
self.set_rc(1, 1500)
319
self.change_mode('FBWA')
320
self.set_rc(3, 1700)
321
return self.wait_level_flight()
322
323
def inside_loop(self, count=1):
324
"""Fly a inside loop."""
325
# full throttle!
326
self.set_rc(3, 2000)
327
self.change_altitude(300, relative=True)
328
# fly the loop in manual
329
self.change_mode('MANUAL')
330
331
while count > 0:
332
self.progress("Starting loop")
333
self.set_rc(2, 1000)
334
self.wait_pitch(-60, accuracy=20)
335
self.wait_pitch(0, accuracy=20)
336
count -= 1
337
338
# back to FBWA
339
self.set_rc(2, 1500)
340
self.change_mode('FBWA')
341
self.set_rc(3, 1700)
342
return self.wait_level_flight()
343
344
def set_attitude_target(self, tolerance=10):
345
"""Test setting of attitude target in guided mode."""
346
self.change_mode("GUIDED")
347
348
steps = [{"name": "roll-over", "roll": 60, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000001},
349
{"name": "roll-back", "roll": 0, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000001},
350
{"name": "pitch-up+throttle", "roll": 0, "pitch": 20, "yaw": 0, "throttle": 1, "type_mask": 0b11000010},
351
{"name": "pitch-back", "roll": 0, "pitch": 0, "yaw": 0, "throttle": 0, "type_mask": 0b10000010}]
352
353
state_wait = "wait"
354
state_hold = "hold"
355
try:
356
for step in steps:
357
step_start = self.get_sim_time_cached()
358
state = state_wait
359
state_start = self.get_sim_time_cached()
360
while True:
361
m = self.mav.recv_match(type='ATTITUDE',
362
blocking=True,
363
timeout=0.1)
364
now = self.get_sim_time_cached()
365
if now - step_start > 30:
366
raise AutoTestTimeoutException("Maneuvers not completed")
367
if m is None:
368
continue
369
370
angle_error = 0
371
if (step["type_mask"] & 0b00000001) or (step["type_mask"] == 0b10000000):
372
angle_error += abs(math.degrees(m.roll) - step["roll"])
373
374
if (step["type_mask"] & 0b00000010) or (step["type_mask"] == 0b10000000):
375
angle_error += abs(math.degrees(m.pitch) - step["pitch"])
376
377
if (step["type_mask"] & 0b00000100) or (step["type_mask"] == 0b10000000):
378
# Strictly we should angle wrap, by plane doesn't support yaw correctly anyway so its not tested here
379
angle_error += abs(math.degrees(m.yaw) - step["yaw"])
380
381
# Note were not checking throttle, however the SITL plane needs full throttle to meet the
382
# target pitch attitude, Pitch test will fail without throttle override
383
384
if state == state_wait:
385
# Reduced tolerance for initial trigger
386
if angle_error < (tolerance * 0.25):
387
state = state_hold
388
state_start = now
389
390
# Allow 10 seconds to reach attitude
391
if (now - state_start) > 10:
392
raise NotAchievedException(step["name"] + ": Failed to get to set attitude")
393
394
elif state == state_hold:
395
# Give 2 seconds to stabilize
396
if (now - state_start) > 2 and not (angle_error < tolerance):
397
raise NotAchievedException(step["name"] + ": Failed to hold set attitude")
398
399
# Hold for 10 seconds
400
if (now - state_start) > 12:
401
# move onto next step
402
self.progress("%s Done" % (step["name"]))
403
break
404
405
self.progress("%s %s error: %f" % (step["name"], state, angle_error))
406
407
time_boot_millis = 0 # FIXME
408
target_system = 1 # FIXME
409
target_component = 1 # FIXME
410
type_mask = step["type_mask"] ^ 0xFF # FIXME
411
# attitude in radians:
412
q = quaternion.Quaternion([math.radians(step["roll"]),
413
math.radians(step["pitch"]),
414
math.radians(step["yaw"])])
415
self.mav.mav.set_attitude_target_send(time_boot_millis,
416
target_system,
417
target_component,
418
type_mask,
419
q,
420
0, # roll rate, not used in AP
421
0, # pitch rate, not used in AP
422
0, # yaw rate, not used in AP
423
step["throttle"])
424
except Exception as e:
425
self.change_mode('FBWA')
426
self.set_rc(3, 1700)
427
raise e
428
429
# back to FBWA
430
self.change_mode('FBWA')
431
self.set_rc(3, 1700)
432
self.wait_level_flight()
433
434
def test_stabilize(self, count=1):
435
"""Fly stabilize mode."""
436
# full throttle!
437
self.set_rc(3, 2000)
438
self.set_rc(2, 1300)
439
self.change_altitude(300, relative=True)
440
self.set_rc(2, 1500)
441
442
self.change_mode('STABILIZE')
443
444
while count > 0:
445
self.progress("Starting roll")
446
self.set_rc(1, 2000)
447
self.wait_roll(-150, accuracy=90)
448
self.wait_roll(150, accuracy=90)
449
self.wait_roll(0, accuracy=90)
450
count -= 1
451
452
self.set_rc(1, 1500)
453
self.wait_roll(0, accuracy=5)
454
455
# back to FBWA
456
self.change_mode('FBWA')
457
self.set_rc(3, 1700)
458
return self.wait_level_flight()
459
460
def test_acro(self, count=1):
461
"""Fly ACRO mode."""
462
# full throttle!
463
self.set_rc(3, 2000)
464
self.set_rc(2, 1300)
465
self.change_altitude(300, relative=True)
466
self.set_rc(2, 1500)
467
468
self.change_mode('ACRO')
469
470
while count > 0:
471
self.progress("Starting roll")
472
self.set_rc(1, 1000)
473
self.wait_roll(-150, accuracy=90)
474
self.wait_roll(150, accuracy=90)
475
self.wait_roll(0, accuracy=90)
476
count -= 1
477
self.set_rc(1, 1500)
478
479
# back to FBWA
480
self.change_mode('FBWA')
481
482
self.wait_level_flight()
483
484
self.change_mode('ACRO')
485
486
count = 2
487
while count > 0:
488
self.progress("Starting loop")
489
self.set_rc(2, 1000)
490
self.wait_pitch(-60, accuracy=20)
491
self.wait_pitch(0, accuracy=20)
492
count -= 1
493
494
self.set_rc(2, 1500)
495
496
# back to FBWA
497
self.change_mode('FBWA')
498
self.set_rc(3, 1700)
499
return self.wait_level_flight()
500
501
def test_FBWB(self, mode='FBWB'):
502
"""Fly FBWB or CRUISE mode."""
503
self.change_mode(mode)
504
self.set_rc(3, 1700)
505
self.set_rc(2, 1500)
506
507
# lock in the altitude by asking for an altitude change then releasing
508
self.set_rc(2, 1000)
509
self.wait_distance(50, accuracy=20)
510
self.set_rc(2, 1500)
511
self.wait_distance(50, accuracy=20)
512
513
m = self.assert_receive_message('VFR_HUD')
514
initial_alt = m.alt
515
self.progress("Initial altitude %u\n" % initial_alt)
516
517
self.progress("Flying right circuit")
518
# do 4 turns
519
for i in range(0, 4):
520
# hard left
521
self.progress("Starting turn %u" % i)
522
self.set_rc(1, 1800)
523
try:
524
self.wait_heading(0 + (90*i), accuracy=20, timeout=60)
525
except Exception as e:
526
self.set_rc(1, 1500)
527
raise e
528
self.set_rc(1, 1500)
529
self.progress("Starting leg %u" % i)
530
self.wait_distance(100, accuracy=20)
531
self.progress("Circuit complete")
532
533
self.progress("Flying rudder left circuit")
534
# do 4 turns
535
for i in range(0, 4):
536
# hard left
537
self.progress("Starting turn %u" % i)
538
self.set_rc(4, 1900)
539
try:
540
self.wait_heading(360 - (90*i), accuracy=20, timeout=60)
541
except Exception as e:
542
self.set_rc(4, 1500)
543
raise e
544
self.set_rc(4, 1500)
545
self.progress("Starting leg %u" % i)
546
self.wait_distance(100, accuracy=20)
547
self.progress("Circuit complete")
548
549
m = self.assert_receive_message('VFR_HUD')
550
final_alt = m.alt
551
self.progress("Final altitude %u initial %u\n" %
552
(final_alt, initial_alt))
553
554
# back to FBWA
555
self.change_mode('FBWA')
556
557
if abs(final_alt - initial_alt) > 20:
558
raise NotAchievedException("Failed to maintain altitude")
559
560
return self.wait_level_flight()
561
562
def fly_mission(self, filename, mission_timeout=60.0, strict=True, quadplane=False):
563
"""Fly a mission from a file."""
564
self.progress("Flying mission %s" % filename)
565
num_wp = self.load_mission(filename, strict=strict)-1
566
self.fly_mission_waypoints(num_wp, mission_timeout=mission_timeout, quadplane=quadplane)
567
568
def fly_mission_waypoints(self, num_wp, mission_timeout=60.0, quadplane=False):
569
self.set_current_waypoint(0, check_afterwards=False)
570
self.context_push()
571
self.context_collect('STATUSTEXT')
572
self.change_mode('AUTO')
573
self.wait_waypoint(1, num_wp, max_dist=60, timeout=mission_timeout)
574
self.wait_groundspeed(0, 0.5, timeout=mission_timeout)
575
if quadplane:
576
self.wait_statustext("Throttle disarmed", timeout=200, check_context=True)
577
else:
578
self.wait_statustext("Auto disarmed", timeout=60, check_context=True)
579
self.context_pop()
580
self.progress("Mission OK")
581
582
def DO_REPOSITION(self):
583
'''Test mavlink DO_REPOSITION command'''
584
self.progress("Takeoff")
585
self.takeoff(alt=50)
586
self.set_rc(3, 1500)
587
self.progress("Entering guided and flying somewhere constant")
588
self.change_mode("GUIDED")
589
loc = self.mav.location()
590
self.location_offset_ne(loc, 500, 500)
591
592
new_alt = 100
593
self.run_cmd_int(
594
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
595
p5=int(loc.lat * 1e7),
596
p6=int(loc.lng * 1e7),
597
p7=new_alt, # alt
598
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
599
)
600
self.wait_altitude(new_alt-10, new_alt, timeout=30, relative=True)
601
602
self.install_terrain_handlers_context()
603
604
self.location_offset_ne(loc, 500, 500)
605
terrain_height_wanted = 150
606
self.run_cmd_int(
607
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
608
0,
609
0,
610
0,
611
0,
612
int(loc.lat*1e7),
613
int(loc.lng*1e7),
614
terrain_height_wanted, # alt
615
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
616
)
617
618
# move to specific terrain-relative altitude and hold for <n> seconds
619
tstart = self.get_sim_time_cached()
620
achieve_start = None
621
tr = None
622
while True:
623
if self.get_sim_time_cached() - tstart > 120:
624
raise NotAchievedException("Did not move to correct terrain alt")
625
626
m = self.assert_receive_message('TERRAIN_REPORT')
627
tr = m
628
terrain_height_achieved = m.current_height
629
self.progress("terrain_alt=%f want=%f" %
630
(terrain_height_achieved, terrain_height_wanted))
631
if m is None:
632
continue
633
if abs(terrain_height_wanted - terrain_height_achieved) > 5:
634
if achieve_start is not None:
635
self.progress("Achieve stop")
636
achieve_start = None
637
elif achieve_start is None:
638
self.progress("Achieve start")
639
achieve_start = self.get_sim_time_cached()
640
if achieve_start is not None:
641
if self.get_sim_time_cached() - achieve_start > 10:
642
break
643
m = self.assert_receive_message('GLOBAL_POSITION_INT')
644
self.progress("TR: %s" % tr)
645
self.progress("GPI: %s" % m)
646
min_delta = 4
647
delta = abs(m.relative_alt/1000.0 - tr.current_height)
648
if abs(delta < min_delta):
649
raise NotAchievedException("Expected altitude delta (want=%f got=%f)" %
650
(min_delta, delta))
651
652
self.fly_home_land_and_disarm(timeout=180)
653
654
def ExternalPositionEstimate(self):
655
'''Test mavlink EXTERNAL_POSITION_ESTIMATE command'''
656
if not hasattr(mavutil.mavlink, 'MAV_CMD_EXTERNAL_POSITION_ESTIMATE'):
657
raise OldpymavlinkException("pymavlink too old; upgrade pymavlink to get MAV_CMD_EXTERNAL_POSITION_ESTIMATE") # noqa
658
self.change_mode("TAKEOFF")
659
self.wait_ready_to_arm()
660
self.arm_vehicle()
661
self.wait_altitude(48, 52, relative=True)
662
663
loc = self.mav.location()
664
self.location_offset_ne(loc, 2000, 2000)
665
666
# setting external position fail while we have GPS lock
667
self.progress("set new position with GPS")
668
self.run_cmd_int(
669
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
670
p1=self.get_sim_time()-1, # transmit time
671
p2=0.5, # processing delay
672
p3=50, # accuracy
673
p5=int(loc.lat * 1e7),
674
p6=int(loc.lng * 1e7),
675
p7=float("NaN"), # alt
676
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
677
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
678
)
679
680
self.progress("disable the GPS")
681
self.run_auxfunc(
682
65,
683
2,
684
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
685
)
686
687
# fly for a bit to get into non-aiding state
688
self.progress("waiting 20 seconds")
689
tstart = self.get_sim_time()
690
while self.get_sim_time() < tstart + 20:
691
self.wait_heartbeat()
692
693
self.progress("getting base position")
694
gpi = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=5)
695
loc = mavutil.location(gpi.lat*1e-7, gpi.lon*1e-7, 0, 0)
696
697
self.progress("set new position with no GPS")
698
self.run_cmd_int(
699
mavutil.mavlink.MAV_CMD_EXTERNAL_POSITION_ESTIMATE,
700
p1=self.get_sim_time()-1, # transmit time
701
p2=0.5, # processing delay
702
p3=50, # accuracy
703
p5=gpi.lat+1,
704
p6=gpi.lon+1,
705
p7=float("NaN"), # alt
706
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
707
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
708
)
709
710
self.progress("waiting 3 seconds")
711
tstart = self.get_sim_time()
712
while self.get_sim_time() < tstart + 3:
713
self.wait_heartbeat()
714
715
gpi2 = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=5)
716
loc2 = mavutil.location(gpi2.lat*1e-7, gpi2.lon*1e-7, 0, 0)
717
dist = self.get_distance(loc, loc2)
718
719
self.progress("dist is %.1f" % dist)
720
if dist > 200:
721
raise NotAchievedException("Position error dist=%.1f" % dist)
722
723
self.progress("re-enable the GPS")
724
self.run_auxfunc(
725
65,
726
0,
727
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
728
)
729
730
self.progress("flying home")
731
self.fly_home_land_and_disarm()
732
733
def DeepStall(self):
734
'''Test DeepStall Landing'''
735
# self.fly_deepstall_absolute()
736
self.fly_deepstall_relative()
737
738
def fly_deepstall_absolute(self):
739
self.start_subtest("DeepStall Relative Absolute")
740
deepstall_elevator_pwm = 1661
741
self.set_parameters({
742
"LAND_TYPE": 1,
743
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
744
"RTL_AUTOLAND": 1,
745
})
746
self.load_mission("plane-deepstall-mission.txt")
747
self.change_mode("AUTO")
748
self.wait_ready_to_arm()
749
self.arm_vehicle()
750
self.progress("Waiting for deepstall messages")
751
752
# note that the following two don't necessarily happen in this
753
# order, but at very high speedups we may miss the elevator
754
# PWM if we first look for the text (due to the get_sim_time()
755
# in wait_servo_channel_value)
756
757
self.context_collect('STATUSTEXT')
758
759
# assume elevator is on channel 2:
760
self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240)
761
762
self.wait_text("Deepstall: Entry: ", check_context=True)
763
764
self.disarm_wait(timeout=120)
765
766
self.progress("Flying home")
767
self.set_current_waypoint(0, check_afterwards=False)
768
self.takeoff(10)
769
self.set_parameter("LAND_TYPE", 0)
770
self.fly_home_land_and_disarm()
771
772
def fly_deepstall_relative(self):
773
self.start_subtest("DeepStall Relative")
774
deepstall_elevator_pwm = 1661
775
self.set_parameters({
776
"LAND_TYPE": 1,
777
"LAND_DS_ELEV_PWM": deepstall_elevator_pwm,
778
"RTL_AUTOLAND": 1,
779
})
780
self.load_mission("plane-deepstall-relative-mission.txt")
781
self.change_mode("AUTO")
782
self.wait_ready_to_arm()
783
self.arm_vehicle()
784
self.wait_current_waypoint(4)
785
786
# assume elevator is on channel 2:
787
self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240)
788
789
self.progress("Waiting for stage DEEPSTALL_STAGE_LAND")
790
self.assert_receive_message(
791
'DEEPSTALL',
792
condition='DEEPSTALL.stage==6',
793
timeout=240,
794
)
795
self.progress("Reached stage DEEPSTALL_STAGE_LAND")
796
797
self.disarm_wait(timeout=120)
798
self.set_current_waypoint(0, check_afterwards=False)
799
800
self.progress("Flying home")
801
self.set_current_waypoint(0, check_afterwards=False)
802
self.takeoff(100)
803
self.set_parameter("LAND_TYPE", 0)
804
self.fly_home_land_and_disarm(timeout=240)
805
806
def SmartBattery(self):
807
'''Test smart battery logging etc'''
808
self.set_parameters({
809
"BATT_MONITOR": 16, # Maxell battery monitor
810
})
811
812
# Must reboot sitl after setting monitor type for SMBus parameters to be set due to dynamic group
813
self.reboot_sitl()
814
self.set_parameters({
815
"BATT_I2C_BUS": 2, # specified in SIM_I2C.cpp
816
"BATT_I2C_ADDR": 11, # specified in SIM_I2C.cpp
817
})
818
self.reboot_sitl()
819
820
self.wait_ready_to_arm()
821
m = self.assert_receive_message('BATTERY_STATUS', timeout=10)
822
if m.voltages_ext[0] == 65536:
823
raise NotAchievedException("Flag value rather than voltage")
824
if abs(m.voltages_ext[0] - 1000) > 300:
825
raise NotAchievedException("Did not get good ext voltage (got=%f)" %
826
(m.voltages_ext[0],))
827
self.arm_vehicle()
828
self.delay_sim_time(5)
829
self.disarm_vehicle()
830
if not self.current_onboard_log_contains_message("BCL2"):
831
raise NotAchievedException("Expected BCL2 message")
832
833
def context_push_do_change_speed(self):
834
# the following lines ensure we revert these parameter values
835
# - DO_CHANGE_AIRSPEED is a permanent vehicle change!
836
self.context_push()
837
self.set_parameters({
838
"AIRSPEED_CRUISE": self.get_parameter("AIRSPEED_CRUISE"),
839
"MIN_GROUNDSPEED": self.get_parameter("MIN_GROUNDSPEED"),
840
"TRIM_THROTTLE": self.get_parameter("TRIM_THROTTLE"),
841
})
842
843
def DO_CHANGE_SPEED(self):
844
'''Test DO_CHANGE_SPEED command/item'''
845
self.set_parameters({
846
"RTL_AUTOLAND": 1,
847
})
848
849
self.context_push_do_change_speed()
850
self.DO_CHANGE_SPEED_mavlink_long()
851
self.context_pop()
852
853
self.set_current_waypoint(1)
854
self.zero_throttle()
855
856
self.context_push_do_change_speed()
857
self.DO_CHANGE_SPEED_mavlink_int()
858
self.context_pop()
859
860
self.context_push_do_change_speed()
861
self.DO_CHANGE_SPEED_mission()
862
self.context_pop()
863
864
def DO_CHANGE_SPEED_mission(self):
865
'''test DO_CHANGE_SPEED as a mission item'''
866
self.start_subtest("DO_CHANGE_SPEED_mission")
867
self.load_mission("mission.txt")
868
self.set_current_waypoint(1)
869
870
self.progress("Takeoff")
871
self.set_rc(3, 1000)
872
self.takeoff(alt=10)
873
self.set_rc(3, 1500)
874
875
self.start_subtest("Check initial speed")
876
877
self.change_mode('AUTO')
878
879
checks = [
880
(1, self.get_parameter("AIRSPEED_CRUISE")),
881
(3, 10),
882
(5, 20),
883
(7, 15),
884
]
885
886
for (current_waypoint, want_airspeed) in checks:
887
self.wait_current_waypoint(current_waypoint, timeout=150)
888
self.wait_airspeed(want_airspeed-1, want_airspeed+1, minimum_duration=5, timeout=120)
889
890
self.fly_home_land_and_disarm()
891
892
def DO_CHANGE_SPEED_mavlink_int(self):
893
self.DO_CHANGE_SPEED_mavlink(self.run_cmd_int)
894
895
def DO_CHANGE_SPEED_mavlink_long(self):
896
self.DO_CHANGE_SPEED_mavlink(self.run_cmd)
897
898
def DO_CHANGE_SPEED_mavlink(self, run_cmd_method):
899
'''test DO_CHANGE_SPEED as a mavlink command'''
900
self.progress("Takeoff")
901
self.takeoff(alt=100, mode="TAKEOFF", timeout=120)
902
self.set_rc(3, 1500)
903
# ensure we know what the airspeed is:
904
self.progress("Entering guided and flying somewhere constant")
905
self.change_mode("GUIDED")
906
self.run_cmd_int(
907
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
908
p5=12345, # lat* 1e7
909
p6=12345, # lon* 1e7
910
p7=100, # alt
911
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
912
)
913
self.delay_sim_time(10)
914
self.progress("Ensuring initial speed is known and relatively constant")
915
initial_speed = 22.0
916
timeout = 15
917
self.wait_airspeed(initial_speed-1, initial_speed+1, minimum_duration=5, timeout=timeout)
918
919
self.start_subtest("Setting groundspeed")
920
for new_target_groundspeed in initial_speed + 5, initial_speed + 2:
921
run_cmd_method(
922
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
923
p1=1, # groundspeed
924
p2=new_target_groundspeed,
925
p3=-1, # throttle / no change
926
p4=0, # absolute values
927
)
928
self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=80, minimum_duration=5)
929
self.progress("Adding some wind, ensuring groundspeed holds")
930
self.set_parameter("SIM_WIND_SPD", 5)
931
self.delay_sim_time(5)
932
self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=40, minimum_duration=5)
933
self.set_parameter("SIM_WIND_SPD", 0)
934
935
# clear target groundspeed
936
run_cmd_method(
937
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
938
p1=1, # groundspeed
939
p2=0,
940
p3=-1, # throttle / no change
941
p4=0, # absolute values
942
)
943
944
self.start_subtest("Setting airspeed")
945
for new_target_airspeed in initial_speed - 5, initial_speed + 5:
946
run_cmd_method(
947
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
948
p1=0, # airspeed
949
p2=new_target_airspeed,
950
p3=-1, # throttle / no change
951
p4=0, # absolute values
952
)
953
self.wait_airspeed(new_target_airspeed-2, new_target_airspeed+2, minimum_duration=5)
954
955
self.context_push()
956
self.progress("Adding some wind, hoping groundspeed increases/decreases")
957
self.set_parameters({
958
"SIM_WIND_SPD": 7,
959
"SIM_WIND_DIR": 270,
960
})
961
self.delay_sim_time(5)
962
timeout = 10
963
tstart = self.get_sim_time()
964
while True:
965
if self.get_sim_time_cached() - tstart > timeout:
966
raise NotAchievedException("Did not achieve groundspeed delta")
967
m = self.assert_receive_message('VFR_HUD')
968
delta = abs(m.airspeed - m.groundspeed)
969
want_delta = 5
970
self.progress("groundspeed and airspeed should be different (have=%f want=%f)" % (delta, want_delta))
971
if delta > want_delta:
972
break
973
self.context_pop()
974
975
# cancel minimum groundspeed:
976
run_cmd_method(
977
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
978
p1=0, # groundspeed
979
p2=-2, # return to default
980
p3=0, # throttle / no change
981
p4=0, # absolute values
982
)
983
# cancel airspeed:
984
run_cmd_method(
985
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
986
p1=1, # airspeed
987
p2=-2, # return to default
988
p3=0, # throttle / no change
989
p4=0, # absolute values
990
)
991
992
self.start_subtest("Setting throttle")
993
self.set_parameter('ARSPD_USE', 0) # setting throttle only effective without airspeed
994
for (set_throttle, expected_throttle) in (97, 79), (60, 51), (95, 77):
995
run_cmd_method(
996
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
997
p1=3, # throttle
998
p2=0,
999
p3=set_throttle, # throttle / no change
1000
p4=0, # absolute values
1001
)
1002
self.wait_message_field_values('VFR_HUD', {
1003
"throttle": expected_throttle,
1004
}, minimum_duration=5, epsilon=5)
1005
1006
self.fly_home_land_and_disarm(timeout=240)
1007
1008
def fly_home_land_and_disarm(self, timeout=120):
1009
filename = "flaps.txt"
1010
self.progress("Using %s to fly home" % filename)
1011
self.load_generic_mission(filename)
1012
self.change_mode("AUTO")
1013
# don't set current waypoint to 8 unless we're distant from it
1014
# or we arrive instantly and never see it as our current
1015
# waypoint:
1016
self.wait_distance_to_waypoint(8, 100, 10000000)
1017
self.set_current_waypoint(8)
1018
# TODO: reflect on file to find this magic waypoint number?
1019
# self.wait_waypoint(7, num_wp-1, timeout=500) # we
1020
# tend to miss the final waypoint by a fair bit, and
1021
# this is probably too noisy anyway?
1022
self.wait_disarmed(timeout=timeout)
1023
1024
def TestFlaps(self):
1025
"""Test flaps functionality."""
1026
filename = "flaps.txt"
1027
flaps_ch = 5
1028
flaps_ch_min = 1000
1029
flaps_ch_trim = 1500
1030
flaps_ch_max = 2000
1031
1032
servo_ch = 5
1033
servo_ch_min = 1200
1034
servo_ch_trim = 1300
1035
servo_ch_max = 1800
1036
1037
self.set_parameters({
1038
"SERVO%u_FUNCTION" % servo_ch: 3, # flapsauto
1039
"RC%u_OPTION" % flaps_ch: 208, # Flaps RCx_OPTION
1040
"LAND_FLAP_PERCNT": 50,
1041
"LOG_DISARMED": 1,
1042
"RTL_AUTOLAND": 1,
1043
1044
"RC%u_MIN" % flaps_ch: flaps_ch_min,
1045
"RC%u_MAX" % flaps_ch: flaps_ch_max,
1046
"RC%u_TRIM" % flaps_ch: flaps_ch_trim,
1047
1048
"SERVO%u_MIN" % servo_ch: servo_ch_min,
1049
"SERVO%u_MAX" % servo_ch: servo_ch_max,
1050
"SERVO%u_TRIM" % servo_ch: servo_ch_trim,
1051
})
1052
1053
self.progress("check flaps are not deployed")
1054
self.set_rc(flaps_ch, flaps_ch_min)
1055
self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=3)
1056
self.progress("deploy the flaps")
1057
self.set_rc(flaps_ch, flaps_ch_max)
1058
tstart = self.get_sim_time()
1059
self.wait_servo_channel_value(servo_ch, servo_ch_max)
1060
tstop = self.get_sim_time_cached()
1061
delta_time = tstop - tstart
1062
delta_time_min = 0.5
1063
delta_time_max = 1.5
1064
if delta_time < delta_time_min or delta_time > delta_time_max:
1065
raise NotAchievedException((
1066
"Flaps Slew not working (%f seconds)" % (delta_time,)))
1067
self.progress("undeploy flaps")
1068
self.set_rc(flaps_ch, flaps_ch_min)
1069
self.wait_servo_channel_value(servo_ch, servo_ch_min)
1070
1071
self.progress("Flying mission %s" % filename)
1072
self.load_mission(filename)
1073
self.change_mode('AUTO')
1074
self.wait_ready_to_arm()
1075
self.arm_vehicle()
1076
self.start_subtest("flaps should deploy for landing") # (RC input value used for position?!)
1077
self.wait_servo_channel_value(servo_ch, flaps_ch_trim, timeout=300)
1078
self.start_subtest("flaps should undeploy at the end")
1079
self.wait_servo_channel_value(servo_ch, servo_ch_min, timeout=30)
1080
1081
self.progress("Flaps OK")
1082
1083
# because we have used flaps, RC output 5 is now non-zero -
1084
# it's actually the SERVO5_MIN value of 1100 now. The simulator
1085
# sees that as 100us above the zero-position (it is
1086
# 1000-to-2000 for flaps). That slows the aircraft down!
1087
self.reboot_sitl()
1088
1089
def TestRCRelay(self):
1090
'''Test Relay RC Channel Option'''
1091
self.set_parameters({
1092
"RELAY1_FUNCTION": 1, # Enable relay as a standard relay pin
1093
"RC12_OPTION": 28 # Relay On/Off
1094
})
1095
self.set_rc(12, 1000)
1096
self.reboot_sitl() # needed for RC12_OPTION and RELAY1_FUNCTION to take effect
1097
1098
off = self.get_parameter("SIM_PIN_MASK")
1099
if off:
1100
raise PreconditionFailedException("SIM_MASK_PIN off")
1101
1102
# allow time for the RC library to register initial value:
1103
self.delay_sim_time(1)
1104
1105
self.set_rc(12, 2000)
1106
self.wait_heartbeat()
1107
self.wait_heartbeat()
1108
1109
on = self.get_parameter("SIM_PIN_MASK")
1110
if not on:
1111
raise NotAchievedException("SIM_PIN_MASK doesn't reflect ON")
1112
self.set_rc(12, 1000)
1113
self.wait_heartbeat()
1114
self.wait_heartbeat()
1115
off = self.get_parameter("SIM_PIN_MASK")
1116
if off:
1117
raise NotAchievedException("SIM_PIN_MASK doesn't reflect OFF")
1118
1119
def TestRCCamera(self):
1120
'''Test RC Option - Camera Trigger'''
1121
self.set_parameter("RC12_OPTION", 9) # CameraTrigger
1122
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
1123
self.reboot_sitl() # needed for RC12_OPTION to take effect
1124
1125
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
1126
if x is not None:
1127
raise PreconditionFailedException("Receiving CAMERA_FEEDBACK?!")
1128
self.set_rc(12, 2000)
1129
tstart = self.get_sim_time()
1130
while self.get_sim_time_cached() - tstart < 10:
1131
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
1132
if x is not None:
1133
break
1134
self.wait_heartbeat()
1135
self.set_rc(12, 1000)
1136
if x is None:
1137
raise NotAchievedException("No CAMERA_FEEDBACK message received")
1138
1139
self.wait_ready_to_arm()
1140
1141
original_alt = self.get_altitude()
1142
1143
takeoff_alt = 30
1144
self.takeoff(takeoff_alt)
1145
self.set_rc(12, 2000)
1146
self.delay_sim_time(1)
1147
self.set_rc(12, 1000)
1148
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
1149
if abs(x.alt_rel - takeoff_alt) > 10:
1150
raise NotAchievedException("Bad relalt (want=%f vs got=%f)" % (takeoff_alt, x.alt_rel))
1151
if abs(x.alt_msl - (original_alt+30)) > 10:
1152
raise NotAchievedException("Bad absalt (want=%f vs got=%f)" % (original_alt+30, x.alt_msl))
1153
1154
loc = self.mav.location()
1155
self.run_cmd_int(
1156
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1157
p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
1158
p5=int(loc.lat * 1e7),
1159
p6=int(loc.lng * 1e7),
1160
p7=x.alt_rel, # alt
1161
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
1162
)
1163
expected_radius = 100
1164
self.wait_circling_point_with_radius(loc, expected_radius)
1165
1166
self.context_collect('CAMERA_FEEDBACK')
1167
self.set_rc(12, 2000)
1168
self.delay_sim_time(1)
1169
self.set_rc(12, 1000)
1170
self.assert_received_message_field_values('CAMERA_FEEDBACK', {
1171
"roll": math.degrees(self.assert_receive_message('ATTITUDE').roll),
1172
}, check_context=True, epsilon=5.0)
1173
1174
self.fly_home_land_and_disarm()
1175
1176
def ThrottleFailsafe(self):
1177
'''Fly throttle failsafe'''
1178
self.change_mode('MANUAL')
1179
m = self.assert_receive_message('SYS_STATUS')
1180
receiver_bit = mavutil.mavlink.MAV_SYS_STATUS_SENSOR_RC_RECEIVER
1181
self.progress("Testing receiver enabled")
1182
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
1183
raise PreconditionFailedException()
1184
self.progress("Testing receiver present")
1185
if (not (m.onboard_control_sensors_present & receiver_bit)):
1186
raise PreconditionFailedException()
1187
self.progress("Testing receiver health")
1188
if (not (m.onboard_control_sensors_health & receiver_bit)):
1189
raise PreconditionFailedException()
1190
1191
self.progress("Ensure we know original throttle value")
1192
self.wait_rc_channel_value(3, 1000)
1193
1194
self.set_parameter("THR_FS_VALUE", 960)
1195
self.progress("Failing receiver (throttle-to-950)")
1196
self.context_collect("HEARTBEAT")
1197
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
1198
self.wait_mode('RTL') # long failsafe
1199
if (self.get_mode_from_mode_mapping("CIRCLE") not in
1200
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
1201
raise NotAchievedException("Did not go via circle mode")
1202
self.progress("Ensure we've had our throttle squashed to 950")
1203
self.wait_rc_channel_value(3, 950)
1204
self.do_timesync_roundtrip()
1205
m = self.assert_receive_message('SYS_STATUS')
1206
self.progress("Got (%s)" % str(m))
1207
self.progress("Testing receiver enabled")
1208
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
1209
raise NotAchievedException("Receiver not enabled")
1210
self.progress("Testing receiver present")
1211
if (not (m.onboard_control_sensors_present & receiver_bit)):
1212
raise NotAchievedException("Receiver not present")
1213
# skip this until RC is fixed
1214
# self.progress("Testing receiver health")
1215
# if (m.onboard_control_sensors_health & receiver_bit):
1216
# raise NotAchievedException("Sensor healthy when it shouldn't be")
1217
self.set_parameter("SIM_RC_FAIL", 0)
1218
# have to allow time for RC to be fetched from SITL
1219
self.delay_sim_time(0.5)
1220
self.do_timesync_roundtrip()
1221
m = self.assert_receive_message('SYS_STATUS')
1222
self.progress("Testing receiver enabled")
1223
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
1224
raise NotAchievedException("Receiver not enabled")
1225
self.progress("Testing receiver present")
1226
if (not (m.onboard_control_sensors_present & receiver_bit)):
1227
raise NotAchievedException("Receiver not present")
1228
self.progress("Testing receiver health")
1229
if (not (m.onboard_control_sensors_health & receiver_bit)):
1230
raise NotAchievedException("Receiver not healthy2")
1231
self.change_mode('MANUAL')
1232
1233
self.progress("Failing receiver (no-pulses)")
1234
self.context_collect("HEARTBEAT")
1235
self.set_parameter("SIM_RC_FAIL", 1) # no-pulses
1236
self.wait_mode('RTL') # long failsafe
1237
if (self.get_mode_from_mode_mapping("CIRCLE") not in
1238
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
1239
raise NotAchievedException("Did not go via circle mode")
1240
self.do_timesync_roundtrip()
1241
m = self.assert_receive_message('SYS_STATUS')
1242
self.progress("Got (%s)" % str(m))
1243
self.progress("Testing receiver enabled")
1244
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
1245
raise NotAchievedException("Receiver not enabled")
1246
self.progress("Testing receiver present")
1247
if (not (m.onboard_control_sensors_present & receiver_bit)):
1248
raise NotAchievedException("Receiver not present")
1249
self.progress("Testing receiver health")
1250
if (m.onboard_control_sensors_health & receiver_bit):
1251
raise NotAchievedException("Sensor healthy when it shouldn't be")
1252
self.progress("Making RC work again")
1253
self.set_parameter("SIM_RC_FAIL", 0)
1254
# have to allow time for RC to be fetched from SITL
1255
self.progress("Giving receiver time to recover")
1256
self.delay_sim_time(0.5)
1257
self.do_timesync_roundtrip()
1258
m = self.assert_receive_message('SYS_STATUS')
1259
self.progress("Testing receiver enabled")
1260
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
1261
raise NotAchievedException("Receiver not enabled")
1262
self.progress("Testing receiver present")
1263
if (not (m.onboard_control_sensors_present & receiver_bit)):
1264
raise NotAchievedException("Receiver not present")
1265
self.progress("Testing receiver health")
1266
if (not (m.onboard_control_sensors_health & receiver_bit)):
1267
raise NotAchievedException("Receiver not healthy")
1268
self.change_mode('MANUAL')
1269
1270
self.progress("Ensure long failsafe can trigger when short failsafe disabled")
1271
self.context_push()
1272
self.context_collect("STATUSTEXT")
1273
self.set_parameters({
1274
"FS_SHORT_ACTN": 3, # 3 means disabled
1275
"SIM_RC_FAIL": 1,
1276
})
1277
self.wait_statustext("Long failsafe on", check_context=True)
1278
self.wait_mode("RTL")
1279
# self.context_clear_collection("STATUSTEXT")
1280
self.set_parameter("SIM_RC_FAIL", 0)
1281
self.wait_text("Long Failsafe Cleared", check_context=True)
1282
self.change_mode("MANUAL")
1283
1284
self.progress("Trying again with THR_FS_VALUE")
1285
self.set_parameters({
1286
"THR_FS_VALUE": 960,
1287
"SIM_RC_FAIL": 2,
1288
})
1289
self.wait_statustext("Long Failsafe on", check_context=True)
1290
self.wait_mode("RTL")
1291
self.context_pop()
1292
1293
self.start_subtest("Not use RC throttle input when THR_FAILSAFE==2")
1294
self.takeoff(100)
1295
self.set_rc(3, 1800)
1296
self.set_rc(1, 2000)
1297
self.wait_attitude(desroll=45, timeout=1)
1298
self.context_push()
1299
self.set_parameters({
1300
"THR_FAILSAFE": 2,
1301
"SIM_RC_FAIL": 1, # no pulses
1302
})
1303
self.delay_sim_time(1)
1304
self.wait_attitude(desroll=0, timeout=5)
1305
self.assert_servo_channel_value(3, self.get_parameter("RC3_MIN"))
1306
self.set_parameters({
1307
"SIM_RC_FAIL": 0, # fix receiver
1308
})
1309
self.zero_throttle()
1310
self.disarm_vehicle(force=True)
1311
self.context_pop()
1312
self.reboot_sitl()
1313
1314
def ThrottleFailsafeFence(self):
1315
'''Fly fence survives throttle failsafe'''
1316
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
1317
1318
self.progress("Checking fence is not present before being configured")
1319
m = self.assert_receive_message('SYS_STATUS')
1320
self.progress("Got (%s)" % str(m))
1321
if (m.onboard_control_sensors_enabled & fence_bit):
1322
raise NotAchievedException("Fence enabled before being configured")
1323
1324
self.change_mode('MANUAL')
1325
self.wait_ready_to_arm()
1326
1327
self.load_fence("CMAC-fence.txt")
1328
1329
self.set_parameter("RC7_OPTION", 11) # AC_Fence uses Aux switch functionality
1330
self.set_parameter("FENCE_ACTION", 4) # Fence action Brake
1331
self.set_rc_from_map({
1332
3: 1000,
1333
7: 2000,
1334
}) # Turn fence on with aux function
1335
1336
m = self.assert_receive_message('FENCE_STATUS', timeout=2, verbose=True)
1337
1338
self.progress("Checking fence is initially OK")
1339
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE,
1340
present=True,
1341
enabled=True,
1342
healthy=True,
1343
verbose=True,
1344
timeout=30)
1345
1346
self.set_parameter("THR_FS_VALUE", 960)
1347
self.progress("Failing receiver (throttle-to-950)")
1348
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
1349
self.wait_mode("CIRCLE")
1350
self.delay_sim_time(1) # give
1351
self.do_timesync_roundtrip()
1352
1353
self.progress("Checking fence is OK after receiver failure (bind-values)")
1354
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
1355
m = self.assert_receive_message('SYS_STATUS')
1356
if (not (m.onboard_control_sensors_enabled & fence_bit)):
1357
raise NotAchievedException("Fence not enabled after RC fail")
1358
self.do_fence_disable() # Ensure the fence is disabled after test
1359
1360
def GCSFailsafe(self):
1361
'''Ensure Long-Failsafe works on GCS loss'''
1362
self.start_subtest("Test Failsafe: RTL")
1363
self.load_sample_mission()
1364
self.set_parameters({
1365
"FS_GCS_ENABL": 1,
1366
"FS_LONG_ACTN": 1,
1367
"RTL_AUTOLAND": 1,
1368
"MAV_GCS_SYSID": self.mav.source_system,
1369
})
1370
self.takeoff()
1371
self.change_mode('LOITER')
1372
self.progress("Disconnecting GCS")
1373
self.set_heartbeat_rate(0)
1374
self.wait_mode("RTL", timeout=10)
1375
self.set_heartbeat_rate(self.speedup)
1376
self.end_subtest("Completed RTL Failsafe test")
1377
1378
self.start_subtest("Test Failsafe: FBWA Glide")
1379
self.set_parameters({
1380
"FS_LONG_ACTN": 2,
1381
})
1382
self.change_mode('AUTO')
1383
self.progress("Disconnecting GCS")
1384
self.set_heartbeat_rate(0)
1385
self.wait_mode("FBWA", timeout=10)
1386
self.set_heartbeat_rate(self.speedup)
1387
self.end_subtest("Completed FBWA Failsafe test")
1388
1389
self.start_subtest("Test Failsafe: Deploy Parachute")
1390
self.load_mission("plane-parachute-mission.txt")
1391
self.set_current_waypoint(1)
1392
self.set_parameters({
1393
"CHUTE_ENABLED": 1,
1394
"CHUTE_TYPE": 10,
1395
"SERVO9_FUNCTION": 27,
1396
"SIM_PARA_ENABLE": 1,
1397
"SIM_PARA_PIN": 9,
1398
"FS_LONG_ACTN": 3,
1399
})
1400
self.change_mode("AUTO")
1401
self.progress("Disconnecting GCS")
1402
self.set_heartbeat_rate(0)
1403
self.wait_statustext("BANG", timeout=60)
1404
self.set_heartbeat_rate(self.speedup)
1405
self.disarm_vehicle(force=True)
1406
self.reboot_sitl()
1407
self.end_subtest("Completed Parachute Failsafe test")
1408
1409
def TestGripperMission(self):
1410
'''Test Gripper mission items'''
1411
self.set_parameter("RTL_AUTOLAND", 1)
1412
self.load_mission("plane-gripper-mission.txt")
1413
self.set_current_waypoint(1)
1414
self.change_mode('AUTO')
1415
self.wait_ready_to_arm()
1416
self.arm_vehicle()
1417
self.wait_statustext("Gripper Grabbed", timeout=60)
1418
self.wait_statustext("Gripper Released", timeout=60)
1419
self.wait_statustext("Auto disarmed", timeout=60)
1420
1421
def assert_fence_sys_status(self, present, enabled, health):
1422
self.delay_sim_time(1)
1423
self.do_timesync_roundtrip()
1424
m = self.assert_receive_message('SYS_STATUS')
1425
tests = [
1426
("present", present, m.onboard_control_sensors_present),
1427
("enabled", enabled, m.onboard_control_sensors_enabled),
1428
("health", health, m.onboard_control_sensors_health),
1429
]
1430
bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
1431
for test in tests:
1432
(name, want, field) = test
1433
got = (field & bit) != 0
1434
if want != got:
1435
raise NotAchievedException("fence status incorrect; %s want=%u got=%u" %
1436
(name, want, got))
1437
1438
def MODE_SWITCH_RESET(self):
1439
'''test the MODE_SWITCH_RESET auxiliary function'''
1440
self.set_parameters({
1441
"RC9_OPTION": 96,
1442
})
1443
1444
self.progress("Using RC to change modes")
1445
self.set_rc(8, 1500)
1446
self.wait_mode('FBWA')
1447
1448
self.progress("Killing RC to engage RC failsafe")
1449
self.set_parameter('SIM_RC_FAIL', 1)
1450
self.wait_mode('RTL')
1451
1452
self.progress("Reinstating RC")
1453
self.set_parameter('SIM_RC_FAIL', 0)
1454
1455
self.progress("Ensuring we don't automatically revert mode")
1456
self.delay_sim_time(2)
1457
self.assert_mode_is('RTL')
1458
1459
self.progress("Ensuring MODE_SWITCH_RESET switch resets to pre-failsafe mode")
1460
self.set_rc(9, 2000)
1461
self.wait_mode('FBWA')
1462
1463
def FenceStatic(self):
1464
'''Test Basic Fence Functionality'''
1465
self.progress("Checking for bizarre healthy-when-not-present-or-enabled")
1466
self.set_parameter("FENCE_TYPE", 4) # Start by only setting polygon fences, otherwise fence will report present
1467
self.assert_fence_sys_status(False, False, True)
1468
self.load_fence("CMAC-fence.txt")
1469
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
1470
if m is not None:
1471
raise NotAchievedException("Got FENCE_STATUS unexpectedly")
1472
self.set_parameter("FENCE_ACTION", 0) # report only
1473
self.assert_fence_sys_status(True, False, True)
1474
self.set_parameter("FENCE_ACTION", 1) # RTL
1475
self.assert_fence_sys_status(True, False, True)
1476
self.do_fence_enable()
1477
self.assert_fence_sys_status(True, True, True)
1478
m = self.assert_receive_message('FENCE_STATUS', timeout=2)
1479
if m.breach_status:
1480
raise NotAchievedException("Breached fence unexpectedly (%u)" %
1481
(m.breach_status))
1482
self.do_fence_disable()
1483
self.assert_fence_sys_status(True, False, True)
1484
self.set_parameter("FENCE_ACTION", 1)
1485
self.assert_fence_sys_status(True, False, True)
1486
self.set_parameter("FENCE_ACTION", 0)
1487
self.assert_fence_sys_status(True, False, True)
1488
self.clear_fence()
1489
if self.get_parameter("FENCE_TOTAL") != 0:
1490
raise NotAchievedException("Expected zero points remaining")
1491
self.assert_fence_sys_status(False, False, True)
1492
self.progress("Trying to enable fence with no points")
1493
self.do_fence_enable(want_result=mavutil.mavlink.MAV_RESULT_FAILED)
1494
1495
# test a rather unfortunate behaviour:
1496
self.progress("Killing a live fence with fence-clear")
1497
self.load_fence("CMAC-fence.txt")
1498
self.set_parameter("FENCE_ACTION", 1) # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
1499
self.do_fence_enable()
1500
self.assert_fence_sys_status(True, True, True)
1501
self.clear_fence()
1502
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, False, False, True)
1503
if self.get_parameter("FENCE_TOTAL") != 0:
1504
raise NotAchievedException("Expected zero points remaining")
1505
self.assert_fence_sys_status(False, False, True)
1506
self.do_fence_disable()
1507
1508
# ensure that a fence is present if it is tin can, min alt or max alt
1509
self.progress("Test other fence types (tin-can, min alt, max alt")
1510
self.set_parameter("FENCE_TYPE", 1) # max alt
1511
self.assert_fence_sys_status(True, False, True)
1512
self.set_parameter("FENCE_TYPE", 8) # min alt
1513
self.assert_fence_sys_status(True, False, True)
1514
self.set_parameter("FENCE_TYPE", 2) # tin can
1515
self.assert_fence_sys_status(True, False, True)
1516
1517
# Test cannot arm if outside of fence and fence is enabled
1518
self.progress("Test Arming while vehicle below FENCE_ALT_MIN")
1519
default_fence_alt_min = self.get_parameter("FENCE_ALT_MIN")
1520
self.set_parameter("FENCE_ALT_MIN", 50)
1521
self.set_parameter("FENCE_TYPE", 8) # Enables minimum altitude breaches
1522
self.do_fence_enable()
1523
self.delay_sim_time(2) # Allow breach to propagate
1524
self.assert_fence_enabled()
1525
1526
self.try_arm(False, "Vehicle breaching Min Alt fence")
1527
self.do_fence_disable()
1528
self.set_parameter("FENCE_ALT_MIN", default_fence_alt_min)
1529
1530
# Test arming outside inclusion zone
1531
self.progress("Test arming while Vehicle breaching of inclusion zone")
1532
self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types
1533
self.upload_fences_from_locations([(
1534
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
1535
mavutil.location(1.000, 1.000, 0, 0),
1536
mavutil.location(1.000, 1.001, 0, 0),
1537
mavutil.location(1.001, 1.001, 0, 0),
1538
mavutil.location(1.001, 1.000, 0, 0)
1539
]
1540
)])
1541
self.delay_sim_time(10) # let fence check run so it loads-from-eeprom
1542
self.do_fence_enable()
1543
self.assert_fence_enabled()
1544
self.delay_sim_time(2) # Allow breach to propagate
1545
self.try_arm(False, "Vehicle breaching Polygon fence")
1546
self.do_fence_disable()
1547
self.clear_fence()
1548
1549
self.progress("Test arming while vehicle inside exclusion zone")
1550
self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types
1551
home_loc = self.mav.location()
1552
locs = [
1553
mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0),
1554
mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0),
1555
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0),
1556
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
1557
]
1558
self.upload_fences_from_locations([
1559
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, locs),
1560
])
1561
self.delay_sim_time(10) # let fence check run so it loads-from-eeprom
1562
self.do_fence_enable()
1563
self.assert_fence_enabled()
1564
self.delay_sim_time(2) # Allow breach to propagate
1565
self.try_arm(False, "Vehicle breaching Polygon fence")
1566
self.do_fence_disable()
1567
1568
def test_fence_breach_circle_at(self, loc, disable_on_breach=False):
1569
self.load_fence("CMAC-fence.txt")
1570
want_radius = 100
1571
# when ArduPlane is fixed, remove this fudge factor
1572
REALLY_BAD_FUDGE_FACTOR = 1.16
1573
expected_radius = REALLY_BAD_FUDGE_FACTOR * want_radius
1574
self.set_parameters({
1575
"RTL_RADIUS": want_radius,
1576
"NAVL1_LIM_BANK": 60,
1577
"FENCE_ACTION": 1, # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
1578
})
1579
1580
self.wait_ready_to_arm() # need an origin to load fence
1581
1582
self.do_fence_enable()
1583
self.assert_fence_sys_status(True, True, True)
1584
1585
self.takeoff(alt=45, alt_max=300)
1586
1587
tstart = self.get_sim_time()
1588
while True:
1589
if self.get_sim_time() - tstart > 30:
1590
raise NotAchievedException("Did not breach fence")
1591
m = self.assert_receive_message('FENCE_STATUS', timeout=2)
1592
if m.breach_status == 0:
1593
continue
1594
1595
# we've breached; check our state;
1596
if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY:
1597
raise NotAchievedException("Unexpected breach type %u" %
1598
(m.breach_type,))
1599
if m.breach_count == 0:
1600
raise NotAchievedException("Unexpected breach count %u" %
1601
(m.breach_count,))
1602
self.assert_fence_sys_status(True, True, False)
1603
break
1604
1605
self.wait_circling_point_with_radius(loc, expected_radius)
1606
self.do_fence_disable()
1607
self.disarm_vehicle(force=True)
1608
self.reboot_sitl()
1609
1610
def FenceRTL(self):
1611
'''Test Fence RTL'''
1612
self.progress("Testing FENCE_ACTION_RTL no rally point")
1613
# have to disable the fence once we've breached or we breach
1614
# it as part of the loiter-at-home!
1615
self.test_fence_breach_circle_at(self.home_position_as_mav_location())
1616
1617
def FenceRTLRally(self):
1618
'''Test Fence RTL Rally'''
1619
self.progress("Testing FENCE_ACTION_RTL with rally point")
1620
1621
self.wait_ready_to_arm()
1622
loc = self.home_relative_loc_ne(50, -50)
1623
self.upload_rally_points_from_locations([loc])
1624
self.test_fence_breach_circle_at(loc)
1625
1626
def FenceRetRally(self):
1627
""" Tests the FENCE_RET_RALLY flag, either returning to fence return point,
1628
or rally point """
1629
target_system = 1
1630
target_component = 1
1631
self.progress("Testing FENCE_ACTION_RTL with fence rally point")
1632
1633
self.wait_ready_to_arm()
1634
1635
# Grab a location for fence return point, and upload it.
1636
fence_loc = self.home_position_as_mav_location()
1637
self.location_offset_ne(fence_loc, 50, 50)
1638
fence_return_mission_items = [
1639
self.mav.mav.mission_item_int_encode(
1640
target_system,
1641
target_component,
1642
0, # seq
1643
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1644
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1645
0, # current
1646
0, # autocontinue
1647
0, # p1
1648
0, # p2
1649
0, # p3
1650
0, # p4
1651
int(fence_loc.lat * 1e7), # latitude
1652
int(fence_loc.lng * 1e7), # longitude
1653
0, # altitude
1654
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
1655
)
1656
]
1657
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
1658
fence_return_mission_items)
1659
self.delay_sim_time(1)
1660
1661
# Grab a location for rally point, and upload it.
1662
rally_loc = self.home_relative_loc_ne(-50, 50)
1663
self.upload_rally_points_from_locations([rally_loc])
1664
1665
return_radius = 100
1666
return_alt = 80
1667
self.set_parameters({
1668
"RTL_RADIUS": return_radius,
1669
"FENCE_ACTION": 6, # Set Fence Action to Guided
1670
"FENCE_TYPE": 8, # Only use fence floor
1671
"FENCE_RET_ALT": return_alt,
1672
})
1673
self.do_fence_enable()
1674
self.assert_fence_enabled()
1675
1676
self.takeoff(alt=50, alt_max=300)
1677
# Trigger fence breach, fly to rally location
1678
self.set_parameters({
1679
"FENCE_RET_RALLY": 1,
1680
"FENCE_ALT_MIN": 60,
1681
})
1682
self.wait_circling_point_with_radius(rally_loc, return_radius)
1683
self.set_parameter("FENCE_ALT_MIN", 0) # Clear fence breach
1684
1685
# 10 second fence min retrigger time
1686
self.delay_sim_time(15)
1687
1688
# Fly up before re-triggering fence breach. Fly to fence return point
1689
self.change_altitude(30, relative=True)
1690
self.set_parameters({
1691
"FENCE_RET_RALLY": 0,
1692
"FENCE_ALT_MIN": 60,
1693
})
1694
self.wait_altitude(altitude_min=return_alt-3,
1695
altitude_max=return_alt+3,
1696
relative=True)
1697
self.wait_circling_point_with_radius(fence_loc, return_radius)
1698
self.do_fence_disable() # Disable fence so we can land
1699
self.fly_home_land_and_disarm() # Pack it up, we're going home.
1700
1701
def TerrainRally(self):
1702
""" Tests terrain follow with a rally point """
1703
self.context_push()
1704
self.install_terrain_handlers_context()
1705
1706
def terrain_following_above_80m(mav, m):
1707
if m.get_type() == 'TERRAIN_REPORT':
1708
if m.current_height < 50:
1709
raise NotAchievedException(
1710
"TERRAIN_REPORT.current_height below 50m %fm" % m.current_height)
1711
if m.get_type() == 'VFR_HUD':
1712
if m.groundspeed < 2:
1713
raise NotAchievedException("hit ground")
1714
1715
def terrain_wait_path(loc1, loc2, steps):
1716
'''wait till we have terrain for N steps from loc1 to loc2'''
1717
tstart = self.get_sim_time_cached()
1718
self.progress("Waiting for terrain data")
1719
while True:
1720
now = self.get_sim_time_cached()
1721
if now - tstart > 60:
1722
raise NotAchievedException("Did not get correct required terrain")
1723
for i in range(steps):
1724
lat = loc1.lat + i * (loc2.lat-loc1.lat)/steps
1725
lon = loc1.lng + i * (loc2.lng-loc1.lng)/steps
1726
self.mav.mav.terrain_check_send(int(lat*1.0e7), int(lon*1.0e7))
1727
1728
report = self.assert_receive_message('TERRAIN_REPORT', timeout=60)
1729
self.progress("Terrain pending=%u" % report.pending)
1730
if report.pending == 0:
1731
break
1732
self.progress("Got required terrain")
1733
1734
self.wait_ready_to_arm()
1735
homeloc = self.mav.location()
1736
1737
guided_loc = mavutil.location(-35.39723762, 149.07284612, homeloc.alt+99.0, 0)
1738
rally_loc = mavutil.location(-35.3654952000, 149.1558698000, homeloc.alt+100, 0)
1739
1740
terrain_wait_path(homeloc, rally_loc, 10)
1741
1742
# set a rally point to the west of home
1743
self.upload_rally_points_from_locations([rally_loc])
1744
1745
self.set_parameter("TKOFF_ALT", 100)
1746
self.change_mode("TAKEOFF")
1747
self.wait_ready_to_arm()
1748
self.arm_vehicle()
1749
self.set_parameter("TERRAIN_FOLLOW", 1)
1750
self.wait_altitude(90, 120, timeout=30, relative=True)
1751
self.progress("Done takeoff")
1752
1753
self.install_message_hook_context(terrain_following_above_80m)
1754
1755
self.change_mode("GUIDED")
1756
self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
1757
self.progress("Flying to guided location")
1758
self.wait_location(
1759
guided_loc,
1760
accuracy=200,
1761
timeout=600,
1762
height_accuracy=10,
1763
)
1764
1765
self.progress("Reached guided location")
1766
self.set_parameter("RALLY_LIMIT_KM", 50)
1767
self.change_mode("RTL")
1768
self.progress("Flying to rally point")
1769
self.wait_location(
1770
rally_loc,
1771
accuracy=200,
1772
timeout=600,
1773
height_accuracy=10,
1774
)
1775
self.progress("Reached rally point with TERRAIN_FOLLOW")
1776
1777
# Fly back to guided location
1778
self.change_mode("GUIDED")
1779
self.send_do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
1780
self.progress("Flying to back to guided location")
1781
1782
# Disable terrain following and re-load rally point with relative to terrain altitude
1783
self.set_parameter("TERRAIN_FOLLOW", 0)
1784
1785
rally_item = [self.create_MISSION_ITEM_INT(
1786
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
1787
x=int(rally_loc.lat*1e7),
1788
y=int(rally_loc.lng*1e7),
1789
z=rally_loc.alt,
1790
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
1791
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY
1792
)]
1793
self.correct_wp_seq_numbers(rally_item)
1794
self.check_rally_upload_download(rally_item)
1795
1796
# Once back at guided location re-trigger RTL
1797
self.wait_location(
1798
guided_loc,
1799
accuracy=200,
1800
timeout=600,
1801
height_accuracy=10,
1802
)
1803
1804
self.change_mode("RTL")
1805
self.progress("Flying to rally point")
1806
self.wait_location(
1807
rally_loc,
1808
accuracy=200,
1809
timeout=600,
1810
height_accuracy=10,
1811
)
1812
self.progress("Reached rally point with terrain alt frame")
1813
1814
self.context_pop()
1815
self.disarm_vehicle(force=True)
1816
self.reboot_sitl()
1817
1818
def Parachute(self):
1819
'''Test Parachute'''
1820
self.set_rc(9, 1000)
1821
self.set_parameters({
1822
"CHUTE_ENABLED": 1,
1823
"CHUTE_TYPE": 10,
1824
"SERVO9_FUNCTION": 27,
1825
"SIM_PARA_ENABLE": 1,
1826
"SIM_PARA_PIN": 9,
1827
})
1828
1829
self.load_mission("plane-parachute-mission.txt")
1830
self.set_current_waypoint(1)
1831
self.change_mode('AUTO')
1832
self.wait_ready_to_arm()
1833
self.arm_vehicle()
1834
self.wait_statustext("BANG", timeout=60)
1835
self.disarm_vehicle(force=True)
1836
self.reboot_sitl()
1837
1838
def ParachuteSinkRate(self):
1839
'''Test Parachute (SinkRate triggering)'''
1840
self.set_rc(9, 1000)
1841
self.set_parameters({
1842
"CHUTE_ENABLED": 1,
1843
"CHUTE_TYPE": 10,
1844
"SERVO9_FUNCTION": 27,
1845
"SIM_PARA_ENABLE": 1,
1846
"SIM_PARA_PIN": 9,
1847
"CHUTE_CRT_SINK": 9,
1848
})
1849
1850
self.progress("Takeoff")
1851
self.takeoff(alt=300)
1852
1853
self.progress("Diving")
1854
self.set_rc(2, 2000)
1855
self.wait_statustext("BANG", timeout=60)
1856
1857
self.disarm_vehicle(force=True)
1858
self.reboot_sitl()
1859
1860
def run_subtest(self, desc, func):
1861
self.start_subtest(desc)
1862
func()
1863
1864
def fly_ahrs2_test(self):
1865
'''check secondary estimator is looking OK'''
1866
1867
ahrs2 = self.assert_receive_message('AHRS2', verbose=1)
1868
gpi = self.assert_receive_message('GLOBAL_POSITION_INT', verbose=1)
1869
if self.get_distance_int(gpi, ahrs2) > 10:
1870
raise NotAchievedException("Secondary location looks bad")
1871
1872
self.check_attitudes_match()
1873
1874
def MainFlight(self):
1875
'''Lots of things in one flight'''
1876
self.change_mode('MANUAL')
1877
1878
self.progress("Asserting we do support transfer of fence via mission item protocol")
1879
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_MISSION_FENCE)
1880
1881
self.run_subtest("Takeoff", self.takeoff)
1882
1883
self.run_subtest("Set Attitude Target", self.set_attitude_target)
1884
1885
self.run_subtest("Fly left circuit", self.fly_left_circuit)
1886
1887
self.run_subtest("Left roll", lambda: self.axial_left_roll(1))
1888
1889
self.run_subtest("Inside loop", self.inside_loop)
1890
1891
self.run_subtest("Stabilize test", self.test_stabilize)
1892
1893
self.run_subtest("ACRO test", self.test_acro)
1894
1895
self.run_subtest("FBWB test", self.test_FBWB)
1896
1897
self.run_subtest("CRUISE test", lambda: self.test_FBWB(mode='CRUISE'))
1898
1899
self.run_subtest("RTL test", self.fly_RTL)
1900
1901
self.run_subtest("LOITER test", self.fly_LOITER)
1902
1903
self.run_subtest("CIRCLE test", self.fly_CIRCLE)
1904
1905
self.run_subtest("AHRS2 test", self.fly_ahrs2_test)
1906
1907
self.run_subtest("Mission test",
1908
lambda: self.fly_mission("ap1.txt", strict=False))
1909
1910
def PitotBlockage(self):
1911
'''Test detection and isolation of a blocked pitot tube'''
1912
self.set_parameters({
1913
"ARSPD_OPTIONS": 15,
1914
"ARSPD_USE": 1,
1915
"SIM_WIND_SPD": 7,
1916
"SIM_WIND_DIR": 0,
1917
"ARSPD_WIND_MAX": 15,
1918
})
1919
self.takeoff(alt=50, mode='TAKEOFF')
1920
# simulate the effect of a blocked pitot tube
1921
self.set_parameter("ARSPD_RATIO", 0.1)
1922
self.delay_sim_time(10)
1923
if (self.get_parameter("ARSPD_USE") == 0):
1924
self.progress("Faulty Sensor Disabled")
1925
else:
1926
raise NotAchievedException("Airspeed Sensor Not Disabled")
1927
self.delay_sim_time(20)
1928
# simulate the effect of blockage partially clearing
1929
self.set_parameter("ARSPD_RATIO", 1.0)
1930
self.delay_sim_time(60)
1931
if (self.get_parameter("ARSPD_USE") == 0):
1932
self.progress("Faulty Sensor Remains Disabled")
1933
else:
1934
raise NotAchievedException("Fault Sensor Re-Enabled")
1935
# simulate the effect of blockage fully clearing
1936
self.set_parameter("ARSPD_RATIO", 2.0)
1937
self.delay_sim_time(60)
1938
if (self.get_parameter("ARSPD_USE") == 1):
1939
self.progress("Sensor Re-Enabled")
1940
else:
1941
raise NotAchievedException("Airspeed Sensor Not Re-Enabled")
1942
self.fly_home_land_and_disarm()
1943
1944
def AIRSPEED_AUTOCAL(self):
1945
'''Test AIRSPEED_AUTOCAL'''
1946
self.progress("Ensure no AIRSPEED_AUTOCAL on ground")
1947
self.set_parameters({
1948
"ARSPD_AUTOCAL": 1,
1949
"ARSPD_PIN": 2,
1950
"ARSPD_RATIO": 0,
1951
"ARSPD2_RATIO": 4,
1952
"ARSPD2_TYPE": 3, # MS5525
1953
"ARSPD2_BUS": 1,
1954
"ARSPD2_AUTOCAL": 1,
1955
"SIM_ARSPD2_OFS": 1900, # default is 2013
1956
1957
"RTL_AUTOLAND": 1,
1958
})
1959
self.context_collect('STATUSTEXT')
1960
self.reboot_sitl()
1961
1962
self.assert_not_receive_message('AIRSPEED_AUTOCAL', timeout=5)
1963
1964
# these are boot-time calibration messages:
1965
self.wait_statustext('Airspeed 1 calibrated', check_context=True, timeout=30)
1966
self.wait_statustext('Airspeed 2 calibrated', check_context=True)
1967
1968
mission_filepath = "flaps.txt"
1969
self.load_mission(mission_filepath)
1970
self.wait_ready_to_arm()
1971
self.arm_vehicle()
1972
self.change_mode("AUTO")
1973
self.progress("Ensure AIRSPEED_AUTOCAL in air")
1974
self.assert_receive_message('AIRSPEED_AUTOCAL')
1975
self.wait_statustext("Airspeed 0 ratio reset", check_context=True, timeout=70)
1976
self.wait_statustext("Airspeed 1 ratio reset", check_context=True, timeout=70)
1977
self.fly_home_land_and_disarm()
1978
1979
def deadreckoning_main(self, disable_airspeed_sensor=False):
1980
self.context_push()
1981
self.set_parameter("EK3_OPTIONS", 1)
1982
self.set_parameter("AHRS_OPTIONS", 3)
1983
self.set_parameter("LOG_REPLAY", 1)
1984
self.reboot_sitl()
1985
self.wait_ready_to_arm()
1986
1987
if disable_airspeed_sensor:
1988
max_allowed_divergence = 300
1989
else:
1990
max_allowed_divergence = 150
1991
self.install_message_hook_context(vehicle_test_suite.TestSuite.ValidateGlobalPositionIntAgainstSimState(self, max_allowed_divergence=max_allowed_divergence)) # noqa
1992
1993
try:
1994
# wind is from the West:
1995
self.set_parameter("SIM_WIND_DIR", 270)
1996
# light winds:
1997
self.set_parameter("SIM_WIND_SPD", 10)
1998
if disable_airspeed_sensor:
1999
self.set_parameter("ARSPD_USE", 0)
2000
2001
self.takeoff(50)
2002
loc = self.mav.location()
2003
self.location_offset_ne(loc, 500, 500)
2004
self.run_cmd_int(
2005
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
2006
p1=0,
2007
p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
2008
p5=int(loc.lat * 1e7),
2009
p6=int(loc.lng * 1e7),
2010
p7=100, # alt
2011
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
2012
)
2013
self.wait_location(loc, accuracy=100)
2014
self.progress("Orbit with GPS and learn wind")
2015
# allow longer to learn wind if there is no airspeed sensor
2016
if disable_airspeed_sensor:
2017
self.delay_sim_time(180)
2018
else:
2019
self.delay_sim_time(20)
2020
self.set_parameter("SIM_GPS1_ENABLE", 0)
2021
self.progress("Continue orbit without GPS")
2022
self.delay_sim_time(20)
2023
self.change_mode("RTL")
2024
self.wait_distance_to_home(100, 200, timeout=200)
2025
# go into LOITER to create additional time for a GPS re-enable test
2026
self.change_mode("LOITER")
2027
self.set_parameter("SIM_GPS1_ENABLE", 1)
2028
t_enabled = self.get_sim_time()
2029
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
2030
# to prevent bad GPS being used when coming back after loss of lock due to interence.
2031
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=15)
2032
if self.get_sim_time() < (t_enabled+9):
2033
raise NotAchievedException("GPS use re-started too quickly")
2034
# wait for EKF and vehicle position to stabilise, then test response to jamming
2035
self.delay_sim_time(20)
2036
2037
self.set_parameter("AHRS_OPTIONS", 1)
2038
self.set_parameter("SIM_GPS1_JAM", 1)
2039
self.delay_sim_time(13)
2040
self.set_parameter("SIM_GPS1_JAM", 0)
2041
t_enabled = self.get_sim_time()
2042
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
2043
# to prevent bad GPS being used when coming back after loss of lock due to interence.
2044
# The EKF_STATUS_REPORT does not tell us when the good to align check passes, so the minimum time
2045
# value of 3.0 seconds is an arbitrary value set on inspection of dataflash logs from this test
2046
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=20)
2047
time_since_jamming_stopped = self.get_sim_time() - t_enabled
2048
if time_since_jamming_stopped < 3:
2049
raise NotAchievedException("GPS use re-started %f sec after jamming stopped" % time_since_jamming_stopped)
2050
self.set_rc(3, 1000)
2051
self.fly_home_land_and_disarm()
2052
finally:
2053
pass
2054
2055
self.context_pop()
2056
self.reboot_sitl()
2057
2058
def Deadreckoning(self):
2059
'''Test deadreckoning support'''
2060
self.deadreckoning_main()
2061
2062
def DeadreckoningNoAirSpeed(self):
2063
'''Test deadreckoning support with no airspeed sensor'''
2064
self.deadreckoning_main(disable_airspeed_sensor=True)
2065
2066
def ClimbBeforeTurn(self):
2067
'''Test climb-before-turn'''
2068
self.wait_ready_to_arm()
2069
self.set_parameters({
2070
"FLIGHT_OPTIONS": 0,
2071
"RTL_ALTITUDE": 80,
2072
"RTL_AUTOLAND": 1,
2073
})
2074
takeoff_alt = 10
2075
self.takeoff(alt=takeoff_alt)
2076
self.change_mode("CRUISE")
2077
self.wait_distance_to_home(500, 1000, timeout=60)
2078
self.change_mode("RTL")
2079
expected_alt = self.get_parameter("RTL_ALTITUDE")
2080
2081
home = self.home_position_as_mav_location()
2082
distance = self.get_distance(home, self.mav.location())
2083
2084
self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80)
2085
2086
new_distance = self.get_distance(home, self.mav.location())
2087
# We should be closer to home.
2088
if new_distance > distance:
2089
raise NotAchievedException(
2090
"Expected to be closer to home (was %fm, now %fm)."
2091
% (distance, new_distance)
2092
)
2093
2094
self.fly_home_land_and_disarm()
2095
self.set_current_waypoint(0, check_afterwards=False)
2096
2097
self.change_mode("MANUAL")
2098
self.set_rc(3, 1000)
2099
2100
self.wait_ready_to_arm()
2101
self.set_parameters({
2102
"FLIGHT_OPTIONS": 16,
2103
"RTL_ALTITUDE": 100,
2104
})
2105
self.takeoff(alt=takeoff_alt)
2106
self.change_mode("CRUISE")
2107
self.wait_distance_to_home(500, 1000, timeout=60)
2108
self.change_mode("RTL")
2109
2110
home = self.home_position_as_mav_location()
2111
distance = self.get_distance(home, self.mav.location())
2112
2113
self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80)
2114
2115
new_distance = self.get_distance(home, self.mav.location())
2116
# We should be farther from to home.
2117
if new_distance < distance:
2118
raise NotAchievedException(
2119
"Expected to be farther from home (was %fm, now %fm)."
2120
% (distance, new_distance)
2121
)
2122
2123
self.fly_home_land_and_disarm(timeout=240)
2124
2125
def RTL_CLIMB_MIN(self):
2126
'''Test RTL_CLIMB_MIN'''
2127
self.wait_ready_to_arm()
2128
rtl_climb_min = 100
2129
self.set_parameter("RTL_CLIMB_MIN", rtl_climb_min)
2130
takeoff_alt = 50
2131
self.takeoff(alt=takeoff_alt)
2132
self.change_mode('CRUISE')
2133
self.wait_distance_to_home(1000, 1500, timeout=60)
2134
post_cruise_alt = self.get_altitude(relative=True)
2135
self.change_mode('RTL')
2136
expected_alt = self.get_parameter("RTL_ALTITUDE")
2137
if expected_alt == -1:
2138
expected_alt = self.get_altitude(relative=True)
2139
2140
# ensure we're about half-way-down at the half-way-home stage:
2141
self.wait_distance_to_nav_target(
2142
0,
2143
500,
2144
timeout=240,
2145
)
2146
alt = self.get_altitude(relative=True)
2147
expected_halfway_alt = expected_alt + (post_cruise_alt + rtl_climb_min - expected_alt)/2.0
2148
if abs(alt - expected_halfway_alt) > 30:
2149
raise NotAchievedException("Not half-way-down and half-way-home (want=%f got=%f" %
2150
(expected_halfway_alt, alt))
2151
self.progress("Half-way-down at half-way-home (want=%f vs got=%f)" %
2152
(expected_halfway_alt, alt))
2153
2154
rtl_radius = self.get_parameter("RTL_RADIUS")
2155
if rtl_radius == 0:
2156
rtl_radius = self.get_parameter("WP_LOITER_RAD")
2157
self.wait_distance_to_nav_target(
2158
0,
2159
rtl_radius,
2160
timeout=120,
2161
)
2162
alt = self.get_altitude(relative=True)
2163
if abs(alt - expected_alt) > 10:
2164
raise NotAchievedException(
2165
"Expected to have %fm altitude at end of RTL (got %f)" %
2166
(expected_alt, alt))
2167
self.fly_home_land_and_disarm()
2168
2169
def sample_enable_parameter(self):
2170
return "Q_ENABLE"
2171
2172
def RangeFinder(self):
2173
'''Test RangeFinder Basic Functionality'''
2174
self.progress("Making sure we don't ordinarily get RANGEFINDER")
2175
self.assert_not_receive_message('RANGEFINDER')
2176
self.assert_not_receive_message('DISTANCE_SENSOR')
2177
2178
self.set_analog_rangefinder_parameters()
2179
2180
self.reboot_sitl()
2181
2182
self.context_set_message_rate_hz('RANGEFINDER', self.sitl_streamrate())
2183
2184
'''ensure rangefinder gives height-above-ground'''
2185
self.load_mission("plane-gripper-mission.txt") # borrow this
2186
self.set_parameter("RTL_AUTOLAND", 1)
2187
self.set_current_waypoint(1)
2188
self.change_mode('AUTO')
2189
self.wait_ready_to_arm()
2190
self.arm_vehicle()
2191
self.wait_waypoint(5, 5, max_dist=100)
2192
rf = self.assert_receive_message('RANGEFINDER')
2193
ds = self.assert_receive_message('DISTANCE_SENSOR')
2194
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
2195
if abs(rf.distance - gpi.relative_alt/1000.0) > 3:
2196
raise NotAchievedException(
2197
"rangefinder alt (%s) disagrees with global-position-int.relative_alt (%s)" %
2198
(rf.distance, gpi.relative_alt/1000.0))
2199
if abs(ds.current_distance*0.01 - gpi.relative_alt/1000.0) > 3:
2200
raise NotAchievedException(
2201
"distance_sensor alt (%s) disagrees with global-position-int.relative_alt (%s)" %
2202
(ds.current_distance*0.01, gpi.relative_alt/1000.0))
2203
self.wait_statustext("Auto disarmed", timeout=60)
2204
2205
self.progress("Ensure RFND messages in log")
2206
if not self.current_onboard_log_contains_message("RFND"):
2207
raise NotAchievedException("No RFND messages in log")
2208
2209
def rc_defaults(self):
2210
ret = super(AutoTestPlane, self).rc_defaults()
2211
ret[3] = 1000
2212
ret[8] = 1800
2213
return ret
2214
2215
def initial_mode_switch_mode(self):
2216
return "MANUAL"
2217
2218
def default_mode(self):
2219
return "MANUAL"
2220
2221
def PIDTuning(self):
2222
'''Test PID Tuning'''
2223
self.change_mode("FBWA") # we don't update PIDs in MANUAL
2224
super(AutoTestPlane, self).PIDTuning()
2225
2226
def AuxModeSwitch(self):
2227
'''Set modes via auxswitches'''
2228
self.set_parameter("FLTMODE1", 1) # circle
2229
self.set_rc(8, 950)
2230
self.wait_mode("CIRCLE")
2231
self.set_rc(9, 1000)
2232
self.set_rc(10, 1000)
2233
self.set_parameters({
2234
"RC9_OPTION": 4, # RTL
2235
"RC10_OPTION": 55, # guided
2236
})
2237
self.set_rc(9, 1900)
2238
self.wait_mode("RTL")
2239
self.set_rc(10, 1900)
2240
self.wait_mode("GUIDED")
2241
2242
self.progress("resetting both switches - should go back to CIRCLE")
2243
self.set_rc(9, 1000)
2244
self.set_rc(10, 1000)
2245
self.wait_mode("CIRCLE")
2246
2247
self.set_rc(9, 1900)
2248
self.wait_mode("RTL")
2249
self.set_rc(10, 1900)
2250
self.wait_mode("GUIDED")
2251
2252
self.progress("Resetting switch should repoll mode switch")
2253
self.set_rc(10, 1000) # this re-polls the mode switch
2254
self.wait_mode("CIRCLE")
2255
self.set_rc(9, 1000)
2256
2257
def wait_for_collision_threat_to_clear(self):
2258
'''wait to get a "clear" collision message", then slurp remaining
2259
messages'''
2260
last_collision = self.get_sim_time()
2261
while True:
2262
now = self.get_sim_time()
2263
if now - last_collision > 5:
2264
return
2265
self.progress("Waiting for collision message")
2266
m = self.mav.recv_match(type='COLLISION', blocking=True, timeout=1)
2267
self.progress("Got (%s)" % str(m))
2268
if m is None:
2269
continue
2270
last_collision = now
2271
2272
def SimADSB(self):
2273
'''Tests to ensure simulated ADSB sensor continues to function'''
2274
self.set_parameters({
2275
"SIM_ADSB_COUNT": 1,
2276
"ADSB_TYPE": 1,
2277
})
2278
self.reboot_sitl()
2279
self.assert_receive_message('ADSB_VEHICLE', timeout=30)
2280
2281
def ADSBResumeActionResumeLoiter(self):
2282
'''ensure we resume auto mission or enter loiter'''
2283
self.set_parameters({
2284
"ADSB_TYPE": 1,
2285
"AVD_ENABLE": 1,
2286
"AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_MOVE_HORIZONTALLY,
2287
"AVD_F_RCVRY": 3, # resume auto or loiter
2288
})
2289
self.reboot_sitl()
2290
self.takeoff(50)
2291
# fly North, create thread to east, wait for flying east
2292
self.start_subtest("Testing loiter resume")
2293
self.reach_heading_manual(0)
2294
here = self.mav.location()
2295
self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30))
2296
self.wait_mode('AVOID_ADSB')
2297
# recovery has the vehicle circling a point... but we don't
2298
# know which point. So wait 'til it looks like it is
2299
# circling, then grab the point, then check we're circling
2300
# it...
2301
self.wait_heading(290)
2302
self.wait_heading(300)
2303
dest = self.position_target_loc()
2304
REALLY_BAD_FUDGE_FACTOR = 1.25 # FIXME
2305
expected_radius = REALLY_BAD_FUDGE_FACTOR * self.get_parameter('WP_LOITER_RAD')
2306
self.wait_circling_point_with_radius(dest, expected_radius)
2307
2308
self.start_subtest("Testing mission resume")
2309
self.reach_heading_manual(270)
2310
self.load_generic_mission("CMAC-circuit.txt", strict=False)
2311
self.change_mode('AUTO')
2312
self.wait_current_waypoint(2)
2313
self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30))
2314
self.wait_mode('AVOID_ADSB')
2315
self.wait_mode('AUTO')
2316
2317
self.fly_home_land_and_disarm()
2318
2319
def ADSBFailActionRTL(self):
2320
'''test ADSB avoidance action of RTL'''
2321
# message ADSB_VEHICLE 37 -353632614 1491652305 0 584070 0 0 0 "bob" 3 1 255 17
2322
self.set_parameter("RC12_OPTION", 38) # avoid-adsb
2323
self.set_rc(12, 2000)
2324
self.set_parameters({
2325
"ADSB_TYPE": 1,
2326
"AVD_ENABLE": 1,
2327
"AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_RTL,
2328
})
2329
self.reboot_sitl()
2330
self.wait_ready_to_arm()
2331
here = self.mav.location()
2332
self.change_mode("FBWA")
2333
self.delay_sim_time(2) # TODO: work out why this is required...
2334
self.test_adsb_send_threatening_adsb_message(here)
2335
self.progress("Waiting for collision message")
2336
m = self.assert_receive_message('COLLISION', timeout=4)
2337
if m.threat_level != 2:
2338
raise NotAchievedException("Expected some threat at least")
2339
if m.action != mavutil.mavlink.MAV_COLLISION_ACTION_RTL:
2340
raise NotAchievedException("Incorrect action; want=%u got=%u" %
2341
(mavutil.mavlink.MAV_COLLISION_ACTION_RTL, m.action))
2342
self.wait_mode("RTL")
2343
2344
self.progress("Sending far-away ABSD_VEHICLE message")
2345
self.mav.mav.adsb_vehicle_send(
2346
37, # ICAO address
2347
int(here.lat+1 * 1e7),
2348
int(here.lng * 1e7),
2349
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
2350
int(here.alt*1000 + 10000), # 10m up
2351
0, # heading in cdeg
2352
0, # horizontal velocity cm/s
2353
0, # vertical velocity cm/s
2354
"bob".encode("ascii"), # callsign
2355
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
2356
1, # time since last communication
2357
65535, # flags
2358
17 # squawk
2359
)
2360
self.wait_for_collision_threat_to_clear()
2361
self.change_mode("FBWA")
2362
2363
self.progress("Disabling ADSB-avoidance with RC channel")
2364
self.set_rc(12, 1000)
2365
self.delay_sim_time(1) # let the switch get polled
2366
self.test_adsb_send_threatening_adsb_message(here)
2367
m = self.assert_not_receive_message('COLLISION', timeout=4)
2368
2369
def GuidedRequest(self, target_system=1, target_component=1):
2370
'''Test handling of MISSION_ITEM in guided mode'''
2371
self.progress("Takeoff")
2372
self.takeoff(alt=50)
2373
self.set_rc(3, 1500)
2374
self.start_subtest("Ensure command bounced outside guided mode")
2375
desired_relative_alt = 33
2376
loc = self.mav.location()
2377
self.location_offset_ne(loc, 300, 300)
2378
loc.alt += desired_relative_alt
2379
self.mav.mav.mission_item_int_send(
2380
target_system,
2381
target_component,
2382
0, # seq
2383
mavutil.mavlink.MAV_FRAME_GLOBAL,
2384
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
2385
2, # current - guided-mode request
2386
0, # autocontinue
2387
0, # p1
2388
0, # p2
2389
0, # p3
2390
0, # p4
2391
int(loc.lat * 1e7), # latitude
2392
int(loc.lng * 1e7), # longitude
2393
loc.alt, # altitude
2394
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
2395
m = self.assert_receive_message('MISSION_ACK', timeout=5)
2396
if m.type != mavutil.mavlink.MAV_MISSION_ERROR:
2397
raise NotAchievedException("Did not get appropriate error")
2398
2399
self.start_subtest("Enter guided and flying somewhere constant")
2400
self.change_mode("GUIDED")
2401
self.mav.mav.mission_item_int_send(
2402
target_system,
2403
target_component,
2404
0, # seq
2405
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
2406
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
2407
2, # current - guided-mode request
2408
0, # autocontinue
2409
0, # p1
2410
0, # p2
2411
0, # p3
2412
0, # p4
2413
int(loc.lat * 1e7), # latitude
2414
int(loc.lng * 1e7), # longitude
2415
desired_relative_alt, # altitude
2416
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
2417
m = self.assert_receive_message('MISSION_ACK', timeout=5)
2418
if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:
2419
raise NotAchievedException("Did not get accepted response")
2420
self.wait_location(loc, accuracy=100) # based on loiter radius
2421
self.wait_altitude(altitude_min=desired_relative_alt-3,
2422
altitude_max=desired_relative_alt+3,
2423
relative=True,
2424
timeout=30)
2425
2426
self.start_subtest("changing alt with mission item in guided mode")
2427
2428
# test changing alt only - NOTE - this is still a
2429
# NAV_WAYPOINT, not a changel-alt request!
2430
desired_relative_alt = desired_relative_alt + 50
2431
self.mav.mav.mission_item_int_send(
2432
target_system,
2433
target_component,
2434
0, # seq
2435
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
2436
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
2437
3, # current - change-alt request
2438
0, # autocontinue
2439
0, # p1
2440
0, # p2
2441
0, # p3
2442
0, # p4
2443
0, # latitude
2444
0,
2445
desired_relative_alt, # altitude
2446
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
2447
2448
self.wait_altitude(altitude_min=desired_relative_alt-3,
2449
altitude_max=desired_relative_alt+3,
2450
relative=True,
2451
timeout=30)
2452
2453
self.fly_home_land_and_disarm()
2454
2455
def LOITER(self):
2456
'''Test Loiter mode'''
2457
# first test old loiter behaviour
2458
self.set_parameter("FLIGHT_OPTIONS", 0)
2459
self.takeoff(alt=200)
2460
self.set_rc(3, 1500)
2461
self.change_mode("LOITER")
2462
self.progress("Doing a bit of loitering to start with")
2463
tstart = self.get_sim_time()
2464
while True:
2465
now = self.get_sim_time_cached()
2466
if now - tstart > 60:
2467
break
2468
m = self.assert_receive_message('VFR_HUD')
2469
new_throttle = m.throttle
2470
alt = m.alt
2471
m = self.assert_receive_message('ATTITUDE', timeout=5)
2472
pitch = math.degrees(m.pitch)
2473
self.progress("Pitch:%f throttle:%u alt:%f" % (pitch, new_throttle, alt))
2474
m = self.assert_receive_message('VFR_HUD', timeout=5)
2475
initial_throttle = m.throttle
2476
initial_alt = m.alt
2477
self.progress("Initial throttle: %u" % initial_throttle)
2478
# pitch down, ensure throttle decreases:
2479
rc2_max = self.get_parameter("RC2_MAX")
2480
self.set_rc(2, int(rc2_max))
2481
tstart = self.get_sim_time()
2482
while True:
2483
now = self.get_sim_time_cached()
2484
'''stick-mixing is pushing the aircraft down. It doesn't want to go
2485
down (the target loiter altitude hasn't changed), so it
2486
tries to add energy by increasing the throttle.
2487
'''
2488
if now - tstart > 60:
2489
raise NotAchievedException("Did not see increase in throttle")
2490
m = self.assert_receive_message('VFR_HUD', timeout=5)
2491
new_throttle = m.throttle
2492
alt = m.alt
2493
m = self.assert_receive_message('ATTITUDE', timeout=5)
2494
pitch = math.degrees(m.pitch)
2495
self.progress("Pitch:%f throttle:%u alt:%f" % (pitch, new_throttle, alt))
2496
if new_throttle - initial_throttle > 20:
2497
self.progress("Throttle delta achieved")
2498
break
2499
self.progress("Centering elevator and ensuring we get back to loiter altitude")
2500
self.set_rc(2, 1500)
2501
self.wait_altitude(initial_alt-1, initial_alt+1)
2502
# Test new loiter behaviour
2503
self.set_parameter("FLIGHT_OPTIONS", 1 << 12)
2504
# should descend at max stick
2505
self.set_rc(2, int(rc2_max))
2506
self.wait_altitude(initial_alt - 110, initial_alt - 90, timeout=90)
2507
# should not climb back at mid stick
2508
self.set_rc(2, 1500)
2509
self.delay_sim_time(60)
2510
self.wait_altitude(initial_alt - 110, initial_alt - 90)
2511
# should climb at min stick
2512
self.set_rc(2, 1100)
2513
self.wait_altitude(initial_alt - 10, initial_alt + 10, timeout=90)
2514
# return stick to center and fly home
2515
self.set_rc(2, 1500)
2516
self.fly_home_land_and_disarm()
2517
2518
def CPUFailsafe(self):
2519
'''In lockup Plane should copy RC inputs to RC outputs'''
2520
self.plane_CPUFailsafe()
2521
2522
def LargeMissions(self):
2523
'''Test Manipulation of Large missions'''
2524
self.load_mission("Kingaroy-vlarge.txt", strict=False)
2525
self.load_mission("Kingaroy-vlarge2.txt", strict=False)
2526
2527
def Soaring(self):
2528
'''Test Soaring feature'''
2529
2530
model = "plane-soaring"
2531
2532
self.customise_SITL_commandline(
2533
[],
2534
model=model,
2535
defaults_filepath=self.model_defaults_filepath(model),
2536
wipe=True)
2537
2538
self.load_mission('CMAC-soar.txt', strict=False)
2539
2540
# Enable thermalling RC
2541
rc_chan = 0
2542
for i in range(8):
2543
rcx_option = self.get_parameter('RC{0}_OPTION'.format(i+1))
2544
if rcx_option == 88:
2545
rc_chan = i+1
2546
break
2547
2548
if rc_chan == 0:
2549
raise NotAchievedException("Did not find soaring enable channel option.")
2550
2551
self.set_rc_from_map({
2552
rc_chan: 1900,
2553
})
2554
2555
self.set_parameters({
2556
"SOAR_VSPEED": 0.55,
2557
"SOAR_MIN_THML_S": 25,
2558
})
2559
2560
self.set_current_waypoint(1)
2561
self.change_mode('AUTO')
2562
self.wait_ready_to_arm()
2563
self.arm_vehicle()
2564
2565
# Wait to detect thermal
2566
self.progress("Waiting for thermal")
2567
self.wait_mode('THERMAL', timeout=600)
2568
2569
# Wait to climb to SOAR_ALT_MAX
2570
self.progress("Waiting for climb to max altitude")
2571
alt_max = self.get_parameter('SOAR_ALT_MAX')
2572
self.wait_altitude(alt_max-10, alt_max, timeout=600, relative=True)
2573
2574
# Wait for AUTO
2575
self.progress("Waiting for AUTO mode")
2576
self.wait_mode('AUTO')
2577
2578
# Disable thermals
2579
self.set_parameter("SIM_THML_SCENARI", 0)
2580
2581
# Wait to descend to SOAR_ALT_MIN
2582
self.progress("Waiting for glide to min altitude")
2583
alt_min = self.get_parameter('SOAR_ALT_MIN')
2584
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
2585
2586
self.progress("Waiting for throttle up")
2587
self.wait_servo_channel_value(3, 1200, timeout=5, comparator=operator.gt)
2588
2589
self.progress("Waiting for climb to cutoff altitude")
2590
alt_ctf = self.get_parameter('SOAR_ALT_CUTOFF')
2591
self.wait_altitude(alt_ctf-10, alt_ctf, timeout=600, relative=True)
2592
2593
# Allow time to suppress throttle and start descent.
2594
self.delay_sim_time(20)
2595
2596
# Now set FBWB mode
2597
self.change_mode('FBWB')
2598
self.delay_sim_time(5)
2599
2600
# Now disable soaring (should hold altitude)
2601
self.set_parameter("SOAR_ENABLE", 0)
2602
self.delay_sim_time(10)
2603
2604
# And re-enable. This should force throttle-down
2605
self.set_parameter("SOAR_ENABLE", 1)
2606
self.delay_sim_time(10)
2607
2608
# Now wait for descent and check throttle up
2609
self.wait_altitude(alt_min-10, alt_min, timeout=600, relative=True)
2610
2611
self.progress("Waiting for climb")
2612
self.wait_altitude(alt_ctf-10, alt_ctf, timeout=600, relative=True)
2613
2614
# Back to auto
2615
self.change_mode('AUTO')
2616
2617
# Re-enable thermals
2618
self.set_parameter("SIM_THML_SCENARI", 1)
2619
2620
# Disable soaring using RC channel.
2621
self.set_rc(rc_chan, 1100)
2622
2623
# Wait to get back to waypoint before thermal.
2624
self.progress("Waiting to get back to position")
2625
self.wait_current_waypoint(3, timeout=1200)
2626
2627
# Enable soaring with mode changes suppressed)
2628
self.set_rc(rc_chan, 1500)
2629
2630
# Make sure this causes throttle down.
2631
self.wait_servo_channel_value(3, 1200, timeout=3, comparator=operator.lt)
2632
2633
self.progress("Waiting for next WP with no thermalling")
2634
self.wait_waypoint(4, 4, timeout=1200, max_dist=120)
2635
2636
# Disarm
2637
self.disarm_vehicle_expect_fail()
2638
2639
self.progress("Mission OK")
2640
2641
def SpeedToFly(self):
2642
'''Test soaring speed-to-fly'''
2643
2644
model = "plane-soaring"
2645
2646
self.customise_SITL_commandline(
2647
[],
2648
model=model,
2649
defaults_filepath=self.model_defaults_filepath(model),
2650
wipe=True)
2651
2652
self.load_mission('CMAC-soar.txt', strict=False)
2653
2654
self.set_parameters({
2655
"SIM_THML_SCENARI": 0, # Turn off environmental thermals.
2656
"SOAR_ALT_MAX": 1000, # remove source of random failure
2657
})
2658
2659
# Get thermalling RC channel
2660
rc_chan = 0
2661
for i in range(8):
2662
rcx_option = self.get_parameter('RC{0}_OPTION'.format(i+1))
2663
if rcx_option == 88:
2664
rc_chan = i+1
2665
break
2666
2667
if rc_chan == 0:
2668
raise NotAchievedException("Did not find soaring enable channel option.")
2669
2670
# Disable soaring
2671
self.set_rc(rc_chan, 1100)
2672
2673
self.set_current_waypoint(1)
2674
self.change_mode('AUTO')
2675
self.wait_ready_to_arm()
2676
self.arm_vehicle()
2677
2678
# Wait for to 400m before starting.
2679
self.wait_altitude(390, 400, timeout=600, relative=True)
2680
2681
# Wait 10s to stabilize.
2682
self.delay_sim_time(30)
2683
2684
# Enable soaring (no automatic thermalling)
2685
self.set_rc(rc_chan, 1500)
2686
2687
self.set_parameters({
2688
"SOAR_CRSE_ARSPD": -1, # Enable speed to fly.
2689
"SOAR_VSPEED": 1, # Set appropriate McCready.
2690
"SIM_WIND_SPD": 0,
2691
})
2692
2693
self.progress('Waiting a few seconds before determining the "trim" airspeed.')
2694
self.delay_sim_time(20)
2695
m = self.assert_receive_message('VFR_HUD')
2696
trim_airspeed = m.airspeed
2697
self.progress("Using trim_airspeed=%f" % (trim_airspeed,))
2698
2699
min_airspeed = self.get_parameter("AIRSPEED_MIN")
2700
max_airspeed = self.get_parameter("AIRSPEED_MAX")
2701
2702
if trim_airspeed > max_airspeed:
2703
raise NotAchievedException("trim airspeed > max_airspeed (%f>%f)" %
2704
(trim_airspeed, max_airspeed))
2705
if trim_airspeed < min_airspeed:
2706
raise NotAchievedException("trim airspeed < min_airspeed (%f<%f)" %
2707
(trim_airspeed, min_airspeed))
2708
2709
self.progress("Adding updraft")
2710
self.set_parameters({
2711
"SIM_WIND_SPD": 1,
2712
'SIM_WIND_DIR_Z': 90,
2713
})
2714
self.progress("Waiting for vehicle to move slower in updraft")
2715
self.wait_airspeed(0, trim_airspeed-0.5, minimum_duration=10, timeout=120)
2716
2717
self.progress("Adding downdraft")
2718
self.set_parameter('SIM_WIND_DIR_Z', -90)
2719
self.progress("Waiting for vehicle to move faster in downdraft")
2720
self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120)
2721
2722
self.progress("Zeroing wind and increasing McCready")
2723
self.set_parameters({
2724
"SIM_WIND_SPD": 0,
2725
"SOAR_VSPEED": 2,
2726
})
2727
self.progress("Waiting for airspeed to increase with higher VSPEED")
2728
self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120)
2729
2730
# mcReady tests don't work ATM, so just return early:
2731
# takes too long to land, so just make it all go away:
2732
self.disarm_vehicle(force=True)
2733
self.reboot_sitl()
2734
return
2735
2736
self.start_subtest('Test McReady values')
2737
# Disable soaring
2738
self.set_rc(rc_chan, 1100)
2739
2740
# Wait for to 400m before starting.
2741
self.wait_altitude(390, 400, timeout=600, relative=True)
2742
2743
# Enable soaring
2744
self.set_rc(rc_chan, 2000)
2745
2746
self.progress("Find airspeed with 1m/s updraft and mcready=1")
2747
self.set_parameters({
2748
"SOAR_VSPEED": 1,
2749
"SIM_WIND_SPD": 1,
2750
})
2751
self.delay_sim_time(20)
2752
m = self.assert_receive_message('VFR_HUD')
2753
mcready1_speed = m.airspeed
2754
self.progress("airspeed is %f" % mcready1_speed)
2755
2756
self.progress("Reducing McCready")
2757
self.set_parameters({
2758
"SOAR_VSPEED": 0.5,
2759
})
2760
self.progress("Waiting for airspeed to decrease with lower McReady")
2761
self.wait_airspeed(0, mcready1_speed-0.5, minimum_duration=10, timeout=120)
2762
2763
self.progress("Increasing McCready")
2764
self.set_parameters({
2765
"SOAR_VSPEED": 1.5,
2766
})
2767
self.progress("Waiting for airspeed to decrease with lower McReady")
2768
self.wait_airspeed(mcready1_speed+0.5, mcready1_speed+100, minimum_duration=10, timeout=120)
2769
2770
# takes too long to land, so just make it all go away:
2771
self.disarm_vehicle(force=True)
2772
self.reboot_sitl()
2773
2774
def AirspeedDrivers(self):
2775
'''Test AirSpeed drivers'''
2776
airspeed_sensors = [
2777
("MS5525", 3, 1),
2778
("DLVR", 7, 2),
2779
("SITL", 100, 0),
2780
]
2781
for (name, t, bus) in airspeed_sensors:
2782
self.context_push()
2783
if bus is not None:
2784
self.set_parameter("ARSPD2_BUS", bus)
2785
self.set_parameter("ARSPD2_TYPE", t)
2786
self.reboot_sitl()
2787
self.wait_ready_to_arm()
2788
self.arm_vehicle()
2789
2790
# insert listener to compare airspeeds:
2791
airspeed = [None, None]
2792
# don't start testing until we've seen real speed from
2793
# both sensors. This gets us out of the noise area.
2794
global initial_airspeed_threshold_reached
2795
initial_airspeed_threshold_reached = False
2796
2797
def check_airspeeds(mav, m):
2798
global initial_airspeed_threshold_reached
2799
m_type = m.get_type()
2800
if (m_type == 'NAMED_VALUE_FLOAT' and
2801
m.name == 'AS2'):
2802
airspeed[1] = m.value
2803
elif m_type == 'VFR_HUD':
2804
airspeed[0] = m.airspeed
2805
else:
2806
return
2807
if airspeed[0] is None or airspeed[1] is None:
2808
return
2809
if airspeed[0] < 2 or airspeed[1] < 2:
2810
# this mismatch can occur on takeoff, or when we
2811
# smack into the ground at the end of the mission
2812
return
2813
if not initial_airspeed_threshold_reached:
2814
if not (airspeed[0] > 10 or airspeed[1] > 10):
2815
return
2816
initial_airspeed_threshold_reached = True
2817
delta = abs(airspeed[0] - airspeed[1])
2818
if delta > 2:
2819
raise NotAchievedException("Airspeed mismatch (as1=%f as2=%f)" % (airspeed[0], airspeed[1]))
2820
self.install_message_hook_context(check_airspeeds)
2821
self.fly_mission("ap1.txt", strict=False)
2822
if airspeed[0] is None:
2823
raise NotAchievedException("Never saw an airspeed1")
2824
if airspeed[1] is None:
2825
raise NotAchievedException("Never saw an airspeed2")
2826
self.context_pop()
2827
self.reboot_sitl()
2828
2829
def TerrainMission(self):
2830
'''Test terrain following in mission'''
2831
self.install_terrain_handlers_context()
2832
2833
num_wp = self.load_mission("ap-terrain.txt")
2834
2835
self.wait_ready_to_arm()
2836
self.arm_vehicle()
2837
2838
global max_alt
2839
max_alt = 0
2840
2841
def record_maxalt(mav, m):
2842
global max_alt
2843
if m.get_type() != 'GLOBAL_POSITION_INT':
2844
return
2845
if m.relative_alt/1000.0 > max_alt:
2846
max_alt = m.relative_alt/1000.0
2847
2848
self.install_message_hook_context(record_maxalt)
2849
2850
self.fly_mission_waypoints(num_wp-1, mission_timeout=600)
2851
2852
if max_alt < 200:
2853
raise NotAchievedException("Did not follow terrain")
2854
2855
def TerrainMissionInterrupt(self):
2856
'''Test terrain following when resuming a mission'''
2857
self.install_terrain_handlers_context()
2858
2859
self.load_mission("ap-terrain.txt")
2860
2861
self.wait_ready_to_arm()
2862
self.arm_vehicle()
2863
2864
self.set_parameter('TECS_RLL2THR', 2)
2865
2866
# Keep track of the maximum terrain alt.
2867
global max_terrain_alt
2868
max_terrain_alt = 0
2869
2870
def record_maxalt(mav, m):
2871
global max_terrain_alt
2872
if m.get_type() != 'TERRAIN_REPORT':
2873
return
2874
if m.current_height > max_terrain_alt:
2875
max_terrain_alt = m.current_height
2876
2877
self.context_push()
2878
2879
self.set_parameter("WP_RADIUS", 100) # Ensure the aircraft will get within 100.0m of the waypoint.
2880
2881
# Start the mission.
2882
self.set_current_waypoint(0, check_afterwards=False)
2883
self.change_mode('AUTO')
2884
2885
# After waypoint 2, go to GUIDED.
2886
self.wait_waypoint(3, 3, max_dist=3150, timeout=600)
2887
self.progress("Entering guided and flying somewhere constant")
2888
self.change_mode("GUIDED")
2889
loc = self.mav.location()
2890
self.location_offset_ne(loc, 350, 0)
2891
new_alt = 280
2892
self.run_cmd_int(
2893
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
2894
p5=int(loc.lat * 1e7),
2895
p6=int(loc.lng * 1e7),
2896
p7=new_alt, # alt
2897
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
2898
)
2899
2900
# Resume auto when we are close to the GUIDED waypoint and start tracking maximum terrain alt.
2901
self.wait_location(loc, accuracy=100) # based on loiter radius
2902
self.change_mode('AUTO')
2903
self.install_message_hook_context(record_maxalt)
2904
2905
self.wait_waypoint(3, 3, max_dist=100, timeout=600)
2906
2907
self.context_pop()
2908
2909
# We've flown enough.
2910
self.disarm_vehicle(force=True)
2911
self.reboot_sitl()
2912
2913
# self.fly_mission_waypoints(num_wp-1, mission_timeout=600)
2914
if max_terrain_alt > 120:
2915
raise NotAchievedException("Did not follow terrain")
2916
2917
def Terrain(self):
2918
'''test AP_Terrain'''
2919
self.reboot_sitl() # we know the terrain height at CMAC
2920
2921
self.install_terrain_handlers_context()
2922
2923
self.wait_ready_to_arm()
2924
loc = self.mav.location()
2925
2926
lng_int = int(loc.lng * 1e7)
2927
lat_int = int(loc.lat * 1e7)
2928
2929
# FIXME: once we have a pre-populated terrain cache this
2930
# should require an instantly correct report to pass
2931
tstart = self.get_sim_time_cached()
2932
last_terrain_report_pending = -1
2933
while True:
2934
now = self.get_sim_time_cached()
2935
if now - tstart > 60:
2936
raise NotAchievedException("Did not get correct terrain report")
2937
2938
self.mav.mav.terrain_check_send(lat_int, lng_int)
2939
2940
report = self.assert_receive_message('TERRAIN_REPORT', timeout=60)
2941
self.progress(self.dump_message_verbose(report))
2942
if report.spacing != 0:
2943
break
2944
2945
# we will keep trying to long as the number of pending
2946
# tiles is dropping:
2947
if last_terrain_report_pending == -1:
2948
last_terrain_report_pending = report.pending
2949
elif report.pending < last_terrain_report_pending:
2950
last_terrain_report_pending = report.pending
2951
tstart = now
2952
2953
self.delay_sim_time(1)
2954
2955
self.progress(self.dump_message_verbose(report))
2956
2957
expected_terrain_height = 583.5
2958
if abs(report.terrain_height - expected_terrain_height) > 0.5:
2959
raise NotAchievedException("Expected terrain height=%f got=%f" %
2960
(expected_terrain_height, report.terrain_height))
2961
2962
def TerrainLoiter(self):
2963
'''Test terrain following in loiter'''
2964
self.context_push()
2965
self.install_terrain_handlers_context()
2966
self.set_parameters({
2967
"TERRAIN_FOLLOW": 1, # enable terrain following in loiter
2968
"WP_LOITER_RAD": 2000, # set very large loiter rad to get some terrain changes
2969
})
2970
alt = 200
2971
self.takeoff(alt*0.9, alt*1.1)
2972
self.set_rc(3, 1500)
2973
self.change_mode("LOITER")
2974
self.progress("loitering at %um" % alt)
2975
tstart = self.get_sim_time()
2976
timeout = 60*15 # enough time to do one and a bit circles
2977
max_delta = 0
2978
while True:
2979
now = self.get_sim_time_cached()
2980
if now - tstart > timeout:
2981
break
2982
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
2983
terrain = self.assert_receive_message('TERRAIN_REPORT')
2984
rel_alt = terrain.current_height
2985
self.progress("%um above terrain (%um bove home)" %
2986
(rel_alt, gpi.relative_alt/1000.0))
2987
if rel_alt > alt*1.2 or rel_alt < alt * 0.8:
2988
raise NotAchievedException("Not terrain following")
2989
delta = abs(rel_alt - gpi.relative_alt/1000.0)
2990
if delta > max_delta:
2991
max_delta = delta
2992
want_max_delta = 30
2993
if max_delta < want_max_delta:
2994
raise NotAchievedException(
2995
"Expected terrain and home alts to vary more than they did (max=%u want=%u)" %
2996
(max_delta, want_max_delta))
2997
self.context_pop()
2998
self.progress("Returning home")
2999
self.fly_home_land_and_disarm(240)
3000
3001
def TerrainLoiterToCircle(self):
3002
'''loiter terrain-relative. Switch to Circle, maintain alt'''
3003
self.install_terrain_handlers_context()
3004
self.set_parameters({
3005
"TERRAIN_FOLLOW": 1, # enable terrain following in loiter
3006
"WP_LOITER_RAD": 2000, # set very large loiter rad to get some terrain changes
3007
})
3008
alt = 50
3009
self.takeoff(alt*0.9, alt*1.1, mode='TAKEOFF')
3010
self.change_mode('LOITER')
3011
self.delay_sim_time(10)
3012
self.change_mode('CIRCLE')
3013
self.wait_altitude(alt*0.9, alt*1.1, minimum_duration=10, relative=True)
3014
self.fly_home_land_and_disarm()
3015
3016
def fly_external_AHRS(self, sim, eahrs_type, mission):
3017
"""Fly with external AHRS"""
3018
self.customise_SITL_commandline(["--serial4=sim:%s" % sim])
3019
3020
self.set_parameters({
3021
"EAHRS_TYPE": eahrs_type,
3022
"SERIAL4_PROTOCOL": 36,
3023
"SERIAL4_BAUD": 230400,
3024
"GPS1_TYPE": 21,
3025
"AHRS_EKF_TYPE": 11,
3026
"INS_GYR_CAL": 1,
3027
})
3028
self.reboot_sitl()
3029
self.delay_sim_time(5)
3030
self.progress("Running accelcal")
3031
self.run_cmd(
3032
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
3033
p5=4,
3034
timeout=5,
3035
)
3036
3037
self.wait_ready_to_arm()
3038
self.arm_vehicle()
3039
self.fly_mission(mission)
3040
3041
def wait_and_maintain_wind_estimate(
3042
self,
3043
want_speed,
3044
want_dir,
3045
timeout=10,
3046
speed_tolerance=0.5,
3047
dir_tolerance=5,
3048
**kwargs):
3049
'''wait for wind estimate to reach speed and direction'''
3050
3051
def validator(last, _min, _max):
3052
'''returns false of spd or direction is too-far wrong'''
3053
(spd, di) = last
3054
_min_spd, _min_dir = _min
3055
_max_spd, _max_dir = _max
3056
if spd < _min_spd or spd > _max_spd:
3057
return False
3058
# my apologies to whoever is staring at this and wondering
3059
# why we're not wrapping angles here...
3060
if di < _min_dir or di > _max_dir:
3061
return False
3062
return True
3063
3064
def value_getter():
3065
'''returns a tuple of (wind_speed, wind_dir), where wind_dir is 45 if
3066
wind is coming from NE'''
3067
m = self.assert_receive_message("WIND")
3068
return (m.speed, m.direction)
3069
3070
class ValueAverager(object):
3071
def __init__(self):
3072
self.speed_average = -1
3073
self.dir_average = -1
3074
self.count = 0.0
3075
3076
def add_value(self, value):
3077
(spd, di) = value
3078
if self.speed_average == -1:
3079
self.speed_average = spd
3080
self.dir_average = di
3081
else:
3082
self.speed_average += spd
3083
self.di_average += spd
3084
self.count += 1
3085
return (self.speed_average/self.count, self.dir_average/self.count)
3086
3087
def reset(self):
3088
self.count = 0
3089
self.speed_average = -1
3090
self.dir_average = -1
3091
3092
self.wait_and_maintain_range(
3093
value_name="WindEstimates",
3094
minimum=(want_speed-speed_tolerance, want_dir-dir_tolerance),
3095
maximum=(want_speed+speed_tolerance, want_dir+dir_tolerance),
3096
current_value_getter=value_getter,
3097
value_averager=ValueAverager(),
3098
validator=lambda last, _min, _max: validator(last, _min, _max),
3099
timeout=timeout,
3100
**kwargs
3101
)
3102
3103
def WindEstimates(self):
3104
'''fly non-external AHRS, ensure wind estimate correct'''
3105
self.set_parameters({
3106
"SIM_WIND_SPD": 5,
3107
"SIM_WIND_DIR": 45,
3108
})
3109
self.wait_ready_to_arm()
3110
self.takeoff(70) # default wind sim wind is a sqrt function up to 60m
3111
self.change_mode('LOITER')
3112
# use default estimator to determine when to check others:
3113
self.wait_and_maintain_wind_estimate(5, 45, timeout=120)
3114
3115
for ahrs_type in 0, 2, 3, 10:
3116
self.start_subtest("Checking AHRS_EKF_TYPE=%u" % ahrs_type)
3117
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
3118
self.wait_and_maintain_wind_estimate(
3119
5, 45,
3120
speed_tolerance=1,
3121
timeout=30
3122
)
3123
self.fly_home_land_and_disarm()
3124
3125
def VectorNavEAHRS(self):
3126
'''Test VectorNav EAHRS support'''
3127
self.fly_external_AHRS("VectorNav", 1, "ap1.txt")
3128
3129
def MicroStrainEAHRS5(self):
3130
'''Test MicroStrain EAHRS series 5 support'''
3131
self.fly_external_AHRS("MicroStrain5", 2, "ap1.txt")
3132
3133
def MicroStrainEAHRS7(self):
3134
'''Test MicroStrain EAHRS series 7 support'''
3135
self.fly_external_AHRS("MicroStrain7", 7, "ap1.txt")
3136
3137
def InertialLabsEAHRS(self):
3138
'''Test InertialLabs EAHRS support'''
3139
self.fly_external_AHRS("ILabs", 5, "ap1.txt")
3140
3141
def GpsSensorPreArmEAHRS(self):
3142
'''Test pre-arm checks related to EAHRS_SENSORS using the MicroStrain7 driver'''
3143
self.customise_SITL_commandline(["--serial4=sim:MicroStrain7"])
3144
3145
self.set_parameters({
3146
"EAHRS_TYPE": 7,
3147
"SERIAL4_PROTOCOL": 36,
3148
"SERIAL4_BAUD": 230400,
3149
"GPS1_TYPE": 0, # Disabled (simulate user setup error)
3150
"GPS2_TYPE": 0, # Disabled (simulate user setup error)
3151
"AHRS_EKF_TYPE": 11,
3152
"INS_GYR_CAL": 1,
3153
"EAHRS_SENSORS": 13, # GPS is enabled
3154
})
3155
self.reboot_sitl()
3156
self.delay_sim_time(5)
3157
self.progress("Running accelcal")
3158
self.run_cmd(
3159
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
3160
p5=4,
3161
timeout=5,
3162
)
3163
3164
self.assert_prearm_failure("ExternalAHRS: Incorrect number", # Cut short due to message limits.
3165
timeout=30,
3166
other_prearm_failures_fatal=False)
3167
3168
self.set_parameters({
3169
"EAHRS_TYPE": 7,
3170
"SERIAL4_PROTOCOL": 36,
3171
"SERIAL4_BAUD": 230400,
3172
"GPS1_TYPE": 1, # Auto
3173
"GPS2_TYPE": 21, # EAHRS
3174
"AHRS_EKF_TYPE": 11,
3175
"INS_GYR_CAL": 1,
3176
"EAHRS_SENSORS": 13, # GPS is enabled
3177
})
3178
self.reboot_sitl()
3179
self.delay_sim_time(5)
3180
self.progress("Running accelcal")
3181
self.run_cmd(
3182
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
3183
p5=4,
3184
timeout=5,
3185
)
3186
# Check prearm success with MicroStrain when the first GPS is occupied by another GPS.
3187
# This supports the use case of comparing MicroStrain dual antenna to another GPS.
3188
self.wait_ready_to_arm()
3189
3190
def get_accelvec(self, m):
3191
return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81
3192
3193
def get_gyrovec(self, m):
3194
return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1)
3195
3196
def IMUTempCal(self):
3197
'''Test IMU temperature calibration'''
3198
self.progress("Setting up SITL temperature profile")
3199
self.set_parameters({
3200
"SIM_IMUT1_ENABLE" : 1,
3201
"SIM_IMUT1_ACC1_X" : 120000.000000,
3202
"SIM_IMUT1_ACC1_Y" : -190000.000000,
3203
"SIM_IMUT1_ACC1_Z" : 1493.864746,
3204
"SIM_IMUT1_ACC2_X" : -51.624416,
3205
"SIM_IMUT1_ACC2_Y" : 10.364172,
3206
"SIM_IMUT1_ACC2_Z" : -7878.000000,
3207
"SIM_IMUT1_ACC3_X" : -0.514242,
3208
"SIM_IMUT1_ACC3_Y" : 0.862218,
3209
"SIM_IMUT1_ACC3_Z" : -234.000000,
3210
"SIM_IMUT1_GYR1_X" : -5122.513817,
3211
"SIM_IMUT1_GYR1_Y" : -3250.470428,
3212
"SIM_IMUT1_GYR1_Z" : -2136.346676,
3213
"SIM_IMUT1_GYR2_X" : 30.720505,
3214
"SIM_IMUT1_GYR2_Y" : 17.778447,
3215
"SIM_IMUT1_GYR2_Z" : 0.765997,
3216
"SIM_IMUT1_GYR3_X" : -0.003572,
3217
"SIM_IMUT1_GYR3_Y" : 0.036346,
3218
"SIM_IMUT1_GYR3_Z" : 0.015457,
3219
"SIM_IMUT1_TMAX" : 70.0,
3220
"SIM_IMUT1_TMIN" : -20.000000,
3221
"SIM_IMUT2_ENABLE" : 1,
3222
"SIM_IMUT2_ACC1_X" : -160000.000000,
3223
"SIM_IMUT2_ACC1_Y" : 198730.000000,
3224
"SIM_IMUT2_ACC1_Z" : 27812.000000,
3225
"SIM_IMUT2_ACC2_X" : 30.658159,
3226
"SIM_IMUT2_ACC2_Y" : 32.085022,
3227
"SIM_IMUT2_ACC2_Z" : 1572.000000,
3228
"SIM_IMUT2_ACC3_X" : 0.102912,
3229
"SIM_IMUT2_ACC3_Y" : 0.229734,
3230
"SIM_IMUT2_ACC3_Z" : 172.000000,
3231
"SIM_IMUT2_GYR1_X" : 3173.925644,
3232
"SIM_IMUT2_GYR1_Y" : -2368.312836,
3233
"SIM_IMUT2_GYR1_Z" : -1796.497177,
3234
"SIM_IMUT2_GYR2_X" : 13.029696,
3235
"SIM_IMUT2_GYR2_Y" : -10.349280,
3236
"SIM_IMUT2_GYR2_Z" : -15.082653,
3237
"SIM_IMUT2_GYR3_X" : 0.004831,
3238
"SIM_IMUT2_GYR3_Y" : -0.020528,
3239
"SIM_IMUT2_GYR3_Z" : 0.009469,
3240
"SIM_IMUT2_TMAX" : 70.000000,
3241
"SIM_IMUT2_TMIN" : -20.000000,
3242
"SIM_IMUT_END" : 45.000000,
3243
"SIM_IMUT_START" : 3.000000,
3244
"SIM_IMUT_TCONST" : 75.000000,
3245
"SIM_DRIFT_SPEED" : 0,
3246
"INS_GYR_CAL" : 0,
3247
})
3248
3249
self.set_parameter("SIM_IMUT_FIXED", 12)
3250
self.progress("Running accel cal")
3251
self.run_cmd(
3252
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
3253
p5=4,
3254
timeout=5,
3255
)
3256
self.progress("Running gyro cal")
3257
self.run_cmd(
3258
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
3259
p5=1,
3260
timeout=5,
3261
)
3262
self.set_parameters({
3263
"SIM_IMUT_FIXED": 0,
3264
"INS_TCAL1_ENABLE": 2,
3265
"INS_TCAL1_TMAX": 42,
3266
"INS_TCAL2_ENABLE": 2,
3267
"INS_TCAL2_TMAX": 42,
3268
"SIM_SPEEDUP": 200,
3269
})
3270
self.set_parameter("LOG_DISARMED", 1)
3271
self.reboot_sitl()
3272
3273
self.progress("Waiting for IMU temperature")
3274
self.assert_reach_imu_temperature(43, timeout=600)
3275
3276
if self.get_parameter("INS_TCAL1_ENABLE") != 1.0:
3277
raise NotAchievedException("TCAL1 did not complete")
3278
if self.get_parameter("INS_TCAL2_ENABLE") != 1.0:
3279
raise NotAchievedException("TCAL2 did not complete")
3280
3281
self.progress("Logging with calibration enabled")
3282
self.reboot_sitl()
3283
3284
self.assert_reach_imu_temperature(43, timeout=600)
3285
3286
self.progress("Testing with compensation enabled")
3287
3288
test_temperatures = range(10, 45, 5)
3289
corrected = {}
3290
uncorrected = {}
3291
3292
for temp in test_temperatures:
3293
self.progress("Testing temperature %.1f" % temp)
3294
self.set_parameter("SIM_IMUT_FIXED", temp)
3295
self.delay_sim_time(2)
3296
for msg in ['RAW_IMU', 'SCALED_IMU2']:
3297
m = self.assert_receive_message(msg, timeout=2)
3298
temperature = m.temperature*0.01
3299
3300
if abs(temperature - temp) > 0.2:
3301
raise NotAchievedException("incorrect %s temperature %.1f should be %.1f" % (msg, temperature, temp))
3302
3303
accel = self.get_accelvec(m)
3304
gyro = self.get_gyrovec(m)
3305
accel2 = accel + Vector3(0, 0, 9.81)
3306
3307
corrected[temperature] = (accel2, gyro)
3308
3309
self.progress("Testing with compensation disabled")
3310
self.set_parameters({
3311
"INS_TCAL1_ENABLE": 0,
3312
"INS_TCAL2_ENABLE": 0,
3313
})
3314
3315
gyro_threshold = 0.2
3316
accel_threshold = 0.2
3317
3318
for temp in test_temperatures:
3319
self.progress("Testing temperature %.1f" % temp)
3320
self.set_parameter("SIM_IMUT_FIXED", temp)
3321
self.wait_heartbeat()
3322
self.wait_heartbeat()
3323
for msg in ['RAW_IMU', 'SCALED_IMU2']:
3324
m = self.assert_receive_message(msg, timeout=2)
3325
temperature = m.temperature*0.01
3326
3327
if abs(temperature - temp) > 0.2:
3328
raise NotAchievedException("incorrect %s temperature %.1f should be %.1f" % (msg, temperature, temp))
3329
3330
accel = self.get_accelvec(m)
3331
gyro = self.get_gyrovec(m)
3332
3333
accel2 = accel + Vector3(0, 0, 9.81)
3334
uncorrected[temperature] = (accel2, gyro)
3335
3336
for temp in test_temperatures:
3337
(accel, gyro) = corrected[temp]
3338
self.progress("Corrected gyro at %.1f %s" % (temp, gyro))
3339
self.progress("Corrected accel at %.1f %s" % (temp, accel))
3340
3341
for temp in test_temperatures:
3342
(accel, gyro) = uncorrected[temp]
3343
self.progress("Uncorrected gyro at %.1f %s" % (temp, gyro))
3344
self.progress("Uncorrected accel at %.1f %s" % (temp, accel))
3345
3346
bad_value = False
3347
for temp in test_temperatures:
3348
(accel, gyro) = corrected[temp]
3349
if gyro.length() > gyro_threshold:
3350
raise NotAchievedException("incorrect corrected at %.1f gyro %s" % (temp, gyro))
3351
3352
if accel.length() > accel_threshold:
3353
raise NotAchievedException("incorrect corrected at %.1f accel %s" % (temp, accel))
3354
3355
(accel, gyro) = uncorrected[temp]
3356
if gyro.length() > gyro_threshold*2:
3357
bad_value = True
3358
3359
if accel.length() > accel_threshold*2:
3360
bad_value = True
3361
3362
if not bad_value:
3363
raise NotAchievedException("uncompensated IMUs did not vary enough")
3364
3365
# the above tests change the internal persistent state of the
3366
# vehicle in ways that autotest doesn't track (magically set
3367
# parameters). So wipe the vehicle's eeprom:
3368
self.reset_SITL_commandline()
3369
3370
def EKFlaneswitch(self):
3371
'''Test EKF3 Affinity and Lane Switching'''
3372
3373
# new lane switch available only with EK3
3374
self.set_parameters({
3375
"EK3_ENABLE": 1,
3376
"EK2_ENABLE": 0,
3377
"AHRS_EKF_TYPE": 3,
3378
"EK3_AFFINITY": 15, # enable affinity for all sensors
3379
"EK3_IMU_MASK": 3, # use only 2 IMUs
3380
"GPS2_TYPE": 1,
3381
"SIM_GPS2_ENABLE": 1,
3382
"SIM_BARO_COUNT": 2,
3383
"SIM_BAR2_DISABLE": 0,
3384
"ARSPD2_TYPE": 2,
3385
"ARSPD2_USE": 1,
3386
"ARSPD2_PIN": 2,
3387
})
3388
3389
# some parameters need reboot to take effect
3390
self.reboot_sitl()
3391
3392
self.lane_switches = []
3393
3394
# add an EKF lane switch hook
3395
def statustext_hook(mav, message):
3396
if message.get_type() != 'STATUSTEXT':
3397
return
3398
# example msg: EKF3 lane switch 1
3399
if not message.text.startswith("EKF3 lane switch "):
3400
return
3401
newlane = int(message.text[-1])
3402
self.lane_switches.append(newlane)
3403
self.install_message_hook_context(statustext_hook)
3404
3405
# get flying
3406
self.takeoff(alt=50)
3407
self.change_mode('CIRCLE')
3408
3409
###################################################################
3410
self.progress("Checking EKF3 Lane Switching trigger from all sensors")
3411
###################################################################
3412
self.start_subtest("ACCELEROMETER: Change z-axis offset")
3413
# create an accelerometer error by changing the Z-axis offset
3414
self.context_collect("STATUSTEXT")
3415
old_parameter = self.get_parameter("INS_ACCOFFS_Z")
3416
self.wait_statustext(
3417
text="EKF3 lane switch",
3418
timeout=30,
3419
the_function=self.set_parameter("INS_ACCOFFS_Z", old_parameter + 5),
3420
check_context=True)
3421
if self.lane_switches != [1]:
3422
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
3423
# Cleanup
3424
self.set_parameter("INS_ACCOFFS_Z", old_parameter)
3425
self.context_clear_collection("STATUSTEXT")
3426
self.wait_heading(0, accuracy=10, timeout=60)
3427
self.wait_heading(180, accuracy=10, timeout=60)
3428
###################################################################
3429
self.start_subtest("BAROMETER: Freeze to last measured value")
3430
self.context_collect("STATUSTEXT")
3431
# create a barometer error by inhibiting any pressure change while changing altitude
3432
old_parameter = self.get_parameter("SIM_BAR2_FREEZE")
3433
self.set_parameter("SIM_BAR2_FREEZE", 1)
3434
self.wait_statustext(
3435
text="EKF3 lane switch",
3436
timeout=30,
3437
the_function=lambda: self.set_rc(2, 2000),
3438
check_context=True)
3439
if self.lane_switches != [1, 0]:
3440
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
3441
# Cleanup
3442
self.set_rc(2, 1500)
3443
self.set_parameter("SIM_BAR2_FREEZE", old_parameter)
3444
self.context_clear_collection("STATUSTEXT")
3445
self.wait_heading(0, accuracy=10, timeout=60)
3446
self.wait_heading(180, accuracy=10, timeout=60)
3447
###################################################################
3448
self.start_subtest("GPS: Apply GPS Velocity Error in NED")
3449
self.context_push()
3450
self.context_collect("STATUSTEXT")
3451
3452
# create a GPS velocity error by adding a random 2m/s
3453
# noise on each axis
3454
def sim_gps_verr():
3455
self.set_parameters({
3456
"SIM_GPS1_VERR_X": self.get_parameter("SIM_GPS1_VERR_X") + 2,
3457
"SIM_GPS1_VERR_Y": self.get_parameter("SIM_GPS1_VERR_Y") + 2,
3458
"SIM_GPS1_VERR_Z": self.get_parameter("SIM_GPS1_VERR_Z") + 2,
3459
})
3460
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True)
3461
if self.lane_switches != [1, 0, 1]:
3462
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
3463
# Cleanup
3464
self.context_pop()
3465
self.context_clear_collection("STATUSTEXT")
3466
self.wait_heading(0, accuracy=10, timeout=60)
3467
self.wait_heading(180, accuracy=10, timeout=60)
3468
###################################################################
3469
self.start_subtest("MAGNETOMETER: Change X-Axis Offset")
3470
self.context_collect("STATUSTEXT")
3471
# create a magnetometer error by changing the X-axis offset
3472
old_parameter = self.get_parameter("SIM_MAG2_OFS_X")
3473
self.wait_statustext(
3474
text="EKF3 lane switch",
3475
timeout=30,
3476
the_function=self.set_parameter("SIM_MAG2_OFS_X", old_parameter + 150),
3477
check_context=True)
3478
if self.lane_switches != [1, 0, 1, 0]:
3479
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
3480
# Cleanup
3481
self.set_parameter("SIM_MAG2_OFS_X", old_parameter)
3482
self.context_clear_collection("STATUSTEXT")
3483
self.wait_heading(0, accuracy=10, timeout=60)
3484
self.wait_heading(180, accuracy=10, timeout=60)
3485
###################################################################
3486
self.start_subtest("AIRSPEED: Fail to constant value")
3487
self.context_push()
3488
self.context_collect("STATUSTEXT")
3489
3490
old_parameter = self.get_parameter("SIM_ARSPD_FAIL")
3491
3492
def fail_speed():
3493
self.change_mode("GUIDED")
3494
loc = self.mav.location()
3495
self.run_cmd_int(
3496
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
3497
p5=int(loc.lat * 1e7),
3498
p6=int(loc.lng * 1e7),
3499
p7=50, # alt
3500
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3501
)
3502
self.delay_sim_time(5)
3503
# create an airspeed sensor error by freezing to the
3504
# current airspeed then changing the airspeed demand
3505
# to a higher value and waiting for the TECS speed
3506
# loop to diverge
3507
m = self.assert_receive_message('VFR_HUD')
3508
self.set_parameter("SIM_ARSPD_FAIL", m.airspeed)
3509
self.run_cmd(
3510
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
3511
p1=0, # airspeed
3512
p2=30,
3513
p3=-1, # throttle / no change
3514
p4=0, # absolute values
3515
)
3516
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=fail_speed, check_context=True)
3517
if self.lane_switches != [1, 0, 1, 0, 1]:
3518
raise NotAchievedException("Expected lane switch 1, got %s" % str(self.lane_switches[-1]))
3519
# Cleanup
3520
self.set_parameter("SIM_ARSPD_FAIL", old_parameter)
3521
self.change_mode('CIRCLE')
3522
self.context_pop()
3523
self.context_clear_collection("STATUSTEXT")
3524
self.wait_heading(0, accuracy=10, timeout=60)
3525
self.wait_heading(180, accuracy=10, timeout=60)
3526
###################################################################
3527
self.progress("GYROSCOPE: Change Y-Axis Offset")
3528
self.context_collect("STATUSTEXT")
3529
# create a gyroscope error by changing the Y-axis offset
3530
old_parameter = self.get_parameter("INS_GYR2OFFS_Y")
3531
self.wait_statustext(
3532
text="EKF3 lane switch",
3533
timeout=30,
3534
the_function=self.set_parameter("INS_GYR2OFFS_Y", old_parameter + 1),
3535
check_context=True)
3536
if self.lane_switches != [1, 0, 1, 0, 1, 0]:
3537
raise NotAchievedException("Expected lane switch 0, got %s" % str(self.lane_switches[-1]))
3538
# Cleanup
3539
self.set_parameter("INS_GYR2OFFS_Y", old_parameter)
3540
self.context_clear_collection("STATUSTEXT")
3541
###################################################################
3542
3543
self.disarm_vehicle(force=True)
3544
3545
def FenceAltCeilFloor(self):
3546
'''Tests the fence ceiling and floor'''
3547
self.set_parameters({
3548
"FENCE_TYPE": 9, # Set fence type to max and min alt
3549
"FENCE_ACTION": 0, # Set action to report
3550
"FENCE_ALT_MAX": 200,
3551
"FENCE_ALT_MIN": 100,
3552
})
3553
3554
# Grab Home Position
3555
self.wait_ready_to_arm()
3556
startpos = self.mav.location()
3557
3558
cruise_alt = 150
3559
self.takeoff(cruise_alt)
3560
3561
# note that while we enable the fence here, since the action
3562
# is set to report-only the fence continues to show as
3563
# not-enabled in the assert calls below
3564
self.do_fence_enable()
3565
3566
self.progress("Fly above ceiling and check for breach")
3567
self.change_altitude(startpos.alt + cruise_alt + 80)
3568
self.assert_fence_sys_status(True, False, False)
3569
3570
self.progress("Return to cruise alt")
3571
self.change_altitude(startpos.alt + cruise_alt)
3572
3573
self.progress("Ensure breach has clearned")
3574
self.assert_fence_sys_status(True, False, True)
3575
3576
self.progress("Fly below floor and check for breach")
3577
self.change_altitude(startpos.alt + cruise_alt - 80)
3578
3579
self.progress("Ensure breach has clearned")
3580
self.assert_fence_sys_status(True, False, False)
3581
3582
self.do_fence_disable()
3583
3584
self.fly_home_land_and_disarm(timeout=150)
3585
3586
def FenceMinAltAutoEnable(self):
3587
'''Tests autoenablement of the alt min fence and fences on arming'''
3588
self.set_parameters({
3589
"FENCE_TYPE": 9, # Set fence type to min alt and max alt
3590
"FENCE_ACTION": 1, # Set action to RTL
3591
"FENCE_ALT_MIN": 25,
3592
"FENCE_ALT_MAX": 100,
3593
"FENCE_AUTOENABLE": 3,
3594
"FENCE_ENABLE" : 0,
3595
"RTL_AUTOLAND" : 2,
3596
})
3597
3598
# check we can takeoff again
3599
for i in [1, 2]:
3600
# Grab Home Position
3601
self.wait_ready_to_arm()
3602
self.arm_vehicle()
3603
# max alt fence should now be enabled
3604
if i == 1:
3605
self.assert_fence_enabled()
3606
3607
self.takeoff(alt=50, mode='TAKEOFF')
3608
self.change_mode("FBWA")
3609
self.set_rc(3, 1100) # lower throttle
3610
3611
self.progress("Waiting for RTL")
3612
tstart = self.get_sim_time()
3613
mode = "RTL"
3614
while not self.mode_is(mode, drain_mav=False):
3615
self.mav.messages['HEARTBEAT'].custom_mode
3616
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
3617
self.mav.flightmode, mode, self.get_altitude(relative=True)))
3618
if (self.get_sim_time_cached() > tstart + 120):
3619
raise WaitModeTimeout("Did not change mode")
3620
self.progress("Got mode %s" % mode)
3621
self.fly_home_land_and_disarm()
3622
self.change_mode("FBWA")
3623
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
3624
self.set_current_waypoint(0, check_afterwards=False)
3625
self.set_rc(3, 1000) # lower throttle
3626
3627
def FenceMinAltEnableAutoland(self):
3628
'''Tests autolanding when alt min fence is enabled'''
3629
self.set_parameters({
3630
"FENCE_TYPE": 12, # Set fence type to min alt and max alt
3631
"FENCE_ACTION": 1, # Set action to RTL
3632
"FENCE_ALT_MIN": 20,
3633
"FENCE_AUTOENABLE": 0,
3634
"FENCE_ENABLE" : 1,
3635
"RTL_AUTOLAND" : 2,
3636
})
3637
3638
# Grab Home Position
3639
self.wait_ready_to_arm()
3640
self.arm_vehicle()
3641
3642
self.takeoff(alt=50, mode='TAKEOFF')
3643
self.change_mode("FBWA")
3644
self.set_rc(3, 1100) # lower throttle
3645
3646
self.progress("Waiting for RTL")
3647
tstart = self.get_sim_time()
3648
mode = "RTL"
3649
while not self.mode_is(mode, drain_mav=False):
3650
self.mav.messages['HEARTBEAT'].custom_mode
3651
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
3652
self.mav.flightmode, mode, self.get_altitude(relative=True)))
3653
if (self.get_sim_time_cached() > tstart + 120):
3654
raise WaitModeTimeout("Did not change mode")
3655
self.progress("Got mode %s" % mode)
3656
# switch to FBWA
3657
self.change_mode("FBWA")
3658
self.set_rc(3, 1500) # raise throttle
3659
self.wait_altitude(25, 35, timeout=50, relative=True)
3660
self.set_rc(3, 1000) # lower throttle
3661
# Now check we can land
3662
self.fly_home_land_and_disarm()
3663
3664
def FenceMinAltAutoEnableAbort(self):
3665
'''Tests autoenablement of the alt min fence and fences on arming'''
3666
self.set_parameters({
3667
"FENCE_TYPE": 8, # Set fence type to min alt
3668
"FENCE_ACTION": 1, # Set action to RTL
3669
"FENCE_ALT_MIN": 25,
3670
"FENCE_ALT_MAX": 100,
3671
"FENCE_AUTOENABLE": 3,
3672
"FENCE_ENABLE" : 0,
3673
"RTL_AUTOLAND" : 2,
3674
})
3675
3676
self.wait_ready_to_arm()
3677
self.arm_vehicle()
3678
3679
self.takeoff(alt=50, mode='TAKEOFF')
3680
self.change_mode("FBWA")
3681
# min alt fence should now be enabled
3682
self.assert_fence_enabled()
3683
self.set_rc(3, 1100) # lower throttle
3684
3685
self.progress("Waiting for RTL")
3686
tstart = self.get_sim_time()
3687
mode = "RTL"
3688
while not self.mode_is(mode, drain_mav=False):
3689
self.mav.messages['HEARTBEAT'].custom_mode
3690
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
3691
self.mav.flightmode, mode, self.get_altitude(relative=True)))
3692
if (self.get_sim_time_cached() > tstart + 120):
3693
raise WaitModeTimeout("Did not change mode")
3694
self.progress("Got mode %s" % mode)
3695
3696
self.load_generic_mission("flaps.txt")
3697
self.change_mode("AUTO")
3698
self.wait_distance_to_waypoint(8, 100, 10000000)
3699
self.set_current_waypoint(8)
3700
# abort the landing
3701
self.wait_altitude(10, 20, timeout=200, relative=True)
3702
self.change_mode("CRUISE")
3703
self.set_rc(2, 1200)
3704
# self.set_rc(3, 1600) # raise throttle
3705
self.wait_altitude(30, 40, timeout=200, relative=True)
3706
# min alt fence should now be re-enabled
3707
self.assert_fence_enabled()
3708
3709
self.change_mode("AUTO")
3710
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
3711
self.fly_home_land_and_disarm(timeout=150)
3712
3713
def FenceAutoEnableDisableSwitch(self):
3714
'''Tests autoenablement of regular fences and manual disablement'''
3715
self.set_parameters({
3716
"FENCE_TYPE": 9, # Set fence type to min alt, max alt
3717
"FENCE_ACTION": 1, # Set action to RTL
3718
"FENCE_ALT_MIN": 50,
3719
"FENCE_ALT_MAX": 100,
3720
"FENCE_AUTOENABLE": 2,
3721
"FENCE_OPTIONS" : 1,
3722
"FENCE_ENABLE" : 1,
3723
"FENCE_RADIUS" : 300,
3724
"FENCE_RET_ALT" : 0,
3725
"FENCE_RET_RALLY" : 0,
3726
"FENCE_TOTAL" : 0,
3727
"RTL_ALTITUDE" : 75,
3728
"TKOFF_ALT" : 75,
3729
"RC7_OPTION" : 11, # AC_Fence uses Aux switch functionality
3730
})
3731
self.reboot_sitl()
3732
self.context_collect("STATUSTEXT")
3733
3734
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
3735
# Grab Home Position
3736
self.assert_receive_message('HOME_POSITION')
3737
self.set_rc(7, 1000) # Turn fence off with aux function, does not impact later auto-enable
3738
3739
self.wait_ready_to_arm()
3740
3741
self.progress("Check fence disabled at boot")
3742
m = self.assert_receive_message('SYS_STATUS')
3743
if (m.onboard_control_sensors_enabled & fence_bit):
3744
raise NotAchievedException("Fence is enabled at boot")
3745
3746
cruise_alt = 75
3747
self.takeoff(cruise_alt, mode='TAKEOFF')
3748
3749
self.progress("Fly above ceiling and check there is a breach")
3750
self.change_mode('FBWA')
3751
self.set_rc(3, 2000)
3752
self.set_rc(2, 1000)
3753
3754
self.wait_statustext("Max Alt fence breached", timeout=10, check_context=True)
3755
self.wait_mode('RTL')
3756
3757
m = self.assert_receive_message('SYS_STATUS')
3758
if (m.onboard_control_sensors_health & fence_bit):
3759
raise NotAchievedException("Fence ceiling not breached")
3760
3761
self.set_rc(3, 1500)
3762
self.set_rc(2, 1500)
3763
3764
self.progress("Wait for RTL alt reached")
3765
self.wait_altitude(cruise_alt-5, cruise_alt+5, relative=True, timeout=30)
3766
3767
self.progress("Return to cruise alt")
3768
self.set_rc(3, 1500)
3769
self.change_altitude(cruise_alt, relative=True)
3770
3771
self.progress("Check fence breach cleared")
3772
m = self.assert_receive_message('SYS_STATUS')
3773
if (not (m.onboard_control_sensors_health & fence_bit)):
3774
raise NotAchievedException("Fence breach not cleared")
3775
3776
self.progress("Fly above ceiling and check there is a breach and switch to AUTOLAND mode")
3777
self.context_push()
3778
self.context_collect('STATUSTEXT')
3779
self.set_parameters({
3780
"FENCE_ACTION": 8, # Set action to AUTOLAND if possible
3781
})
3782
3783
self.set_rc(3, 2000)
3784
self.set_rc(2, 1000)
3785
3786
self.wait_statustext("Max Alt fence breached", timeout=10, check_context=True)
3787
self.wait_mode(26) # AUTOLAND,need pymavlink .43 to use text name
3788
self.assert_fence_sys_status(True, True, False)
3789
3790
self.set_rc(3, 1500)
3791
self.set_rc(2, 1500)
3792
3793
self.progress("Wait for cruise alt reached")
3794
self.wait_altitude(
3795
cruise_alt-5,
3796
cruise_alt+5,
3797
relative=True,
3798
timeout=30,
3799
)
3800
3801
self.progress("Check fence breach cleared")
3802
self.assert_fence_sys_status(True, True, True)
3803
3804
self.context_pop()
3805
self.change_mode('FBWA')
3806
self.progress("Fly below floor and check for breach")
3807
self.set_rc(2, 2000)
3808
self.wait_statustext("Min Alt fence breached", timeout=10, check_context=True)
3809
self.wait_mode("RTL")
3810
m = self.assert_receive_message('SYS_STATUS')
3811
if (m.onboard_control_sensors_health & fence_bit):
3812
raise NotAchievedException("Fence floor not breached")
3813
3814
self.change_mode("FBWA")
3815
3816
self.progress("Fly above floor and check fence is enabled")
3817
self.set_rc(3, 2000)
3818
self.change_altitude(75, relative=True)
3819
m = self.assert_receive_message('SYS_STATUS')
3820
if (not (m.onboard_control_sensors_enabled & fence_bit)):
3821
raise NotAchievedException("Fence Floor not enabled")
3822
3823
self.progress("Toggle fence enable/disable")
3824
self.set_rc(7, 2000)
3825
self.delay_sim_time(2)
3826
self.set_rc(7, 1000)
3827
self.delay_sim_time(2)
3828
3829
self.progress("Check fence is disabled")
3830
m = self.assert_receive_message('SYS_STATUS')
3831
if (m.onboard_control_sensors_enabled & fence_bit):
3832
raise NotAchievedException("Fence disable with switch failed")
3833
3834
self.progress("Fly below floor and check for no breach")
3835
self.change_altitude(40, relative=True)
3836
m = self.assert_receive_message('SYS_STATUS')
3837
if (not (m.onboard_control_sensors_health & fence_bit)):
3838
raise NotAchievedException("Fence floor breached")
3839
3840
self.progress("Return to cruise alt")
3841
self.set_rc(3, 1500)
3842
self.change_altitude(cruise_alt, relative=True)
3843
self.fly_home_land_and_disarm(timeout=250)
3844
3845
def FenceCircleExclusionAutoEnable(self):
3846
'''Tests autolanding when alt min fence is enabled'''
3847
self.set_parameters({
3848
"FENCE_TYPE": 2, # Set fence type to circle
3849
"FENCE_ACTION": 1, # Set action to RTL
3850
"FENCE_AUTOENABLE": 2,
3851
"FENCE_ENABLE" : 0,
3852
"RTL_AUTOLAND" : 2,
3853
})
3854
3855
fence_loc = self.home_position_as_mav_location()
3856
self.location_offset_ne(fence_loc, 300, 0)
3857
3858
self.upload_fences_from_locations([(
3859
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION, {
3860
"radius" : 100,
3861
"loc" : fence_loc
3862
}
3863
)])
3864
3865
self.takeoff(alt=50, mode='TAKEOFF')
3866
self.change_mode("FBWA")
3867
self.set_rc(3, 1100) # lower throttle
3868
3869
self.progress("Waiting for RTL")
3870
self.wait_mode('RTL')
3871
# Now check we can land
3872
self.fly_home_land_and_disarm()
3873
3874
def FenceEnableDisableSwitch(self):
3875
'''Tests enablement and disablement of fences on a switch'''
3876
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
3877
3878
self.set_parameters({
3879
"FENCE_TYPE": 4, # Set fence type to polyfence
3880
"FENCE_ACTION": 6, # Set action to GUIDED
3881
"FENCE_ALT_MIN": 10,
3882
"FENCE_ENABLE" : 0,
3883
"RC7_OPTION" : 11, # AC_Fence uses Aux switch functionality
3884
})
3885
3886
self.progress("Checking fence is not present before being configured")
3887
m = self.assert_receive_message('SYS_STATUS')
3888
self.progress("Got (%s)" % str(m))
3889
if (m.onboard_control_sensors_enabled & fence_bit):
3890
raise NotAchievedException("Fence enabled before being configured")
3891
3892
self.wait_ready_to_arm()
3893
# takeoff at a lower altitude to avoid immediately breaching polyfence
3894
self.takeoff(alt=25)
3895
self.change_mode("FBWA")
3896
3897
self.load_fence("CMAC-fence.txt")
3898
3899
self.set_rc_from_map({
3900
3: 1500,
3901
7: 2000,
3902
}) # Turn fence on with aux function
3903
3904
m = self.assert_receive_message('FENCE_STATUS', timeout=2, verbose=True)
3905
3906
self.progress("Checking fence is initially OK")
3907
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE,
3908
present=True,
3909
enabled=True,
3910
healthy=True,
3911
verbose=False,
3912
timeout=30)
3913
3914
self.progress("Waiting for GUIDED")
3915
tstart = self.get_sim_time()
3916
mode = "GUIDED"
3917
while not self.mode_is(mode, drain_mav=False):
3918
self.mav.messages['HEARTBEAT'].custom_mode
3919
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
3920
self.mav.flightmode, mode, self.get_altitude(relative=True)))
3921
if (self.get_sim_time_cached() > tstart + 120):
3922
raise WaitModeTimeout("Did not change mode")
3923
self.progress("Got mode %s" % mode)
3924
# check we are in breach
3925
self.assert_fence_enabled()
3926
3927
self.set_rc_from_map({
3928
7: 1000,
3929
}) # Turn fence off with aux function
3930
3931
# wait to no longer be in breach
3932
self.delay_sim_time(5)
3933
self.assert_fence_disabled()
3934
3935
self.fly_home_land_and_disarm(timeout=250)
3936
self.do_fence_disable() # Ensure the fence is disabled after test
3937
3938
def FenceEnableDisableAux(self):
3939
'''Tests enablement and disablement of fences via aux command'''
3940
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
3941
3942
enable = 0
3943
self.set_parameters({
3944
"FENCE_TYPE": 12, # Set fence type to polyfence + AltMin
3945
"FENCE_ALT_MIN": 10,
3946
"FENCE_ENABLE" : enable,
3947
})
3948
3949
if not enable:
3950
self.progress("Checking fence is not present before being configured")
3951
m = self.assert_receive_message('SYS_STATUS')
3952
self.progress("Got (%s)" % str(m))
3953
if (m.onboard_control_sensors_enabled & fence_bit):
3954
raise NotAchievedException("Fence enabled before being configured")
3955
3956
self.load_fence("CMAC-fence.txt")
3957
3958
self.wait_ready_to_arm()
3959
# takeoff at a lower altitude to avoid immediately breaching polyfence
3960
self.takeoff(alt=25)
3961
self.change_mode("CRUISE")
3962
self.wait_distance(150, accuracy=20)
3963
3964
self.run_auxfunc(
3965
11,
3966
2,
3967
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
3968
)
3969
3970
m = self.assert_receive_message('FENCE_STATUS', timeout=2, verbose=True)
3971
3972
self.progress("Checking fence is initially OK")
3973
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE,
3974
present=True,
3975
enabled=True,
3976
healthy=True,
3977
verbose=False,
3978
timeout=30)
3979
3980
self.progress("Waiting for RTL")
3981
tstart = self.get_sim_time()
3982
mode = "RTL"
3983
while not self.mode_is(mode, drain_mav=False):
3984
self.mav.messages['HEARTBEAT'].custom_mode
3985
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
3986
self.mav.flightmode, mode, self.get_altitude(relative=True)))
3987
if (self.get_sim_time_cached() > tstart + 120):
3988
raise WaitModeTimeout("Did not change mode")
3989
self.progress("Got mode %s" % mode)
3990
# check we are in breach
3991
self.assert_fence_enabled()
3992
self.assert_fence_sys_status(True, True, False)
3993
3994
# wait until we get home
3995
self.wait_distance_to_home(50, 100, timeout=200)
3996
# now check we are now not in breach
3997
self.assert_fence_sys_status(True, True, True)
3998
# Turn fence off with aux function
3999
self.run_auxfunc(
4000
11,
4001
0,
4002
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
4003
)
4004
# switch back to cruise
4005
self.change_mode("CRUISE")
4006
self.wait_distance(150, accuracy=20)
4007
4008
# re-enable the fences
4009
self.run_auxfunc(
4010
11,
4011
2,
4012
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED
4013
)
4014
4015
m = self.assert_receive_message('FENCE_STATUS', timeout=2, verbose=True)
4016
4017
self.progress("Waiting for RTL")
4018
tstart = self.get_sim_time()
4019
mode = "RTL"
4020
while not self.mode_is(mode, drain_mav=False):
4021
self.mav.messages['HEARTBEAT'].custom_mode
4022
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
4023
self.mav.flightmode, mode, self.get_altitude(relative=True)))
4024
if (self.get_sim_time_cached() > tstart + 120):
4025
raise WaitModeTimeout("Did not change mode")
4026
self.progress("Got mode %s" % mode)
4027
4028
# wait to no longer be in breach
4029
self.wait_distance_to_home(50, 100, timeout=200)
4030
self.assert_fence_sys_status(True, True, True)
4031
4032
# fly home and land with fences still enabled
4033
self.fly_home_land_and_disarm(timeout=250)
4034
self.do_fence_disable() # Ensure the fence is disabled after test
4035
4036
def FenceBreachedChangeMode(self):
4037
'''Tests manual mode change after fence breach, as set with FENCE_OPTIONS'''
4038
""" Attempts to change mode while a fence is breached.
4039
mode should change should fail if fence option bit is set"""
4040
self.set_parameters({
4041
"FENCE_ACTION": 1,
4042
"FENCE_TYPE": 4,
4043
})
4044
home_loc = self.mav.location()
4045
locs = [
4046
mavutil.location(home_loc.lat - 0.001, home_loc.lng - 0.001, 0, 0),
4047
mavutil.location(home_loc.lat - 0.001, home_loc.lng + 0.001, 0, 0),
4048
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.001, 0, 0),
4049
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
4050
]
4051
self.upload_fences_from_locations([
4052
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),
4053
])
4054
self.delay_sim_time(1)
4055
self.wait_ready_to_arm()
4056
self.takeoff(alt=50)
4057
self.change_mode("CRUISE")
4058
self.wait_distance(250, accuracy=15)
4059
4060
self.progress("Enable fence and initiate fence action")
4061
self.do_fence_enable()
4062
self.assert_fence_enabled()
4063
self.wait_mode("RTL") # We should RTL because of fence breach
4064
4065
self.progress("User mode change to cruise should retrigger fence action")
4066
try:
4067
# mode change should time out, 'WaitModeTimeout' exception is the desired result
4068
# can't wait too long or the vehicle will be inside fence and allow the mode change
4069
self.change_mode("CRUISE", timeout=10)
4070
raise NotAchievedException("Should not change mode in fence breach")
4071
except WaitModeTimeout:
4072
pass
4073
except Exception as e:
4074
raise e
4075
4076
# enable mode change
4077
self.set_parameter("FENCE_OPTIONS", 0)
4078
self.progress("Check user mode change to LOITER is allowed")
4079
self.change_mode("LOITER")
4080
4081
# Fly for 20 seconds and make sure still in LOITER mode
4082
self.delay_sim_time(20)
4083
if not self.mode_is("LOITER"):
4084
raise NotAchievedException("Fence should not re-trigger")
4085
4086
# reset options parameter
4087
self.set_parameter("FENCE_OPTIONS", 1)
4088
4089
self.progress("Test complete, disable fence and come home")
4090
self.do_fence_disable()
4091
self.fly_home_land_and_disarm()
4092
4093
def FenceNoFenceReturnPoint(self):
4094
'''Tests calculated return point during fence breach when no fence return point present'''
4095
""" Attempts to change mode while a fence is breached.
4096
This should revert to the mode specified by the fence action. """
4097
want_radius = 100 # Fence Return Radius
4098
self.set_parameters({
4099
"FENCE_ACTION": 6,
4100
"FENCE_TYPE": 4,
4101
"RTL_RADIUS": want_radius,
4102
"NAVL1_LIM_BANK": 60,
4103
})
4104
home_loc = self.mav.location()
4105
locs = [
4106
mavutil.location(home_loc.lat - 0.003, home_loc.lng - 0.001, 0, 0),
4107
mavutil.location(home_loc.lat - 0.003, home_loc.lng + 0.003, 0, 0),
4108
mavutil.location(home_loc.lat + 0.001, home_loc.lng + 0.003, 0, 0),
4109
mavutil.location(home_loc.lat + 0.001, home_loc.lng - 0.001, 0, 0),
4110
]
4111
self.upload_fences_from_locations([
4112
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),
4113
])
4114
self.delay_sim_time(1)
4115
self.wait_ready_to_arm()
4116
self.takeoff(alt=50)
4117
self.change_mode("CRUISE")
4118
self.wait_distance(150, accuracy=20)
4119
4120
self.progress("Enable fence and initiate fence action")
4121
self.do_fence_enable()
4122
self.assert_fence_enabled()
4123
self.wait_mode("GUIDED", timeout=120) # We should RTL because of fence breach
4124
self.delay_sim_time(60)
4125
4126
items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4127
if len(items) != 4:
4128
raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (4, len(items)))
4129
4130
# Check there are no fence return points specified still
4131
for fence_loc in items:
4132
if fence_loc.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:
4133
raise NotAchievedException(
4134
"Unexpected fence return point found (%u) got %u" %
4135
(fence_loc.command,
4136
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))
4137
4138
# Work out the approximate return point when no fence return point present
4139
# Logic taken from AC_PolyFence_loader.cpp
4140
min_loc = self.mav.location()
4141
max_loc = self.mav.location()
4142
for new_loc in locs:
4143
if new_loc.lat < min_loc.lat:
4144
min_loc.lat = new_loc.lat
4145
if new_loc.lng < min_loc.lng:
4146
min_loc.lng = new_loc.lng
4147
if new_loc.lat > max_loc.lat:
4148
max_loc.lat = new_loc.lat
4149
if new_loc.lng > max_loc.lng:
4150
max_loc.lng = new_loc.lng
4151
4152
# Generate the return location based on min and max locs
4153
ret_lat = (min_loc.lat + max_loc.lat) / 2
4154
ret_lng = (min_loc.lng + max_loc.lng) / 2
4155
ret_loc = mavutil.location(ret_lat, ret_lng, 0, 0)
4156
self.progress("Return loc: (%s)" % str(ret_loc))
4157
4158
# Wait for guided return to vehicle calculated fence return location
4159
self.wait_distance_to_location(ret_loc, 90, 110)
4160
self.wait_circling_point_with_radius(ret_loc, 92)
4161
4162
self.progress("Test complete, disable fence and come home")
4163
self.do_fence_disable()
4164
self.fly_home_land_and_disarm()
4165
4166
def FenceNoFenceReturnPointInclusion(self):
4167
'''Tests using home as fence return point when none is present, and no inclusion fence is uploaded'''
4168
""" Test result when a breach occurs and No fence return point is present and
4169
no inclusion fence is present and exclusion fence is present """
4170
want_radius = 100 # Fence Return Radius
4171
4172
self.set_parameters({
4173
"FENCE_ACTION": 6,
4174
"FENCE_TYPE": 2,
4175
"FENCE_RADIUS": 300,
4176
"RTL_RADIUS": want_radius,
4177
"NAVL1_LIM_BANK": 60,
4178
})
4179
4180
self.clear_fence()
4181
4182
self.delay_sim_time(1)
4183
self.wait_ready_to_arm()
4184
home_loc = self.mav.location()
4185
self.takeoff(alt=50)
4186
self.change_mode("CRUISE")
4187
self.wait_distance(150, accuracy=20)
4188
4189
self.progress("Enable fence and initiate fence action")
4190
self.do_fence_enable()
4191
self.assert_fence_enabled()
4192
self.wait_mode("GUIDED") # We should RTL because of fence breach
4193
self.delay_sim_time(30)
4194
4195
items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4196
if len(items) != 0:
4197
raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (0, len(items)))
4198
4199
# Check there are no fence return points specified still
4200
for fence_loc in items:
4201
if fence_loc.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:
4202
raise NotAchievedException(
4203
"Unexpected fence return point found (%u) got %u" %
4204
(fence_loc.command,
4205
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))
4206
4207
# Wait for guided return to vehicle calculated fence return location
4208
self.wait_distance_to_location(home_loc, 90, 110)
4209
self.wait_circling_point_with_radius(home_loc, 92)
4210
4211
self.progress("Test complete, disable fence and come home")
4212
self.do_fence_disable()
4213
self.fly_home_land_and_disarm()
4214
4215
def FenceDisableUnderAction(self):
4216
'''Tests Disabling fence while undergoing action caused by breach'''
4217
""" Fence breach will cause the vehicle to enter guided mode.
4218
Upon breach clear, check the vehicle is in the expected mode"""
4219
self.set_parameters({
4220
"FENCE_ALT_MIN": 50, # Sets the fence floor
4221
"FENCE_TYPE": 8, # Only use fence floor for breaches
4222
})
4223
self.wait_ready_to_arm()
4224
4225
def attempt_fence_breached_disable(start_mode, end_mode, expected_mode, action):
4226
self.set_parameter("FENCE_ACTION", action) # Set Fence Action to Guided
4227
self.change_mode(start_mode)
4228
self.arm_vehicle()
4229
self.do_fence_enable()
4230
self.assert_fence_enabled()
4231
self.wait_mode(expected_mode)
4232
self.do_fence_disable()
4233
self.assert_fence_disabled()
4234
self.wait_mode(end_mode)
4235
self.disarm_vehicle(force=True)
4236
4237
attempt_fence_breached_disable(start_mode="FBWA", end_mode="RTL", expected_mode="RTL", action=1)
4238
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6)
4239
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7)
4240
4241
def _MAV_CMD_DO_AUX_FUNCTION(self, run_cmd):
4242
'''Test triggering Auxiliary Functions via mavlink'''
4243
self.context_collect('STATUSTEXT')
4244
self.run_auxfunc(64, 2, run_cmd=run_cmd) # 64 == reverse throttle
4245
self.wait_statustext("RevThrottle: ENABLE", check_context=True)
4246
self.run_auxfunc(64, 0, run_cmd=run_cmd)
4247
self.wait_statustext("RevThrottle: DISABLE", check_context=True)
4248
self.run_auxfunc(65, 2, run_cmd=run_cmd) # 65 == GPS_DISABLE
4249
4250
self.start_subtest("Bad auxfunc")
4251
self.run_auxfunc(
4252
65231,
4253
2,
4254
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
4255
run_cmd=run_cmd,
4256
)
4257
4258
self.start_subtest("Bad switchpos")
4259
self.run_auxfunc(
4260
62,
4261
17,
4262
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
4263
run_cmd=run_cmd,
4264
)
4265
4266
def MAV_CMD_DO_AUX_FUNCTION(self):
4267
'''Test triggering Auxiliary Functions via mavlink'''
4268
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd)
4269
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd_int)
4270
4271
def FlyEachFrame(self):
4272
'''Fly each supported internal frame'''
4273
vinfo = vehicleinfo.VehicleInfo()
4274
vinfo_options = vinfo.options[self.vehicleinfo_key()]
4275
known_broken_frames = {
4276
"plane-tailsitter": "unstable in hover; unflyable in cruise",
4277
"quadplane-can" : "needs CAN periph",
4278
"stratoblimp" : "not expected to fly normally",
4279
"glider" : "needs balloon lift",
4280
}
4281
for frame in sorted(vinfo_options["frames"].keys()):
4282
self.start_subtest("Testing frame (%s)" % str(frame))
4283
if frame in known_broken_frames:
4284
self.progress("Actually, no I'm not - it is known-broken (%s)" %
4285
(known_broken_frames[frame]))
4286
continue
4287
frame_bits = vinfo_options["frames"][frame]
4288
print("frame_bits: %s" % str(frame_bits))
4289
if frame_bits.get("external", False):
4290
self.progress("Actually, no I'm not - it is an external simulation")
4291
continue
4292
model = frame_bits.get("model", frame)
4293
defaults = self.model_defaults_filepath(frame)
4294
if not isinstance(defaults, list):
4295
defaults = [defaults]
4296
self.customise_SITL_commandline(
4297
[],
4298
defaults_filepath=defaults,
4299
model=model,
4300
wipe=True,
4301
)
4302
mission_file = "basic.txt"
4303
quadplane = self.get_parameter('Q_ENABLE')
4304
if quadplane:
4305
mission_file = "basic-quadplane.txt"
4306
tailsitter = self.get_parameter('Q_TAILSIT_ENABLE')
4307
if tailsitter:
4308
# tailsitter needs extra re-boot to pick up the rotated AHRS view
4309
self.reboot_sitl()
4310
self.wait_ready_to_arm()
4311
self.arm_vehicle()
4312
self.fly_mission(mission_file, strict=False, quadplane=quadplane, mission_timeout=400.0)
4313
self.wait_disarmed()
4314
4315
def AutoLandMode(self):
4316
'''Test AUTOLAND mode'''
4317
self.set_parameters({
4318
"AUTOLAND_DIR_OFF": 45,
4319
"TERRAIN_FOLLOW": 1,
4320
"AUTOLAND_CLIMB": 300,
4321
})
4322
self.customise_SITL_commandline(["--home", "-35.362938,149.165085,585,173"])
4323
self.context_collect('STATUSTEXT')
4324
self.load_mission("autoland_mission.txt")
4325
self.install_terrain_handlers_context()
4326
self.change_mode("AUTO")
4327
self.wait_ready_to_arm()
4328
self.arm_vehicle()
4329
self.wait_text("Autoland direction", check_context=True)
4330
self.wait_waypoint(2, 2, max_dist=100)
4331
self.change_mode(26) # AUTOLAND need .43 pymavlink to use text name
4332
self.wait_disarmed(400)
4333
self.progress("Check the landed heading matches takeoff plus offset")
4334
self.wait_heading(218, accuracy=5, timeout=1)
4335
loc = mavutil.location(-35.362938, 149.165085, 585, 218)
4336
if self.get_distance(loc, self.mav.location()) > 35:
4337
raise NotAchievedException("Did not land close to home")
4338
self.set_parameters({
4339
"TKOFF_OPTIONS": 2,
4340
})
4341
self.wait_ready_to_arm()
4342
self.set_autodisarm_delay(0)
4343
self.arm_vehicle()
4344
self.progress("Check the set dir on arm option")
4345
self.wait_text("Autoland direction", check_context=True)
4346
4347
def RCDisableAirspeedUse(self):
4348
'''Test RC DisableAirspeedUse option'''
4349
self.set_parameter("RC9_OPTION", 106)
4350
self.delay_sim_time(5)
4351
self.set_rc(9, 1000)
4352
self.wait_sensor_state(
4353
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
4354
True,
4355
True,
4356
True)
4357
self.set_rc(9, 2000)
4358
self.wait_sensor_state(
4359
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
4360
True,
4361
False,
4362
True)
4363
self.set_rc(9, 1000)
4364
self.wait_sensor_state(
4365
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
4366
True,
4367
True,
4368
True)
4369
4370
def WatchdogHome(self):
4371
'''Ensure home is restored after watchdog reset'''
4372
if self.gdb:
4373
# we end up signalling the wrong process. I think.
4374
# Probably need to have a "sitl_pid()" method to get the
4375
# ardupilot process's PID.
4376
self.progress("######## Skipping WatchdogHome test under GDB")
4377
return
4378
4379
ex = None
4380
try:
4381
self.progress("Enabling watchdog")
4382
self.set_parameter("BRD_OPTIONS", 1 << 0)
4383
self.reboot_sitl()
4384
self.wait_ready_to_arm()
4385
self.progress("Explicitly setting home to a known location")
4386
orig_home = self.poll_home_position()
4387
new_home = orig_home
4388
new_home.latitude = new_home.latitude + 1000
4389
new_home.longitude = new_home.longitude + 2000
4390
new_home.altitude = new_home.altitude + 300000 # 300 metres
4391
self.run_cmd_int(
4392
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
4393
p5=new_home.latitude,
4394
p6=new_home.longitude,
4395
p7=new_home.altitude/1000.0, # mm => m
4396
)
4397
old_bootcount = self.get_parameter('STAT_BOOTCNT')
4398
self.progress("Forcing watchdog reset")
4399
os.kill(self.sitl.pid, signal.SIGALRM)
4400
self.detect_and_handle_reboot(old_bootcount)
4401
self.wait_statustext("WDG:")
4402
self.wait_statustext("IMU1 is using GPS") # won't be come armable
4403
self.progress("Verifying home position")
4404
post_reboot_home = self.poll_home_position()
4405
delta = self.get_distance_int(new_home, post_reboot_home)
4406
max_delta = 1
4407
if delta > max_delta:
4408
raise NotAchievedException(
4409
"New home not where it should be (dist=%f) (want=%s) (got=%s)" %
4410
(delta, str(new_home), str(post_reboot_home)))
4411
except Exception as e:
4412
self.print_exception_caught(e)
4413
ex = e
4414
4415
self.reboot_sitl()
4416
4417
if ex is not None:
4418
raise ex
4419
4420
def AUTOTUNE(self):
4421
'''Test AutoTune mode'''
4422
self.run_autotune()
4423
4424
# Values that are set to constants
4425
# If these are changed then the expected tune parameters should also change
4426
self.assert_parameter_value_pct("RLL2SRV_TCONST", 0.5, 0)
4427
self.assert_parameter_value_pct("RLL2SRV_RMAX", 75, 0)
4428
self.assert_parameter_value_pct("RLL_RATE_IMAX", 0.666, 0.01) # allow some small error to account for floating point stuff # noqa:E501
4429
self.assert_parameter_value_pct("RLL_RATE_FLTT", 3.183, 0.01)
4430
self.assert_parameter_value_pct("RLL_RATE_FLTE", 0, 0)
4431
self.assert_parameter_value_pct("RLL_RATE_FLTD", 10.0, 0)
4432
self.assert_parameter_value_pct("RLL_RATE_SMAX", 150.0, 0)
4433
4434
self.assert_parameter_value_pct("PTCH2SRV_TCONST", 0.75, 0)
4435
self.assert_parameter_value_pct("PTCH2SRV_RMAX_UP", 75, 0)
4436
self.assert_parameter_value_pct("PTCH2SRV_RMAX_DN", 75, 0)
4437
self.assert_parameter_value_pct("PTCH_RATE_IMAX", 0.666, 0.01)
4438
self.assert_parameter_value_pct("PTCH_RATE_FLTT", 2.122, 0.01)
4439
self.assert_parameter_value_pct("PTCH_RATE_FLTE", 0, 0)
4440
self.assert_parameter_value_pct("PTCH_RATE_FLTD", 10, 0)
4441
self.assert_parameter_value_pct("PTCH_RATE_SMAX", 150, 0)
4442
4443
# Check tuned values, targets derived from running tests multiple times and taking average
4444
# Expect within 2%
4445
# Note that I is not checked directly, its value is derived from P, FF, and TCONST which are all checked.
4446
self.assert_parameter_value_pct("RLL_RATE_P", 1.222702146, 2)
4447
self.assert_parameter_value_pct("RLL_RATE_FF", 0.229291457, 2)
4448
4449
self.assert_parameter_value_pct("PTCH_RATE_FF", 0.503520715, 5)
4450
4451
# there are sometimes multiple solutions for roll but the distribution
4452
# is much more skewed than pitch below
4453
try:
4454
self.assert_parameter_value_pct("RLL_RATE_D", 0.070284024, 2)
4455
except ValueError:
4456
self.assert_parameter_value_pct("RLL_RATE_D", 0.091369226, 2) # added 2025-10
4457
4458
# There seem to be multiple solutions for pitch. I'm not sure why this is.
4459
# Each value is quite consistent because of the fixed steps that autotune takes
4460
try:
4461
# Expect this about 84% of the time
4462
self.assert_parameter_value_pct("PTCH_RATE_P", 1.746079683, 2)
4463
except ValueError:
4464
try:
4465
# 12%
4466
self.assert_parameter_value_pct("PTCH_RATE_P", 1.343138218, 2)
4467
except ValueError:
4468
# 4%
4469
self.assert_parameter_value_pct("PTCH_RATE_P", 2.26990366, 2)
4470
4471
try:
4472
# 64%
4473
self.assert_parameter_value_pct("PTCH_RATE_D", 0.108, 2)
4474
except ValueError:
4475
try:
4476
# 28%
4477
self.assert_parameter_value_pct("PTCH_RATE_D", 0.141, 2)
4478
except ValueError:
4479
try:
4480
# 4%
4481
self.assert_parameter_value_pct("PTCH_RATE_D", 0.049, 2)
4482
except ValueError:
4483
# 4%
4484
try:
4485
self.assert_parameter_value_pct("PTCH_RATE_D", 0.0836, 2)
4486
except ValueError:
4487
self.assert_parameter_value_pct("PTCH_RATE_D", 0.0380, 2) # added 2025-10
4488
4489
def run_autotune(self):
4490
self.takeoff(100)
4491
self.change_mode('AUTOTUNE')
4492
self.context_collect('STATUSTEXT')
4493
tstart = self.get_sim_time()
4494
axis = "Roll"
4495
rc_value = 1000
4496
while True:
4497
timeout = 600
4498
if self.get_sim_time() - tstart > timeout:
4499
raise NotAchievedException("Did not complete within %u seconds" % timeout)
4500
try:
4501
m = self.wait_statustext("%s: Finished" % axis, check_context=True, timeout=0.1)
4502
self.progress("Got %s" % str(m))
4503
if axis == "Roll":
4504
axis = "Pitch"
4505
# Center sticks to allow roll to return to neutral before starting pitch
4506
self.set_rc(1, 1500)
4507
self.set_rc(2, 1500)
4508
self.delay_sim_time(15)
4509
4510
# Reset toggle value so the initial input is in a consistent direction
4511
rc_value = 1000
4512
4513
elif axis == "Pitch":
4514
break
4515
else:
4516
raise ValueError("Bug: %s" % axis)
4517
except AutoTestTimeoutException:
4518
pass
4519
self.delay_sim_time(1)
4520
4521
if rc_value == 1000:
4522
rc_value = 2000
4523
elif rc_value == 2000:
4524
rc_value = 1000
4525
elif rc_value == 1000:
4526
rc_value = 2000
4527
else:
4528
raise ValueError("Bug")
4529
4530
if axis == "Roll":
4531
self.set_rc(1, rc_value)
4532
self.set_rc(2, 1500)
4533
elif axis == "Pitch":
4534
self.set_rc(1, 1500)
4535
self.set_rc(2, rc_value)
4536
else:
4537
raise ValueError("Bug")
4538
4539
tdelta = self.get_sim_time() - tstart
4540
self.progress("Finished in %0.1f seconds" % (tdelta,))
4541
4542
self.set_rc(1, 1500)
4543
self.set_rc(2, 1500)
4544
4545
self.change_mode('FBWA')
4546
self.fly_home_land_and_disarm(timeout=tdelta+240)
4547
4548
def AutotuneFiltering(self):
4549
'''Test AutoTune mode with filter updates disabled'''
4550
self.set_parameters({
4551
"AUTOTUNE_OPTIONS": 3,
4552
# some filtering is required for autotune to complete
4553
"RLL_RATE_FLTD": 10,
4554
"PTCH_RATE_FLTD": 10,
4555
"RLL_RATE_FLTT": 20,
4556
"PTCH_RATE_FLTT": 20,
4557
})
4558
self.run_autotune()
4559
4560
def LandingDrift(self):
4561
'''Circuit with baro drift'''
4562
self.customise_SITL_commandline([], wipe=True)
4563
4564
self.set_analog_rangefinder_parameters()
4565
4566
self.set_parameters({
4567
"SIM_BARO_DRIFT": -0.02,
4568
"SIM_TERRAIN": 0,
4569
"RNGFND_LANDING": 1,
4570
"LAND_SLOPE_RCALC": 2,
4571
"LAND_ABORT_DEG": 1,
4572
})
4573
4574
self.reboot_sitl()
4575
4576
self.wait_ready_to_arm()
4577
self.arm_vehicle()
4578
4579
# Load and start mission
4580
self.load_mission("ap-circuit.txt", strict=True)
4581
self.set_current_waypoint(1, check_afterwards=True)
4582
self.change_mode('AUTO')
4583
self.wait_current_waypoint(1, timeout=5)
4584
self.wait_groundspeed(0, 10, timeout=5)
4585
4586
# Wait for landing waypoint
4587
self.wait_current_waypoint(9, timeout=1200)
4588
4589
# Wait for landing restart
4590
self.wait_current_waypoint(5, timeout=60)
4591
4592
# Wait for landing waypoint (second attempt)
4593
self.wait_current_waypoint(9, timeout=1200)
4594
4595
self.wait_disarmed(timeout=180)
4596
4597
def TakeoffAuto1(self):
4598
'''Test the behaviour of an AUTO takeoff, pt1.'''
4599
'''
4600
Conditions:
4601
- ARSPD_USE=1
4602
- TKOFF_OPTIONS[0]=0
4603
- TKOFF_THR_MAX < THR_MAX
4604
'''
4605
4606
self.customise_SITL_commandline(
4607
[],
4608
model='plane-catapult',
4609
defaults_filepath=self.model_defaults_filepath("plane")
4610
)
4611
self.set_parameters({
4612
"ARSPD_USE": 1.0,
4613
"THR_MAX": 100.0,
4614
"TKOFF_THR_MAX": 80.0,
4615
"TKOFF_THR_MINACC": 3.0,
4616
"TECS_PITCH_MAX": 35.0,
4617
"PTCH_LIM_MAX_DEG": 35.0,
4618
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
4619
})
4620
4621
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4622
self.wait_ready_to_arm()
4623
4624
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4625
self.load_mission("catapult.txt", strict=True)
4626
self.change_mode('AUTO')
4627
4628
self.arm_vehicle()
4629
4630
# Throw the catapult.
4631
self.set_servo(7, 2000)
4632
4633
# Wait until we're midway through the climb.
4634
test_alt = 50
4635
self.wait_altitude(test_alt, test_alt+2, relative=True)
4636
4637
# Ensure that by then the aircraft still goes at max allowed throttle.
4638
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4639
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4640
4641
# Wait for landing waypoint.
4642
self.wait_current_waypoint(11, timeout=1200)
4643
self.wait_disarmed(120)
4644
4645
def TakeoffAuto2(self):
4646
'''Test the behaviour of an AUTO takeoff, pt2.'''
4647
'''
4648
Conditions:
4649
- ARSPD_USE=0
4650
- TKOFF_OPTIONS[0]=0
4651
- TKOFF_THR_MAX > THR_MAX
4652
'''
4653
4654
self.customise_SITL_commandline(
4655
[],
4656
model='plane-catapult',
4657
defaults_filepath=self.model_defaults_filepath("plane")
4658
)
4659
self.set_parameters({
4660
"ARSPD_USE": 0.0,
4661
"THR_MAX": 80.0,
4662
"TKOFF_THR_MAX": 100.0,
4663
"TKOFF_THR_MINACC": 3.0,
4664
"TECS_PITCH_MAX": 35.0,
4665
"PTCH_LIM_MAX_DEG": 35.0,
4666
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
4667
})
4668
4669
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4670
self.wait_ready_to_arm()
4671
4672
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4673
self.load_mission("catapult.txt", strict=True)
4674
self.change_mode('AUTO')
4675
4676
self.arm_vehicle()
4677
4678
# Throw the catapult.
4679
self.set_servo(7, 2000)
4680
4681
# Wait until we're midway through the climb.
4682
test_alt = 50
4683
self.wait_altitude(test_alt, test_alt+2, relative=True)
4684
4685
# Ensure that by then the aircraft still goes at max allowed throttle.
4686
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4687
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4688
4689
# Wait for landing waypoint.
4690
self.wait_current_waypoint(11, timeout=1200)
4691
self.wait_disarmed(120)
4692
4693
def TakeoffAuto3(self):
4694
'''Test the behaviour of an AUTO takeoff, pt3.'''
4695
'''
4696
Conditions:
4697
- ARSPD_USE=1
4698
- TKOFF_OPTIONS[0]=1
4699
'''
4700
4701
self.customise_SITL_commandline(
4702
[],
4703
model='plane-catapult',
4704
defaults_filepath=self.model_defaults_filepath("plane")
4705
)
4706
self.set_parameters({
4707
"ARSPD_USE": 1.0,
4708
"THR_MAX": 80.0,
4709
"THR_MIN": 0.0,
4710
"TKOFF_OPTIONS": 1.0,
4711
"TKOFF_THR_MAX": 100.0,
4712
"TKOFF_THR_MINACC": 3.0,
4713
"TECS_PITCH_MAX": 35.0,
4714
"TKOFF_THR_MAX_T": 3.0,
4715
"PTCH_LIM_MAX_DEG": 35.0,
4716
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
4717
})
4718
4719
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4720
self.wait_ready_to_arm()
4721
4722
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4723
self.load_mission("catapult.txt", strict=True)
4724
self.change_mode('AUTO')
4725
4726
self.arm_vehicle()
4727
4728
# Throw the catapult.
4729
self.set_servo(7, 2000)
4730
4731
# Ensure that TKOFF_THR_MAX_T is respected.
4732
self.delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1)
4733
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4734
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4735
4736
# Ensure that after that the aircraft does not go full throttle anymore.
4737
test_alt = 50
4738
self.wait_altitude(test_alt, test_alt+2, relative=True)
4739
w = vehicle_test_suite.WaitAndMaintainServoChannelValue(
4740
self,
4741
3, # throttle
4742
1000+10*self.get_parameter("TKOFF_THR_MAX")-10,
4743
comparator=operator.lt,
4744
minimum_duration=1,
4745
)
4746
w.run()
4747
4748
# Wait for landing waypoint.
4749
self.wait_current_waypoint(11, timeout=1200)
4750
self.wait_disarmed(120)
4751
4752
def TakeoffAuto4(self):
4753
'''Test the behaviour of an AUTO takeoff, pt4.'''
4754
'''
4755
Conditions:
4756
- ARSPD_USE=0
4757
- TKOFF_OPTIONS[0]=1
4758
'''
4759
4760
self.customise_SITL_commandline(
4761
[],
4762
model='plane-catapult',
4763
defaults_filepath=self.model_defaults_filepath("plane")
4764
)
4765
self.set_parameters({
4766
"ARSPD_USE": 0.0,
4767
"THR_MAX": 80.0,
4768
"THR_MIN": 0.0,
4769
"TKOFF_OPTIONS": 1.0,
4770
"TKOFF_THR_MAX": 100.0,
4771
"TKOFF_THR_MINACC": 3.0,
4772
"TECS_PITCH_MAX": 35.0,
4773
"TKOFF_THR_MAX_T": 3.0,
4774
"PTCH_LIM_MAX_DEG": 35.0,
4775
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
4776
})
4777
4778
self.wait_ready_to_arm()
4779
4780
# Load and start mission. It contains a MAV_CMD_NAV_TAKEOFF item at 100m.
4781
self.load_mission("catapult.txt", strict=True)
4782
self.change_mode('AUTO')
4783
4784
self.arm_vehicle()
4785
4786
# Throw the catapult.
4787
self.set_servo(7, 2000)
4788
4789
# Ensure that TKOFF_THR_MAX_T is respected.
4790
self.delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1)
4791
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4792
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4793
4794
# Ensure that after that the aircraft still goes to maximum throttle.
4795
test_alt = 50
4796
self.wait_altitude(test_alt, test_alt+2, relative=True)
4797
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4798
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4799
4800
# Wait for landing waypoint.
4801
self.wait_current_waypoint(11, timeout=1200)
4802
self.wait_disarmed(120)
4803
4804
def TakeoffTakeoff1(self):
4805
'''Test the behaviour of a takeoff in TAKEOFF mode, pt1.'''
4806
'''
4807
Conditions:
4808
- ARSPD_USE=1
4809
- TKOFF_OPTIONS[0]=0
4810
- TKOFF_THR_MAX < THR_MAX
4811
'''
4812
4813
self.customise_SITL_commandline(
4814
[],
4815
model='plane-catapult',
4816
defaults_filepath=self.model_defaults_filepath("plane")
4817
)
4818
self.set_parameters({
4819
"ARSPD_USE": 1.0,
4820
"THR_MAX": 100.0,
4821
"TKOFF_LVL_ALT": 30.0,
4822
"TKOFF_ALT": 80.0,
4823
"TKOFF_OPTIONS": 0.0,
4824
"TKOFF_THR_MINACC": 3.0,
4825
"TKOFF_THR_MAX": 80.0,
4826
"TECS_PITCH_MAX": 35.0,
4827
"PTCH_LIM_MAX_DEG": 35.0,
4828
})
4829
self.change_mode("TAKEOFF")
4830
4831
self.wait_ready_to_arm()
4832
self.arm_vehicle()
4833
4834
# Throw the catapult.
4835
self.set_servo(7, 2000)
4836
4837
# Check whether we're at max throttle below TKOFF_LVL_ALT.
4838
test_alt = self.get_parameter("TKOFF_LVL_ALT")-10
4839
self.wait_altitude(test_alt, test_alt+2, relative=True)
4840
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4841
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4842
4843
# Check whether we're still at max throttle past TKOFF_LVL_ALT.
4844
test_alt = self.get_parameter("TKOFF_LVL_ALT")+10
4845
self.wait_altitude(test_alt, test_alt+2, relative=True)
4846
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4847
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4848
4849
# Wait for the takeoff to complete.
4850
target_alt = self.get_parameter("TKOFF_ALT")
4851
self.wait_altitude(target_alt-5, target_alt, relative=True)
4852
4853
# Wait a bit for the Takeoff altitude to settle.
4854
self.delay_sim_time(5)
4855
4856
self.fly_home_land_and_disarm()
4857
4858
def TakeoffTakeoff2(self):
4859
'''Test the behaviour of a takeoff in TAKEOFF mode, pt2.'''
4860
'''
4861
Conditions:
4862
- ARSPD_USE=1
4863
- TKOFF_OPTIONS[0]=1
4864
- TKOFF_THR_MAX < THR_MAX
4865
'''
4866
4867
self.customise_SITL_commandline(
4868
[],
4869
model='plane-catapult',
4870
defaults_filepath=self.model_defaults_filepath("plane")
4871
)
4872
self.set_parameters({
4873
"ARSPD_USE": 1.0,
4874
"THR_MAX": 100.0,
4875
"TKOFF_LVL_ALT": 30.0,
4876
"TKOFF_ALT": 80.0,
4877
"TKOFF_OPTIONS": 1.0,
4878
"TKOFF_THR_MINACC": 3.0,
4879
"TKOFF_THR_MAX": 80.0,
4880
"TECS_PITCH_MAX": 35.0,
4881
"PTCH_LIM_MAX_DEG": 35.0,
4882
})
4883
self.change_mode("TAKEOFF")
4884
4885
self.wait_ready_to_arm()
4886
self.arm_vehicle()
4887
4888
# Throw the catapult.
4889
self.set_servo(7, 2000)
4890
4891
# Check whether we're at max throttle below TKOFF_LVL_ALT.
4892
test_alt = self.get_parameter("TKOFF_LVL_ALT")-10
4893
self.wait_altitude(test_alt, test_alt+2, relative=True)
4894
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
4895
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
4896
4897
# Check whether we've receded from max throttle past TKOFF_LVL_ALT.
4898
test_alt = self.get_parameter("TKOFF_LVL_ALT")+10
4899
self.wait_altitude(test_alt, test_alt+2, relative=True)
4900
thr_min = 1000+10*(self.get_parameter("TKOFF_THR_MIN"))-1
4901
thr_max = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))-10
4902
self.assert_servo_channel_range(3, thr_min, thr_max)
4903
4904
# Wait for the takeoff to complete.
4905
target_alt = self.get_parameter("TKOFF_ALT")
4906
self.wait_altitude(target_alt-5, target_alt, relative=True)
4907
4908
# Wait a bit for the Takeoff altitude to settle.
4909
self.delay_sim_time(5)
4910
4911
self.fly_home_land_and_disarm()
4912
4913
def TakeoffTakeoff3(self):
4914
'''Test the behaviour of a takeoff in TAKEOFF mode, pt3.'''
4915
'''
4916
This is the same as case #1, but with disabled airspeed sensor.
4917
4918
Conditions:
4919
- ARSPD_USE=0
4920
- TKOFF_OPTIONS[0]=0
4921
- TKOFF_THR_MAX < THR_MAX
4922
'''
4923
4924
self.customise_SITL_commandline(
4925
[],
4926
model='plane-catapult',
4927
defaults_filepath=self.model_defaults_filepath("plane")
4928
)
4929
self.set_parameters({
4930
"ARSPD_USE": 0.0,
4931
"THR_MAX": 100.0,
4932
"TKOFF_DIST": 400.0,
4933
"TKOFF_LVL_ALT": 30.0,
4934
"TKOFF_ALT": 100.0,
4935
"TKOFF_OPTIONS": 0.0,
4936
"TKOFF_THR_MINACC": 3.0,
4937
"TKOFF_THR_MAX": 80.0,
4938
"TECS_PITCH_MAX": 35.0,
4939
"PTCH_LIM_MAX_DEG": 35.0,
4940
})
4941
self.change_mode("TAKEOFF")
4942
4943
self.wait_ready_to_arm()
4944
self.arm_vehicle()
4945
4946
# Throw the catapult.
4947
self.set_servo(7, 2000)
4948
4949
# we expect to maintain this throttle level past the takeoff
4950
# altitude through to our takeoff altitude:
4951
expected_takeoff_throttle = 1000+10*self.get_parameter("TKOFF_THR_MAX")
4952
4953
# Check whether we're at max throttle below TKOFF_LVL_ALT.
4954
test_alt = self.get_parameter("TKOFF_LVL_ALT")-10
4955
self.wait_altitude(test_alt, test_alt+2, relative=True)
4956
w = vehicle_test_suite.WaitAndMaintainServoChannelValue(
4957
self,
4958
3, # throttle
4959
expected_takeoff_throttle,
4960
epsilon=10,
4961
minimum_duration=1,
4962
)
4963
w.run()
4964
4965
# Check whether we're still at max throttle past TKOFF_LVL_ALT.
4966
test_alt = self.get_parameter("TKOFF_LVL_ALT")+10
4967
self.wait_altitude(test_alt, test_alt+2, relative=True)
4968
4969
w = vehicle_test_suite.WaitAndMaintainServoChannelValue(
4970
self,
4971
3, # throttle
4972
expected_takeoff_throttle,
4973
epsilon=10,
4974
minimum_duration=1,
4975
)
4976
w.run()
4977
4978
# Wait for the takeoff to complete.
4979
target_alt = self.get_parameter("TKOFF_ALT")
4980
self.wait_altitude(target_alt-2.5, target_alt+2.5, relative=True, minimum_duration=10, timeout=30)
4981
4982
self.reboot_sitl(force=True)
4983
4984
def TakeoffTakeoff4(self):
4985
'''Test the behaviour of a takeoff in TAKEOFF mode, pt4.'''
4986
'''
4987
This is the same as case #3, but with almost stock parameters and without a catapult.
4988
4989
Conditions:
4990
- ARSPD_USE=0
4991
'''
4992
4993
self.customise_SITL_commandline(
4994
[],
4995
model='plane-catapult',
4996
defaults_filepath=self.model_defaults_filepath("plane")
4997
)
4998
self.set_parameters({
4999
"ARSPD_USE": 0.0,
5000
})
5001
self.change_mode("TAKEOFF")
5002
5003
self.wait_ready_to_arm()
5004
self.arm_vehicle()
5005
5006
# Check whether we're at max throttle below TKOFF_LVL_ALT.
5007
test_alt = self.get_parameter("TKOFF_LVL_ALT")-10
5008
self.wait_altitude(test_alt, test_alt+2, relative=True)
5009
target_throttle = 1000+10*(self.get_parameter("THR_MAX"))
5010
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
5011
5012
# Check whether we're still at max throttle past TKOFF_LVL_ALT.
5013
test_alt = self.get_parameter("TKOFF_LVL_ALT")+10
5014
self.wait_altitude(test_alt, test_alt+2, relative=True)
5015
target_throttle = 1000+10*(self.get_parameter("THR_MAX"))
5016
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)
5017
5018
# Wait for the takeoff to complete.
5019
target_alt = self.get_parameter("TKOFF_ALT")
5020
self.wait_altitude(target_alt-5, target_alt, relative=True)
5021
5022
# Wait a bit for the Takeoff altitude to settle.
5023
self.delay_sim_time(5)
5024
5025
self.fly_home_land_and_disarm()
5026
5027
def TakeoffTakeoff5(self):
5028
'''Test the behaviour of a takeoff with no compass'''
5029
self.set_parameters({
5030
"COMPASS_USE": 0,
5031
"COMPASS_USE2": 0,
5032
"COMPASS_USE3": 0,
5033
})
5034
import copy
5035
start_loc = copy.copy(SITL_START_LOCATION)
5036
start_loc.heading = 175
5037
self.customise_SITL_commandline(["--home=%.9f,%.9f,%.2f,%.1f" % (
5038
start_loc.lat, start_loc.lng, start_loc.alt, start_loc.heading)])
5039
self.reboot_sitl()
5040
self.change_mode("TAKEOFF")
5041
5042
# waiting for the EKF to be happy won't work
5043
self.delay_sim_time(20)
5044
self.arm_vehicle()
5045
5046
target_alt = self.get_parameter("TKOFF_ALT")
5047
self.wait_altitude(target_alt-5, target_alt, relative=True)
5048
5049
# Wait a bit for the Takeoff altitude to settle.
5050
self.delay_sim_time(5)
5051
5052
bearing_margin = 35
5053
loc = self.mav.location()
5054
bearing_from_home = self.get_bearing(start_loc, loc)
5055
if bearing_from_home < 0:
5056
bearing_from_home += 360
5057
if abs(bearing_from_home - start_loc.heading) > bearing_margin:
5058
raise NotAchievedException(f"Did not takeoff in the right direction {bearing_from_home}")
5059
5060
self.fly_home_land_and_disarm()
5061
5062
def TakeoffGround(self):
5063
'''Test a rolling TAKEOFF.'''
5064
5065
self.set_parameters({
5066
"TKOFF_ROTATE_SPD": 15.0,
5067
"TKOFF_PLIM_SEC": 0, # Ensure TKOFF_PLIM_SEC doesn't interfere with the test.
5068
"TKOFF_DIST": 500, # Ensure stall prevention doesn't interfere with the test.
5069
"TKOFF_ALT": 100 # Ditto
5070
})
5071
self.change_mode("TAKEOFF")
5072
5073
self.wait_ready_to_arm()
5074
self.arm_vehicle()
5075
5076
# Check that we demand minimum pitch below rotation speed.
5077
self.wait_groundspeed(8, 10)
5078
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=5)
5079
nav_pitch = m.nav_pitch
5080
if nav_pitch > 5.1 or nav_pitch < 4.9:
5081
raise NotAchievedException(f"Did not achieve correct takeoff pitch ({nav_pitch}).")
5082
5083
# Check whether we've achieved correct target pitch after rotation.
5084
self.wait_groundspeed(24, 25)
5085
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=5)
5086
nav_pitch = m.nav_pitch
5087
if nav_pitch > 15.1 or nav_pitch < 14.9:
5088
raise NotAchievedException(f"Did not achieve correct takeoff pitch ({nav_pitch}).")
5089
5090
self.fly_home_land_and_disarm()
5091
5092
def TakeoffIdleThrottle(self):
5093
'''Apply idle throttle before takeoff.'''
5094
self.customise_SITL_commandline(
5095
[],
5096
model='plane-catapult',
5097
defaults_filepath=self.model_defaults_filepath("plane")
5098
)
5099
self.set_parameters({
5100
"TKOFF_THR_IDLE": 20.0,
5101
"TKOFF_THR_MINSPD": 3.0,
5102
})
5103
self.change_mode("TAKEOFF")
5104
5105
self.wait_ready_to_arm()
5106
self.arm_vehicle()
5107
5108
# Ensure that the throttle rises to idle throttle.
5109
expected_idle_throttle = 1000+10*self.get_parameter("TKOFF_THR_IDLE")
5110
self.assert_servo_channel_range(3, expected_idle_throttle-10, expected_idle_throttle+10)
5111
5112
# Launch the catapult
5113
self.set_servo(6, 1000)
5114
5115
self.delay_sim_time(5)
5116
self.change_mode('RTL')
5117
5118
self.fly_home_land_and_disarm()
5119
5120
def TakeoffBadLevelOff(self):
5121
'''Ensure that the takeoff can be completed under 0 pitch demand.'''
5122
'''
5123
When using no airspeed, the pitch level-off will eventually command 0
5124
pitch demand. Ensure that the plane can climb the final 2m to deem the
5125
takeoff complete.
5126
'''
5127
5128
self.customise_SITL_commandline(
5129
[],
5130
model='plane-catapult',
5131
defaults_filepath=self.model_defaults_filepath("plane")
5132
)
5133
self.set_parameters({
5134
"ARSPD_USE": 0.0,
5135
"PTCH_TRIM_DEG": -10.0,
5136
"RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item.
5137
"TKOFF_ALT": 50.0,
5138
"TKOFF_DIST": 1000.0,
5139
"TKOFF_THR_MAX": 75.0,
5140
"TKOFF_THR_MINACC": 3.0,
5141
})
5142
5143
self.load_mission("flaps_tkoff_50.txt")
5144
self.change_mode('AUTO')
5145
5146
self.wait_ready_to_arm()
5147
self.arm_vehicle()
5148
5149
# Throw the catapult.
5150
self.set_servo(7, 2000)
5151
5152
# Wait until we've reached the takeoff altitude.
5153
target_alt = 50
5154
self.wait_altitude(target_alt-1, target_alt+1, relative=True, timeout=30)
5155
5156
self.delay_sim_time(5)
5157
5158
self.disarm_vehicle(force=True)
5159
5160
def TakeoffLevelOffWind(self):
5161
'''Ensure the level-off functionality works.'''
5162
'''
5163
This is primarily targeted to test whether the level-off angle works
5164
correctly even though the groundspeed eventually drops in face of wind.
5165
'''
5166
tkoff_alt = 100.
5167
self.set_parameters({
5168
"TKOFF_ROTATE_SPD": 15.0,
5169
"TKOFF_ALT": tkoff_alt,
5170
"TKOFF_DIST": 500, # Ensure stall prevention doesn't interfere with the test.
5171
"TKOFF_PLIM_SEC": 5 # Give some more time to detect the level-off.
5172
})
5173
self.change_mode("TAKEOFF")
5174
5175
self.wait_ready_to_arm()
5176
self.arm_vehicle()
5177
5178
# Wait until we're well past the rotation.
5179
self.wait_groundspeed(24, 25)
5180
5181
self.set_parameters({
5182
"SIM_WIND_DIR": 0.0, # Set North wind.
5183
"SIM_WIND_SPD": 10.0 # Enough to bring groundspeed below cruise speed.
5184
})
5185
5186
self.wait_altitude(tkoff_alt-10, tkoff_alt, relative=True)
5187
self.wait_level_flight(accuracy=10, timeout=1) # Ensure we have roughly level-off.
5188
self.delay_sim_time(5)
5189
5190
self.change_mode('AUTOLAND')
5191
self.wait_disarmed(timeout=180)
5192
5193
def DCMFallback(self):
5194
'''Really annoy the EKF and force fallback'''
5195
self.reboot_sitl()
5196
self.delay_sim_time(30)
5197
5198
self.takeoff(50)
5199
self.change_mode('CIRCLE')
5200
self.context_push()
5201
self.context_collect('STATUSTEXT')
5202
self.set_parameters({
5203
"EK3_POS_I_GATE": 0,
5204
"SIM_GPS1_HZ": 1,
5205
"SIM_GPS1_LAG_MS": 1000,
5206
})
5207
self.wait_statustext("DCM Active", check_context=True, timeout=60)
5208
self.wait_statustext("EKF3 Active", check_context=True)
5209
self.wait_statustext("DCM Active", check_context=True)
5210
self.wait_statustext("EKF3 Active", check_context=True)
5211
self.wait_statustext("DCM Active", check_context=True)
5212
self.wait_statustext("EKF3 Active", check_context=True)
5213
self.context_stop_collecting('STATUSTEXT')
5214
5215
self.fly_home_land_and_disarm()
5216
self.context_pop()
5217
self.reboot_sitl()
5218
5219
def ForcedDCM(self):
5220
'''Switch to DCM mid-flight'''
5221
self.wait_ready_to_arm()
5222
self.arm_vehicle()
5223
5224
self.takeoff(50)
5225
self.context_collect('STATUSTEXT')
5226
self.set_parameter("AHRS_EKF_TYPE", 0)
5227
self.wait_statustext("DCM Active", check_context=True)
5228
self.context_stop_collecting('STATUSTEXT')
5229
5230
self.change_mode('AUTOLAND')
5231
self.wait_disarmed(timeout=180)
5232
5233
def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True):
5234
'''method to be called by EFI tests'''
5235
self.start_subtest("EFI Test for (%s)" % name)
5236
self.assert_not_receiving_message('EFI_STATUS')
5237
self.set_parameters({
5238
'SIM_EFI_TYPE': efi_type,
5239
'EFI_TYPE': efi_type,
5240
'SERIAL5_PROTOCOL': 24,
5241
'RPM1_TYPE': 10,
5242
})
5243
5244
self.customise_SITL_commandline(
5245
["--serial5=sim:%s" % sim_name,
5246
],
5247
)
5248
self.wait_ready_to_arm()
5249
5250
baro_m = self.assert_receive_message("SCALED_PRESSURE")
5251
self.progress(self.dump_message_verbose(baro_m))
5252
baro_temperature = baro_m.temperature / 100.0 # cDeg->deg
5253
m = self.assert_received_message_field_values("EFI_STATUS", {
5254
"throttle_out": 0,
5255
"health": 1,
5256
}, very_verbose=1)
5257
5258
if abs(baro_temperature - m.intake_manifold_temperature) > 1:
5259
raise NotAchievedException(
5260
"Bad intake manifold temperature (want=%f got=%f)" %
5261
(baro_temperature, m.intake_manifold_temperature))
5262
5263
self.arm_vehicle()
5264
5265
self.set_rc(3, 1300)
5266
5267
tstart = self.get_sim_time()
5268
while True:
5269
now = self.get_sim_time_cached()
5270
if now - tstart > 10:
5271
raise NotAchievedException("RPM1 and EFI_STATUS.rpm did not match")
5272
rpm_m = self.assert_receive_message("RPM", verbose=1)
5273
want_rpm = 1000
5274
if rpm_m.rpm1 < want_rpm:
5275
continue
5276
5277
m = self.assert_receive_message("EFI_STATUS", verbose=1)
5278
if abs(m.rpm - rpm_m.rpm1) > 100:
5279
continue
5280
5281
break
5282
5283
self.progress("now we're started, check a few more values")
5284
# note that megasquirt drver doesn't send throttle, so throttle_out is zero!
5285
m = self.assert_received_message_field_values("EFI_STATUS", {
5286
"health": 1,
5287
}, very_verbose=1)
5288
m = self.wait_message_field_values("EFI_STATUS", {
5289
"throttle_position": 31,
5290
"intake_manifold_temperature": 28,
5291
}, very_verbose=1, epsilon=2)
5292
5293
if check_fuel_flow:
5294
if abs(m.fuel_flow - 0.2) < 0.0001:
5295
raise NotAchievedException("Expected fuel flow")
5296
5297
self.set_rc(3, 1000)
5298
5299
# need to force disarm as the is_flying flag can trigger with the engine running
5300
self.disarm_vehicle(force=True)
5301
5302
def MegaSquirt(self):
5303
'''test MegaSquirt driver'''
5304
self.EFITest(
5305
1, "MegaSquirt", "megasquirt",
5306
check_fuel_flow=False,
5307
)
5308
5309
def Hirth(self):
5310
'''Test Hirth EFI'''
5311
self.EFITest(8, "Hirth", "hirth")
5312
5313
def AltitudeSlopeMaxHeight(self):
5314
'''Test rebuild altitude slope if above and climbing'''
5315
5316
# Test that ALT_SLOPE_MAXHGT correctly controls re-planning altitude slope
5317
# in the scenario that aircraft is above planned slope and slope is positive (climbing).
5318
#
5319
#
5320
# Behaviour with ALT_SLOPE_MAXHGT = 0 (no slope replanning)
5321
# (2).. __(4)
5322
# | \..__/
5323
# | __/
5324
# (3)
5325
#
5326
# Behaviour with ALT_SLOPE_MAXHGT = 5 (slope replanning when >5m error)
5327
# (2)........__(4)
5328
# | __/
5329
# | __/
5330
# (3)
5331
# Solid is plan, dots are actual flightpath.
5332
5333
self.load_mission('rapid-descent-then-climb.txt', strict=False)
5334
5335
self.set_current_waypoint(1)
5336
self.change_mode('AUTO')
5337
self.wait_ready_to_arm()
5338
self.arm_vehicle()
5339
5340
#
5341
# Initial run with ALT_SLOPE_MAXHGT = 5 (default).
5342
#
5343
self.set_parameter("ALT_SLOPE_MAXHGT", 5)
5344
5345
# Wait for waypoint commanding rapid descent, followed by climb.
5346
self.wait_current_waypoint(5, timeout=1200)
5347
5348
# Altitude should not descend significantly below the initial altitude
5349
init_altitude = self.get_altitude(relative=True, timeout=2)
5350
timeout = 600
5351
wpnum = 7
5352
tstart = self.get_sim_time()
5353
while True:
5354
if self.get_sim_time() - tstart > timeout:
5355
raise AutoTestTimeoutException("Did not get wanted current waypoint")
5356
5357
if (self.get_altitude(relative=True, timeout=2) - init_altitude) < -10:
5358
raise NotAchievedException("Descended >10m before reaching desired waypoint,\
5359
indicating slope was not replanned")
5360
5361
seq = self.mav.waypoint_current()
5362
self.progress("Waiting for wp=%u current=%u" % (wpnum, seq))
5363
if seq == wpnum:
5364
break
5365
5366
self.set_current_waypoint(2)
5367
5368
#
5369
# Second run with ALT_SLOPE_MAXHGT = 0 (no re-plan).
5370
#
5371
self.set_parameter("ALT_SLOPE_MAXHGT", 0)
5372
5373
# Wait for waypoint commanding rapid descent, followed by climb.
5374
self.wait_current_waypoint(5, timeout=1200)
5375
5376
# This time altitude should descend significantly below the initial altitude
5377
init_altitude = self.get_altitude(relative=True, timeout=2)
5378
timeout = 600
5379
wpnum = 7
5380
tstart = self.get_sim_time()
5381
while True:
5382
if self.get_sim_time() - tstart > timeout:
5383
raise AutoTestTimeoutException("Did not get wanted altitude")
5384
5385
seq = self.mav.waypoint_current()
5386
self.progress("Waiting for wp=%u current=%u" % (wpnum, seq))
5387
if seq == wpnum:
5388
raise NotAchievedException("Reached desired waypoint without first descending 10m,\
5389
indicating slope was replanned unexpectedly")
5390
5391
if (self.get_altitude(relative=True, timeout=2) - init_altitude) < -10:
5392
break
5393
5394
# Disarm
5395
self.wait_disarmed(timeout=600)
5396
5397
self.progress("Mission OK")
5398
5399
def MAV_CMD_NAV_LOITER_TURNS(self, target_system=1, target_component=1):
5400
'''test MAV_CMD_NAV_LOITER_TURNS mission item'''
5401
alt = 100
5402
seq = 0
5403
items = []
5404
tests = [
5405
(self.home_relative_loc_ne(50, -50), 100, 0.3),
5406
(self.home_relative_loc_ne(100, 50), 1005, 3),
5407
]
5408
# add a home position:
5409
items.append(self.mav.mav.mission_item_int_encode(
5410
target_system,
5411
target_component,
5412
seq, # seq
5413
mavutil.mavlink.MAV_FRAME_GLOBAL,
5414
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5415
0, # current
5416
0, # autocontinue
5417
0, # p1
5418
0, # p2
5419
0, # p3
5420
0, # p4
5421
0, # latitude
5422
0, # longitude
5423
0, # altitude
5424
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
5425
seq += 1
5426
5427
# add takeoff
5428
items.append(self.mav.mav.mission_item_int_encode(
5429
target_system,
5430
target_component,
5431
seq, # seq
5432
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5433
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
5434
0, # current
5435
0, # autocontinue
5436
0, # p1
5437
0, # p2
5438
0, # p3
5439
0, # p4
5440
0, # latitude
5441
0, # longitude
5442
alt, # altitude
5443
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
5444
seq += 1
5445
5446
# add circles
5447
for (loc, radius, turn) in tests:
5448
items.append(self.mav.mav.mission_item_int_encode(
5449
target_system,
5450
target_component,
5451
seq, # seq
5452
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5453
mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS,
5454
0, # current
5455
0, # autocontinue
5456
turn, # p1
5457
0, # p2
5458
radius, # p3
5459
0, # p4
5460
int(loc.lat*1e7), # latitude
5461
int(loc.lng*1e7), # longitude
5462
alt, # altitude
5463
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
5464
seq += 1
5465
5466
# add an RTL
5467
items.append(self.mav.mav.mission_item_int_encode(
5468
target_system,
5469
target_component,
5470
seq, # seq
5471
mavutil.mavlink.MAV_FRAME_GLOBAL,
5472
mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
5473
0, # current
5474
0, # autocontinue
5475
0, # p1
5476
0, # p2
5477
0, # p3
5478
0, # p4
5479
0, # latitude
5480
0, # longitude
5481
0, # altitude
5482
mavutil.mavlink.MAV_MISSION_TYPE_MISSION))
5483
seq += 1
5484
5485
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, items)
5486
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
5487
ofs = 2
5488
self.progress("Checking downloaded mission is as expected")
5489
for (loc, radius, turn) in tests:
5490
downloaded = downloaded_items[ofs]
5491
if radius > 255:
5492
# ArduPilot only stores % 10
5493
radius = radius - radius % 10
5494
if downloaded.param3 != radius:
5495
raise NotAchievedException(
5496
"Did not get expected radius for item %u; want=%f got=%f" %
5497
(ofs, radius, downloaded.param3))
5498
if turn > 0 and turn < 1:
5499
# ArduPilot stores fractions in 8 bits (*256) and unpacks it (/256)
5500
turn = int(turn*256) / 256.0
5501
if downloaded.param1 != turn:
5502
raise NotAchievedException(
5503
"Did not get expected turn for item %u; want=%f got=%f" %
5504
(ofs, turn, downloaded.param1))
5505
ofs += 1
5506
5507
self.change_mode('AUTO')
5508
self.wait_ready_to_arm()
5509
self.arm_vehicle()
5510
self.set_parameter("NAVL1_LIM_BANK", 50)
5511
5512
self.wait_current_waypoint(2)
5513
5514
for (loc, expected_radius, _) in tests:
5515
self.wait_circling_point_with_radius(
5516
loc,
5517
expected_radius,
5518
epsilon=20.0,
5519
timeout=240,
5520
)
5521
self.set_current_waypoint(self.current_waypoint()+1)
5522
5523
self.fly_home_land_and_disarm(timeout=180)
5524
5525
def MidAirDisarmDisallowed(self):
5526
'''Ensure mid-air disarm is not possible'''
5527
self.takeoff(50)
5528
disarmed = False
5529
try:
5530
self.disarm_vehicle()
5531
disarmed = True
5532
except ValueError as e:
5533
self.progress("Got %s" % repr(e))
5534
if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e):
5535
raise e
5536
if disarmed:
5537
raise NotAchievedException("Disarmed when we shouldn't have")
5538
# should still be able to force-disarm:
5539
self.disarm_vehicle(force=True)
5540
self.reboot_sitl()
5541
5542
def AerobaticsScripting(self):
5543
'''Fixed Wing Aerobatics'''
5544
applet_script = "Aerobatics/FixedWing/plane_aerobatics.lua"
5545
airshow = "Aerobatics/FixedWing/Schedules/AirShow.txt"
5546
trick72 = "trick72.txt"
5547
5548
model = "plane-3d"
5549
5550
self.customise_SITL_commandline(
5551
[],
5552
model=model,
5553
defaults_filepath="Tools/autotest/models/plane-3d.parm",
5554
wipe=True)
5555
5556
self.context_push()
5557
self.install_applet_script_context(applet_script)
5558
self.install_applet_script_context(airshow, install_name=trick72)
5559
self.context_collect('STATUSTEXT')
5560
self.reboot_sitl()
5561
5562
self.set_parameter("TRIK_ENABLE", 1)
5563
self.set_rc(7, 1000) # disable tricks
5564
5565
self.scripting_restart()
5566
self.wait_text("Enabled 3 aerobatic tricks", check_context=True)
5567
self.set_parameters({
5568
"TRIK1_ID": 72,
5569
"RC7_OPTION" : 300, # activation switch
5570
"RC9_OPTION" : 301, # selection switch
5571
"SIM_SPEEDUP": 5, # need to give some cycles to lua
5572
})
5573
5574
self.wait_ready_to_arm()
5575
self.change_mode("TAKEOFF")
5576
self.arm_vehicle()
5577
self.wait_altitude(30, 40, timeout=30, relative=True)
5578
self.change_mode("CRUISE")
5579
5580
self.set_rc(9, 1000) # select first trick
5581
self.delay_sim_time(1)
5582
self.set_rc(7, 1500) # show selected trick
5583
5584
self.wait_text("Trick 1 selected (SuperAirShow)", check_context=True)
5585
self.set_rc(7, 2000) # activate trick
5586
self.wait_text("Trick 1 started (SuperAirShow)", check_context=True)
5587
5588
highest_error = 0
5589
while True:
5590
m = self.mav.recv_match(type='NAMED_VALUE_FLOAT', timeout=2, blocking=True)
5591
if not m:
5592
break
5593
if m.name != 'PERR':
5594
continue
5595
highest_error = max(highest_error, m.value)
5596
if highest_error > 15:
5597
raise NotAchievedException("path error %.1f" % highest_error)
5598
5599
if highest_error == 0:
5600
raise NotAchievedException("path error not reported")
5601
self.progress("Finished trick, max error=%.1fm" % highest_error)
5602
self.disarm_vehicle(force=True)
5603
5604
messages = self.context_collection('STATUSTEXT')
5605
self.context_pop()
5606
self.reboot_sitl()
5607
5608
# check all messages to see if we got all tricks
5609
tricks = ["Loop", "HalfReverseCubanEight", "ScaleFigureEight", "Immelmann",
5610
"Split-S", "RollingCircle", "HumptyBump", "HalfCubanEight",
5611
"BarrelRoll", "CrossBoxTopHat", "TriangularLoop",
5612
"Finishing SuperAirShow!"]
5613
texts = [m.text for m in messages]
5614
for t in tricks:
5615
if t in texts:
5616
self.progress("Completed trick %s" % t)
5617
else:
5618
raise NotAchievedException("Missing trick %s" % t)
5619
5620
def UniversalAutoLandScript(self):
5621
'''Test UniversalAutoLandScript'''
5622
applet_script = "UniversalAutoLand.lua"
5623
self.customise_SITL_commandline(["--home", "-35.362938,149.165085,585,173"])
5624
5625
self.install_applet_script_context(applet_script)
5626
self.context_collect('STATUSTEXT')
5627
self.set_parameters({
5628
"SCR_ENABLE" : 1,
5629
"SCR_VM_I_COUNT" : 1000000,
5630
"RTL_AUTOLAND" : 2
5631
})
5632
self.reboot_sitl()
5633
self.wait_text("Loaded UniversalAutoLand.lua", check_context=True)
5634
self.set_parameters({
5635
"ALAND_ENABLE" : 1,
5636
"ALAND_WP_ALT" : 55,
5637
"ALAND_WP_DIST" : 400
5638
})
5639
self.wait_ready_to_arm()
5640
self.scripting_restart()
5641
self.wait_text("Scripting: restarted", check_context=True)
5642
5643
self.wait_ready_to_arm()
5644
self.arm_vehicle()
5645
self.change_mode("AUTO")
5646
self.wait_text("Captured initial takeoff direction", check_context=True)
5647
5648
self.wait_disarmed(120)
5649
self.progress("Check the landed heading matches takeoff")
5650
self.wait_heading(173, accuracy=5, timeout=1)
5651
loc = mavutil.location(-35.362938, 149.165085, 585, 173)
5652
if self.get_distance(loc, self.mav.location()) > 35:
5653
raise NotAchievedException("Did not land close to home")
5654
5655
def SDCardWPTest(self):
5656
'''test BRD_SD_MISSION support'''
5657
spiral_script = "mission_spiral.lua"
5658
5659
self.context_push()
5660
self.install_example_script(spiral_script)
5661
self.context_collect('STATUSTEXT')
5662
self.set_parameters({
5663
"BRD_SD_MISSION" : 64,
5664
"SCR_ENABLE" : 1,
5665
"SCR_VM_I_COUNT" : 1000000
5666
})
5667
5668
self.wait_ready_to_arm()
5669
self.reboot_sitl()
5670
5671
self.wait_text("Loaded spiral mission creator", check_context=True)
5672
self.set_parameters({
5673
"SCR_USER2": 19, # radius
5674
"SCR_USER3": -35.36322, # lat
5675
"SCR_USER4": 149.16525, # lon
5676
"SCR_USER5": 684.13, # alt
5677
})
5678
5679
count = (65536 // 15) - 1
5680
5681
self.progress("Creating spiral mission of size %s" % count)
5682
self.set_parameter("SCR_USER1", count)
5683
5684
self.wait_text("Created spiral of size %u" % count, check_context=True)
5685
5686
self.progress("Checking spiral before reboot")
5687
self.set_parameter("SCR_USER6", count)
5688
self.wait_text("Compared spiral of size %u OK" % count, check_context=True)
5689
self.set_parameter("SCR_USER6", 0)
5690
5691
self.wait_ready_to_arm()
5692
self.reboot_sitl()
5693
self.progress("Checking spiral after reboot")
5694
self.set_parameter("SCR_USER6", count)
5695
self.wait_text("Compared spiral of size %u OK" % count, check_context=True)
5696
5697
self.remove_installed_script(spiral_script)
5698
5699
self.context_pop()
5700
self.wait_ready_to_arm()
5701
self.reboot_sitl()
5702
5703
def MANUAL_CONTROL(self):
5704
'''test MANUAL_CONTROL mavlink message'''
5705
self.set_parameter("MAV_GCS_SYSID", self.mav.source_system)
5706
5707
self.progress("Takeoff")
5708
self.takeoff(alt=50)
5709
5710
self.change_mode('FBWA')
5711
5712
tstart = self.get_sim_time_cached()
5713
roll_input = -500
5714
want_roll_degrees = -12
5715
while True:
5716
if self.get_sim_time_cached() - tstart > 10:
5717
raise AutoTestTimeoutException("Did not reach roll")
5718
self.progress("Sending roll-left")
5719
self.mav.mav.manual_control_send(
5720
1, # target system
5721
32767, # x (pitch)
5722
roll_input, # y (roll)
5723
32767, # z (thrust)
5724
32767, # r (yaw)
5725
0) # button mask
5726
m = self.assert_receive_message('ATTITUDE', verbose=True)
5727
p = math.degrees(m.roll)
5728
self.progress("roll=%f want<=%f" % (p, want_roll_degrees))
5729
if p <= want_roll_degrees:
5730
break
5731
self.mav.mav.manual_control_send(
5732
1, # target system
5733
32767, # x (pitch)
5734
32767, # y (roll)
5735
32767, # z (thrust)
5736
32767, # r (yaw)
5737
0) # button mask
5738
self.fly_home_land_and_disarm()
5739
5740
def mission_home_point(self, target_system=1, target_component=1):
5741
'''just an empty-ish item-int to store home'''
5742
return self.mav.mav.mission_item_int_encode(
5743
target_system,
5744
target_component,
5745
0, # seq
5746
mavutil.mavlink.MAV_FRAME_GLOBAL,
5747
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5748
0, # current
5749
0, # autocontinue
5750
0, # p1
5751
0, # p2
5752
0, # p3
5753
0, # p4
5754
0, # latitude
5755
0, # longitude
5756
0, # altitude
5757
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
5758
5759
def mission_jump_tag(self, tag, target_system=1, target_component=1):
5760
'''create a jump tag mission item'''
5761
return self.mav.mav.mission_item_int_encode(
5762
target_system,
5763
target_component,
5764
0, # seq
5765
mavutil.mavlink.MAV_FRAME_GLOBAL,
5766
mavutil.mavlink.MAV_CMD_JUMP_TAG,
5767
0, # current
5768
0, # autocontinue
5769
tag, # p1
5770
0, # p2
5771
0, # p3
5772
0, # p4
5773
0, # latitude
5774
0, # longitude
5775
0, # altitude
5776
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
5777
5778
def mission_do_jump_tag(self, tag, target_system=1, target_component=1):
5779
'''create a jump tag mission item'''
5780
return self.mav.mav.mission_item_int_encode(
5781
target_system,
5782
target_component,
5783
0, # seq
5784
mavutil.mavlink.MAV_FRAME_GLOBAL,
5785
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
5786
0, # current
5787
0, # autocontinue
5788
tag, # p1
5789
0, # p2
5790
0, # p3
5791
0, # p4
5792
0, # latitude
5793
0, # longitude
5794
0, # altitude
5795
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
5796
5797
def mission_anonymous_waypoint(self, target_system=1, target_component=1):
5798
'''just a boring waypoint'''
5799
return self.mav.mav.mission_item_int_encode(
5800
target_system,
5801
target_component,
5802
0, # seq
5803
mavutil.mavlink.MAV_FRAME_GLOBAL,
5804
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5805
0, # current
5806
0, # autocontinue
5807
0, # p1
5808
0, # p2
5809
0, # p3
5810
0, # p4
5811
1, # latitude
5812
1, # longitude
5813
1, # altitude
5814
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
5815
5816
def renumber_mission_items(self, mission):
5817
count = 0
5818
for item in mission:
5819
item.seq = count
5820
count += 1
5821
5822
def MissionJumpTags_missing_jump_target(self, target_system=1, target_component=1):
5823
self.start_subtest("Check missing-jump-tag behaviour")
5824
jump_target = 2
5825
mission = [
5826
self.mission_home_point(),
5827
self.mission_anonymous_waypoint(),
5828
self.mission_anonymous_waypoint(),
5829
self.mission_jump_tag(jump_target),
5830
self.mission_anonymous_waypoint(),
5831
self.mission_anonymous_waypoint(),
5832
]
5833
self.renumber_mission_items(mission)
5834
self.check_mission_upload_download(mission)
5835
self.progress("Checking incorrect tag behaviour")
5836
self.run_cmd(
5837
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
5838
p1=jump_target + 1,
5839
want_result=mavutil.mavlink.MAV_RESULT_FAILED
5840
)
5841
self.progress("Checking correct tag behaviour")
5842
self.run_cmd(
5843
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
5844
p1=jump_target,
5845
)
5846
self.assert_current_waypoint(4)
5847
5848
def MissionJumpTags_do_jump_to_bad_tag(self, target_system=1, target_component=1):
5849
mission = [
5850
self.mission_home_point(),
5851
self.mission_anonymous_waypoint(),
5852
self.mission_do_jump_tag(17),
5853
self.mission_anonymous_waypoint(),
5854
]
5855
self.renumber_mission_items(mission)
5856
self.check_mission_upload_download(mission)
5857
self.change_mode('AUTO')
5858
self.arm_vehicle()
5859
self.set_current_waypoint(2, check_afterwards=False)
5860
self.assert_mode('RTL')
5861
self.disarm_vehicle()
5862
5863
def MissionJumpTags_jump_tag_at_end_of_mission(self, target_system=1, target_component=1):
5864
mission = [
5865
self.mission_home_point(),
5866
self.mission_anonymous_waypoint(),
5867
self.mission_jump_tag(17),
5868
]
5869
# Jumping to an end of a mission, either DO_JUMP or DO_JUMP_TAG will result in a failed attempt.
5870
# The failure is from mission::set_current_cmd() returning false if it can not find any NAV
5871
# commands on or after the index. Two scenarios:
5872
# 1) AUTO mission triggered: The the set_command will fail and it will cause an RTL event
5873
# (Harder to test, need vehicle to actually reach the waypoint)
5874
# 2) GCS/MAVLink: It will return MAV_RESULT_FAILED and there's on change to the mission. (Easy to test)
5875
self.renumber_mission_items(mission)
5876
self.check_mission_upload_download(mission)
5877
self.progress("Checking correct tag behaviour")
5878
self.change_mode('AUTO')
5879
self.arm_vehicle()
5880
self.run_cmd(
5881
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
5882
p1=17,
5883
want_result=mavutil.mavlink.MAV_RESULT_FAILED
5884
)
5885
self.disarm_vehicle()
5886
5887
def MissionJumpTags(self):
5888
'''test MAV_CMD_JUMP_TAG'''
5889
self.wait_ready_to_arm()
5890
self.MissionJumpTags_missing_jump_target()
5891
self.MissionJumpTags_do_jump_to_bad_tag()
5892
self.MissionJumpTags_jump_tag_at_end_of_mission()
5893
5894
def AltResetBadGPS(self):
5895
'''Tests the handling of poor GPS lock pre-arm alt resets'''
5896
self.set_parameters({
5897
"SIM_GPS1_GLTCH_Z": 0,
5898
"SIM_GPS1_ACC": 0.3,
5899
})
5900
self.wait_ready_to_arm()
5901
5902
m = self.assert_receive_message('GLOBAL_POSITION_INT')
5903
relalt = m.relative_alt*0.001
5904
if abs(relalt) > 3:
5905
raise NotAchievedException("Bad relative alt %.1f" % relalt)
5906
5907
self.progress("Setting low accuracy, glitching GPS")
5908
self.set_parameter("SIM_GPS1_ACC", 40)
5909
self.set_parameter("SIM_GPS1_GLTCH_Z", -47)
5910
5911
self.progress("Waiting 10s for height update")
5912
self.delay_sim_time(10)
5913
5914
self.wait_ready_to_arm()
5915
self.arm_vehicle()
5916
5917
m = self.assert_receive_message('GLOBAL_POSITION_INT')
5918
relalt = m.relative_alt*0.001
5919
if abs(relalt) > 3:
5920
raise NotAchievedException("Bad glitching relative alt %.1f" % relalt)
5921
5922
self.disarm_vehicle()
5923
# reboot to clear potentially bad state
5924
5925
def trigger_airspeed_cal(self):
5926
self.run_cmd(
5927
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
5928
p3=1,
5929
)
5930
5931
def AirspeedCal(self):
5932
'''test Airspeed calibration'''
5933
5934
self.start_subtest('1 airspeed sensor')
5935
self.context_push()
5936
self.context_collect('STATUSTEXT')
5937
self.trigger_airspeed_cal()
5938
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
5939
self.context_pop()
5940
5941
self.context_push()
5942
self.context_collect('STATUSTEXT')
5943
self.start_subtest('0 airspeed sensors')
5944
self.set_parameter('ARSPD_TYPE', 0)
5945
self.reboot_sitl()
5946
self.wait_statustext('No airspeed sensor', check_context=True)
5947
self.trigger_airspeed_cal()
5948
self.delay_sim_time(5)
5949
if self.statustext_in_collections('Airspeed 1 calibrated'):
5950
raise NotAchievedException("Did not disable airspeed sensor?!")
5951
self.context_pop()
5952
5953
self.start_subtest('2 airspeed sensors')
5954
self.set_parameter('ARSPD_TYPE', 100)
5955
self.set_parameter('ARSPD2_TYPE', 100)
5956
self.reboot_sitl()
5957
self.context_push()
5958
self.context_collect('STATUSTEXT')
5959
self.trigger_airspeed_cal()
5960
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
5961
self.wait_statustext('Airspeed 2 calibrated', check_context=True)
5962
self.context_pop()
5963
5964
self.reboot_sitl()
5965
5966
def RunMissionScript(self):
5967
'''Test run_mission.py script'''
5968
script = os.path.join('Tools', 'autotest', 'run_mission.py')
5969
self.stop_SITL()
5970
util.run_cmd([
5971
util.reltopdir(script),
5972
self.binary,
5973
'plane',
5974
self.generic_mission_filepath_for_filename("flaps.txt"),
5975
], checkfail=True)
5976
self.start_SITL()
5977
5978
def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
5979
'''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE'''
5980
target_alt = 750
5981
# this location is chosen to be fairly flat, but at a different terrain height to home
5982
higher_ground = mavutil.location(-35.35465024, 149.13974996, target_alt, 0)
5983
self.install_terrain_handlers_context()
5984
self.start_subtest("set home relative altitude")
5985
self.takeoff(30, relative=True)
5986
self.change_mode('GUIDED')
5987
5988
# remember home
5989
home_loc = self.home_position_as_mav_location()
5990
height_diff = target_alt - home_loc.alt
5991
5992
# fly to higher ground
5993
self.send_do_reposition(higher_ground, frame=mavutil.mavlink.MAV_FRAME_GLOBAL)
5994
self.wait_location(
5995
higher_ground,
5996
accuracy=200,
5997
timeout=600,
5998
height_accuracy=10,
5999
)
6000
6001
for alt in 50, 70:
6002
self.run_cmd_int(
6003
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
6004
p7=alt+height_diff,
6005
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
6006
)
6007
self.wait_altitude(target_alt+alt-1, target_alt+alt+1, timeout=30, minimum_duration=10, relative=False)
6008
6009
# test for #24535
6010
self.start_subtest("switch to loiter and resume guided maintains home relative altitude")
6011
self.change_mode('LOITER')
6012
self.delay_sim_time(1)
6013
self.change_mode('GUIDED')
6014
self.wait_altitude(
6015
height_diff+alt-3, # NOTE: reuse of alt from above loop!
6016
height_diff+alt+3,
6017
minimum_duration=10,
6018
timeout=30,
6019
relative=True,
6020
)
6021
# test that this works if switching between RELATIVE (HOME) and GLOBAL(AMSL)
6022
self.start_subtest("set global/AMSL altitude, switch to loiter and resume guided")
6023
alt = target_alt+30
6024
self.run_cmd_int(
6025
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
6026
p7=alt,
6027
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
6028
)
6029
self.wait_altitude(alt-3, alt+3, timeout=30, relative=False, minimum_duration=10)
6030
6031
# let it settle so LOITER captures a constant altitude
6032
self.delay_sim_time(10)
6033
6034
# now switch to LOITER then back to GUIDED
6035
self.change_mode('LOITER')
6036
self.delay_sim_time(5)
6037
self.change_mode('GUIDED')
6038
self.wait_altitude(
6039
alt-5, # NOTE: reuse of alt from above CHANGE_ALTITUDE
6040
alt+5,
6041
minimum_duration=10,
6042
timeout=30,
6043
relative=False,
6044
)
6045
6046
# test that this works if switching between RELATIVE (HOME) and terrain
6047
self.start_subtest("set terrain altitude, switch to loiter and resume guided")
6048
self.change_mode('GUIDED')
6049
alt = 100
6050
self.run_cmd_int(
6051
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
6052
p7=alt,
6053
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
6054
)
6055
self.wait_altitude(
6056
alt-10, # NOTE: reuse of alt from abovE
6057
alt+10, # use a 10m buffer as the plane needs to go up and down a bit to maintain terrain distance
6058
minimum_duration=10,
6059
timeout=30,
6060
relative=False,
6061
altitude_source="TERRAIN_REPORT.current_height"
6062
)
6063
6064
alt = 150
6065
self.run_cmd_int(
6066
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
6067
p7=alt,
6068
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
6069
)
6070
self.wait_altitude(
6071
alt-10, # NOTE: reuse of alt from abovE
6072
alt+10, # use a 10m buffer as the plane needs to go up and down a bit to maintain terrain distance
6073
minimum_duration=10,
6074
timeout=30,
6075
relative=False,
6076
altitude_source="TERRAIN_REPORT.current_height"
6077
)
6078
self.delay_sim_time(30)
6079
6080
self.change_mode('LOITER')
6081
self.delay_sim_time(1)
6082
self.change_mode('GUIDED')
6083
self.wait_altitude(
6084
alt-5, # NOTE: reuse of alt from abovE
6085
alt+5, # use a 5m buffer as the plane needs to go up and down a bit to maintain terrain distance
6086
minimum_duration=10,
6087
timeout=30,
6088
relative=False,
6089
altitude_source="TERRAIN_REPORT.current_height"
6090
)
6091
6092
self.start_subtest("test flyto with relative alt")
6093
dest = copy.copy(higher_ground)
6094
dest.alt = higher_ground.alt + 100 - home_loc.alt
6095
self.progress("dest.alt=%.1f" % dest.alt)
6096
self.send_do_reposition(dest, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT)
6097
self.wait_location(
6098
dest,
6099
accuracy=200,
6100
timeout=600,
6101
height_accuracy=10,
6102
)
6103
self.wait_altitude(
6104
dest.alt-5,
6105
dest.alt+5,
6106
minimum_duration=10,
6107
timeout=30,
6108
relative=True
6109
)
6110
6111
self.start_subtest("test flyto with absolute alt")
6112
dest = copy.copy(higher_ground)
6113
dest.alt = higher_ground.alt + 60
6114
self.progress("dest.alt=%.1f" % dest.alt)
6115
self.send_do_reposition(dest, frame=mavutil.mavlink.MAV_FRAME_GLOBAL)
6116
self.wait_location(
6117
dest,
6118
accuracy=200,
6119
timeout=600,
6120
height_accuracy=10,
6121
)
6122
self.wait_altitude(
6123
dest.alt-5,
6124
dest.alt+5,
6125
minimum_duration=10,
6126
timeout=30,
6127
relative=False
6128
)
6129
6130
self.start_subtest("test flyto with terrain alt")
6131
dest = copy.copy(higher_ground)
6132
dest.alt = 130
6133
self.progress("dest.alt=%.1f" % dest.alt)
6134
self.send_do_reposition(dest, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
6135
self.wait_location(
6136
dest,
6137
accuracy=200,
6138
timeout=600,
6139
height_accuracy=10,
6140
)
6141
self.wait_altitude(
6142
dest.alt-10,
6143
dest.alt+10,
6144
minimum_duration=10,
6145
timeout=30,
6146
relative=False,
6147
altitude_source="TERRAIN_REPORT.current_height"
6148
)
6149
6150
self.delay_sim_time(5)
6151
self.fly_home_land_and_disarm()
6152
6153
def _MAV_CMD_PREFLIGHT_CALIBRATION(self, command):
6154
self.context_push()
6155
self.start_subtest("Denied when armed")
6156
self.wait_ready_to_arm()
6157
self.arm_vehicle()
6158
command(
6159
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6160
p1=1,
6161
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
6162
)
6163
self.disarm_vehicle()
6164
6165
self.context_collect('STATUSTEXT')
6166
6167
self.start_subtest("gyro cal")
6168
command(
6169
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6170
p1=1,
6171
)
6172
6173
self.start_subtest("baro cal")
6174
command(
6175
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6176
p3=1,
6177
)
6178
self.wait_statustext('Barometer calibration complete', check_context=True)
6179
6180
# accelcal skipped here, it is checked elsewhere
6181
6182
self.start_subtest("ins trim")
6183
command(
6184
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6185
p5=2,
6186
)
6187
6188
# enforced delay between cals:
6189
self.delay_sim_time(5)
6190
6191
self.start_subtest("simple accel cal")
6192
command(
6193
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6194
p5=4,
6195
)
6196
# simple gyro cal makes the GPS units go unhealthy as they are
6197
# not maintaining their update rate (gyro cal is synchronous
6198
# in the main loop). Usually ~30 seconds to recover...
6199
self.wait_gps_sys_status_not_present_or_enabled_and_healthy(timeout=60)
6200
6201
self.start_subtest("force save accels")
6202
command(
6203
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6204
p5=76,
6205
)
6206
6207
self.start_subtest("force save compasses")
6208
command(
6209
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
6210
p2=76,
6211
)
6212
6213
self.context_pop()
6214
6215
def MAV_CMD_PREFLIGHT_CALIBRATION(self):
6216
'''test MAV_CMD_PREFLIGHT_CALIBRATION mavlink handling'''
6217
self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd)
6218
self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd_int)
6219
6220
def MAV_CMD_DO_INVERTED_FLIGHT(self):
6221
'''fly upside-down mission item'''
6222
alt = 30
6223
wps = self.create_simple_relhome_mission([
6224
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, alt),
6225
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 400, 0, alt),
6226
self.create_MISSION_ITEM_INT(
6227
mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT,
6228
p1=1,
6229
),
6230
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, alt),
6231
self.create_MISSION_ITEM_INT(
6232
mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT,
6233
p1=0,
6234
),
6235
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1200, 0, alt),
6236
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
6237
])
6238
self.check_mission_upload_download(wps)
6239
6240
self.change_mode('AUTO')
6241
self.wait_ready_to_arm()
6242
6243
self.arm_vehicle()
6244
6245
self.wait_current_waypoint(2) # upright flight
6246
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
6247
"nav_roll": 0,
6248
"nav_pitch": 0,
6249
}, epsilon=10)
6250
6251
def check_altitude(mav, m):
6252
m_type = m.get_type()
6253
if m_type != 'GLOBAL_POSITION_INT':
6254
return
6255
if abs(30 - m.relative_alt * 0.001) > 15:
6256
raise NotAchievedException("Bad altitude while flying inverted")
6257
6258
self.context_push()
6259
self.install_message_hook_context(check_altitude)
6260
6261
self.wait_current_waypoint(4) # inverted flight
6262
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
6263
"nav_roll": 180,
6264
"nav_pitch": 9,
6265
}, epsilon=10,)
6266
6267
self.wait_current_waypoint(6) # upright flight
6268
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
6269
"nav_roll": 0,
6270
"nav_pitch": 0,
6271
}, epsilon=10)
6272
6273
self.context_pop() # remove the check_altitude call
6274
6275
self.wait_current_waypoint(7)
6276
6277
self.fly_home_land_and_disarm()
6278
6279
def MAV_CMD_DO_AUTOTUNE_ENABLE(self):
6280
'''test enabling autotune via mavlink'''
6281
self.context_collect('STATUSTEXT')
6282
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=1)
6283
self.wait_statustext('Started autotune', check_context=True)
6284
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=0)
6285
self.wait_statustext('Stopped autotune', check_context=True)
6286
6287
def DO_PARACHUTE(self):
6288
'''test triggering parachute via mavlink'''
6289
self.set_parameters({
6290
"CHUTE_ENABLED": 1,
6291
"CHUTE_TYPE": 10,
6292
"SERVO9_FUNCTION": 27,
6293
"SIM_PARA_ENABLE": 1,
6294
"SIM_PARA_PIN": 9,
6295
"FS_LONG_ACTN": 3,
6296
})
6297
for command in self.run_cmd, self.run_cmd_int:
6298
self.wait_servo_channel_value(9, 1100)
6299
self.wait_ready_to_arm()
6300
self.arm_vehicle()
6301
command(
6302
mavutil.mavlink.MAV_CMD_DO_PARACHUTE,
6303
p1=mavutil.mavlink.PARACHUTE_RELEASE,
6304
)
6305
self.wait_servo_channel_value(9, 1300)
6306
self.disarm_vehicle()
6307
self.reboot_sitl()
6308
6309
def _MAV_CMD_DO_GO_AROUND(self, command):
6310
self.load_mission("mission.txt")
6311
self.set_parameter("RTL_AUTOLAND", 3)
6312
self.change_mode('AUTO')
6313
self.wait_ready_to_arm()
6314
self.arm_vehicle()
6315
self.wait_current_waypoint(6)
6316
command(mavutil.mavlink.MAV_CMD_DO_GO_AROUND, p1=150)
6317
self.wait_current_waypoint(5)
6318
self.wait_altitude(135, 165, relative=True)
6319
self.wait_disarmed(timeout=300)
6320
6321
def MAV_CMD_DO_GO_AROUND(self):
6322
'''test MAV_CMD_DO_GO_AROUND as a mavlink command'''
6323
self._MAV_CMD_DO_GO_AROUND(self.run_cmd)
6324
self._MAV_CMD_DO_GO_AROUND(self.run_cmd_int)
6325
6326
def _MAV_CMD_DO_FLIGHTTERMINATION(self, command):
6327
self.set_parameters({
6328
"AFS_ENABLE": 1,
6329
"MAV_GCS_SYSID": self.mav.source_system,
6330
"AFS_TERM_ACTION": 42,
6331
})
6332
self.wait_ready_to_arm()
6333
self.arm_vehicle()
6334
self.context_collect('STATUSTEXT')
6335
command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1)
6336
self.wait_disarmed()
6337
self.wait_text('Terminating due to GCS request', check_context=True)
6338
self.reboot_sitl()
6339
6340
def MAV_CMD_DO_FLIGHTTERMINATION(self):
6341
'''test MAV_CMD_DO_FLIGHTTERMINATION works on Plane'''
6342
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd)
6343
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int)
6344
6345
def MAV_CMD_DO_LAND_START(self):
6346
'''test MAV_CMD_DO_LAND_START as mavlink command'''
6347
self.set_parameters({
6348
"RTL_AUTOLAND": 3,
6349
})
6350
self.upload_simple_relhome_mission([
6351
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
6352
(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30),
6353
self.create_MISSION_ITEM_INT(
6354
mavutil.mavlink.MAV_CMD_DO_LAND_START,
6355
),
6356
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
6357
])
6358
6359
self.change_mode('AUTO')
6360
self.wait_ready_to_arm()
6361
6362
self.arm_vehicle()
6363
6364
self.start_subtest("DO_LAND_START as COMMAND_LONG")
6365
self.wait_current_waypoint(2)
6366
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START)
6367
self.wait_current_waypoint(4)
6368
6369
self.start_subtest("DO_LAND_START as COMMAND_INT")
6370
self.set_current_waypoint(2)
6371
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_LAND_START)
6372
self.wait_current_waypoint(4)
6373
6374
self.fly_home_land_and_disarm()
6375
6376
def MAV_CMD_NAV_ALTITUDE_WAIT(self):
6377
'''test MAV_CMD_NAV_ALTITUDE_WAIT mission item, wiggling only'''
6378
6379
# Load a single waypoint
6380
self.upload_simple_relhome_mission([
6381
self.create_MISSION_ITEM_INT(
6382
mavutil.mavlink.MAV_CMD_NAV_ALTITUDE_WAIT,
6383
p1=1000, # 1000m alt threshold, this should not trigger
6384
p2=10, # 10m/s descent rate, this should not trigger
6385
p3=10 # servo wiggle every 10 seconds
6386
)
6387
])
6388
6389
# Set initial conditions for servo wiggle testing
6390
servo_wiggled = {1: False, 2: False, 4: False}
6391
6392
def look_for_wiggle(mav, m):
6393
if m.get_type() == 'SERVO_OUTPUT_RAW':
6394
# Throttle must be zero
6395
if m.servo3_raw != 1000:
6396
raise NotAchievedException(
6397
"Throttle must be 0 in altitude wait, got %f" % m.servo3_raw)
6398
6399
# Check if all servos wiggle
6400
if m.servo1_raw != 1500:
6401
servo_wiggled[1] = True
6402
if m.servo2_raw != 1500:
6403
servo_wiggled[2] = True
6404
if m.servo4_raw != 1500:
6405
servo_wiggled[4] = True
6406
6407
# Start mission
6408
self.change_mode('AUTO')
6409
self.wait_ready_to_arm()
6410
self.arm_vehicle()
6411
6412
# Check outputs
6413
self.context_push()
6414
self.install_message_hook_context(look_for_wiggle)
6415
6416
# Wait for a bit to let message hook sample
6417
self.delay_sim_time(60)
6418
6419
self.context_pop()
6420
6421
# If the mission item completes as there is no other waypoints we will end up in RTL
6422
if not self.mode_is('AUTO'):
6423
raise NotAchievedException("Must still be in AUTO")
6424
6425
# Raise error if not all servos have wiggled
6426
if not all(servo_wiggled.values()):
6427
raise NotAchievedException("Not all servos have moved within the test frame")
6428
6429
self.disarm_vehicle()
6430
6431
def InteractTest(self):
6432
'''just takeoff'''
6433
6434
if self.mavproxy is None:
6435
raise NotAchievedException("Must be started with --map")
6436
6437
self.start_flying_simple_relhome_mission([
6438
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
6439
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
6440
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 800, 0),
6441
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 400, 0),
6442
])
6443
6444
self.wait_current_waypoint(4)
6445
6446
self.set_parameter('SIM_SPEEDUP', 1)
6447
6448
self.mavproxy.interact()
6449
6450
def MAV_CMD_MISSION_START(self):
6451
'''test MAV_CMD_MISSION_START starts AUTO'''
6452
self.upload_simple_relhome_mission([
6453
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
6454
])
6455
for run_cmd in self.run_cmd, self.run_cmd_int:
6456
self.change_mode('LOITER')
6457
run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
6458
self.wait_mode('AUTO')
6459
6460
def MAV_CMD_NAV_LOITER_UNLIM(self):
6461
'''test receiving MAV_CMD_NAV_LOITER_UNLIM from GCS'''
6462
self.takeoff(10)
6463
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM)
6464
self.wait_mode('LOITER')
6465
self.change_mode('GUIDED')
6466
self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM)
6467
self.wait_mode('LOITER')
6468
self.fly_home_land_and_disarm()
6469
6470
def MAV_CMD_NAV_RETURN_TO_LAUNCH(self):
6471
'''test receiving MAV_CMD_NAV_RETURN_TO_LAUNCH from GCS'''
6472
self.set_parameter('RTL_AUTOLAND', 1)
6473
self.start_flying_simple_relhome_mission([
6474
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
6475
(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30),
6476
self.create_MISSION_ITEM_INT(
6477
mavutil.mavlink.MAV_CMD_DO_LAND_START,
6478
),
6479
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
6480
])
6481
6482
for i in self.run_cmd, self.run_cmd_int:
6483
self.wait_current_waypoint(2)
6484
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)
6485
self.wait_current_waypoint(4)
6486
self.set_current_waypoint(2)
6487
self.fly_home_land_and_disarm()
6488
6489
def location_from_ADSB_VEHICLE(self, m):
6490
'''return a mavutil.location extracted from an ADSB_VEHICLE mavlink
6491
message'''
6492
if m.altitude_type != mavutil.mavlink.ADSB_ALTITUDE_TYPE_GEOMETRIC:
6493
raise ValueError("Expected geometric alt")
6494
return mavutil.location(
6495
m.lat*1e-7,
6496
m.lon*1e-7,
6497
m.altitude/1000.0585, # mm -> m
6498
m.heading * 0.01 # centidegrees -> degrees
6499
)
6500
6501
def SagetechMXS(self):
6502
'''test Sagetech MXS ADSB device driver'''
6503
sim_name = "sagetech_mxs"
6504
self.set_parameters({
6505
"SERIAL5_PROTOCOL": 35,
6506
"ADSB_TYPE": 4, # Sagetech-MXS
6507
"SIM_ADSB_TYPES": 8, # Sagetech-MXS
6508
"SIM_ADSB_COUNT": 5,
6509
})
6510
self.customise_SITL_commandline(["--serial5=sim:%s" % sim_name])
6511
m = self.assert_receive_message("ADSB_VEHICLE")
6512
adsb_vehicle_loc = self.location_from_ADSB_VEHICLE(m)
6513
self.progress("ADSB Vehicle at loc %s" % str(adsb_vehicle_loc))
6514
home = self.home_position_as_mav_location()
6515
self.assert_distance(home, adsb_vehicle_loc, 0, 10000)
6516
6517
def MinThrottle(self):
6518
'''Make sure min throttle does not apply in manual mode and does in FBWA'''
6519
6520
servo_min = self.get_parameter("RC3_MIN")
6521
servo_max = self.get_parameter("RC3_MAX")
6522
min_throttle = 10
6523
servo_min_throttle = servo_min + (servo_max - servo_min) * (min_throttle / 100)
6524
6525
# Set min throttle
6526
self.set_parameter('THR_MIN', min_throttle)
6527
6528
# Should be 0 throttle while disarmed
6529
self.change_mode("MANUAL")
6530
self.drain_mav() # make sure we have the latest data before checking throttle output
6531
self.assert_servo_channel_value(3, servo_min)
6532
6533
# Arm and check throttle is still 0 in manual
6534
self.wait_ready_to_arm()
6535
self.arm_vehicle()
6536
self.drain_mav()
6537
self.assert_servo_channel_value(3, servo_min)
6538
6539
# FBWA should apply throttle min
6540
self.change_mode("FBWA")
6541
self.drain_mav()
6542
self.assert_servo_channel_value(3, servo_min_throttle)
6543
6544
# But not when disarmed
6545
self.disarm_vehicle()
6546
self.drain_mav()
6547
self.assert_servo_channel_value(3, servo_min)
6548
6549
def ClimbThrottleSaturation(self):
6550
'''check what happens when throttle is saturated in GUIDED'''
6551
self.set_parameters({
6552
"TECS_CLMB_MAX": 30,
6553
"TKOFF_ALT": 1000,
6554
})
6555
6556
self.change_mode("TAKEOFF")
6557
self.wait_ready_to_arm()
6558
self.arm_vehicle()
6559
self.wait_message_field_values('VFR_HUD', {
6560
"throttle": 100,
6561
}, minimum_duration=30, timeout=90)
6562
self.disarm_vehicle(force=True)
6563
self.reboot_sitl()
6564
6565
def GuidedAttitudeNoGPS(self):
6566
'''test that guided-attitude still works with no GPS'''
6567
self.takeoff(50)
6568
self.change_mode('GUIDED')
6569
self.context_push()
6570
self.set_parameter('SIM_GPS1_ENABLE', 0)
6571
self.delay_sim_time(30)
6572
self.set_attitude_target()
6573
self.context_pop()
6574
self.fly_home_land_and_disarm()
6575
6576
def ScriptStats(self):
6577
'''test script stats logging'''
6578
self.context_push()
6579
self.set_parameters({
6580
'SCR_ENABLE': 1,
6581
'SCR_DEBUG_OPTS': 8, # runtime memory usage and time
6582
})
6583
self.install_test_scripts_context([
6584
"math.lua",
6585
"strings.lua",
6586
])
6587
self.install_example_script_context('simple_loop.lua')
6588
self.context_collect('STATUSTEXT')
6589
6590
self.reboot_sitl()
6591
6592
self.wait_statustext('hello, world')
6593
delay = 20
6594
self.delay_sim_time(delay, reason='gather some stats')
6595
self.wait_statustext("math.lua exceeded time limit", check_context=True, timeout=0)
6596
6597
dfreader = self.dfreader_for_current_onboard_log()
6598
seen_hello_world = False
6599
# runtime = None
6600
while True:
6601
m = dfreader.recv_match(type=['SCR'])
6602
if m is None:
6603
break
6604
if m.Name == "simple_loop.lua":
6605
seen_hello_world = True
6606
# if m.Name == "math.lua":
6607
# runtime = m.Runtime
6608
6609
if not seen_hello_world:
6610
raise NotAchievedException("Did not see simple_loop.lua script")
6611
6612
# self.progress(f"math took {runtime} seconds to run over {delay} seconds")
6613
# if runtime == 0:
6614
# raise NotAchievedException("Expected non-zero runtime for math")
6615
6616
self.context_pop()
6617
self.reboot_sitl()
6618
6619
def GPSPreArms(self):
6620
'''ensure GPS prearm checks work'''
6621
self.wait_ready_to_arm()
6622
self.start_subtest('DroneCAN sanity checks')
6623
self.set_parameter('GPS1_TYPE', 9)
6624
self.set_parameter('GPS2_TYPE', 9)
6625
self.set_parameter('GPS1_CAN_OVRIDE', 130)
6626
self.set_parameter('GPS2_CAN_OVRIDE', 130)
6627
self.assert_prearm_failure(
6628
"set for multiple GPS",
6629
other_prearm_failures_fatal=False,
6630
)
6631
6632
def SetHomeAltChange(self):
6633
'''check modes retain altitude when home alt changed'''
6634
for mode in 'FBWB', 'CRUISE', 'LOITER':
6635
self.set_rc(3, 1000)
6636
self.wait_ready_to_arm()
6637
home = self.home_position_as_mav_location()
6638
target_alt = 20
6639
self.takeoff(target_alt, mode="TAKEOFF")
6640
self.delay_sim_time(20) # Give some time to altitude to stabilize.
6641
self.set_rc(3, 1500)
6642
self.change_mode(mode)
6643
higher_home = copy.copy(home)
6644
higher_home.alt += 40
6645
self.set_home(higher_home)
6646
self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=10, timeout=12)
6647
self.disarm_vehicle(force=True)
6648
self.reboot_sitl()
6649
6650
def SetHomeAltChange2(self):
6651
'''ensure TECS operates predictably as home altitude changes continuously'''
6652
'''
6653
This can happen when performing a ship landing, where the home
6654
coordinates are continuously set by the ship GNSS RX.
6655
'''
6656
self.set_parameter('TRIM_THROTTLE', 70)
6657
self.wait_ready_to_arm()
6658
home = self.home_position_as_mav_location()
6659
target_alt = 20
6660
self.takeoff(target_alt, mode="TAKEOFF")
6661
self.change_mode("LOITER")
6662
self.delay_sim_time(20) # Let the plane settle.
6663
6664
tstart = self.get_sim_time()
6665
test_time = 10 # Run the test for 10s.
6666
pub_freq = 10
6667
for i in range(test_time*pub_freq):
6668
tnow = self.get_sim_time()
6669
higher_home = copy.copy(home)
6670
# Produce 1Hz sine waves in home altitude change.
6671
higher_home.alt += 40*math.sin((tnow-tstart)*(2*math.pi))
6672
self.set_home(higher_home)
6673
if tnow-tstart > test_time:
6674
break
6675
self.delay_sim_time(1.0/pub_freq)
6676
6677
# Test if the altitude is still within bounds.
6678
self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=1, timeout=2)
6679
self.disarm_vehicle(force=True)
6680
self.reboot_sitl()
6681
6682
def SetHomeAltChange3(self):
6683
'''same as SetHomeAltChange, but the home alt change occurs during TECS operation'''
6684
self.wait_ready_to_arm()
6685
home = self.home_position_as_mav_location()
6686
target_alt = 20
6687
self.takeoff(target_alt, mode="TAKEOFF")
6688
self.change_mode("LOITER")
6689
self.delay_sim_time(20) # Let the plane settle.
6690
6691
higher_home = copy.copy(home)
6692
higher_home.alt += 40
6693
self.set_home(higher_home)
6694
self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=10, timeout=10.1)
6695
6696
self.disarm_vehicle(force=True)
6697
self.reboot_sitl()
6698
6699
def ForceArm(self):
6700
'''check force-arming functionality'''
6701
self.set_parameter("SIM_GPS1_ENABLE", 0)
6702
# 21196 is the mavlink standard, 2989 is legacy
6703
for magic_value in 21196, 2989:
6704
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK,
6705
present=True,
6706
enabled=True,
6707
healthy=False,
6708
)
6709
self.run_cmd(
6710
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
6711
p1=1, # ARM
6712
p2=0,
6713
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
6714
)
6715
self.run_cmd(
6716
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
6717
p1=1, # ARM
6718
p2=magic_value,
6719
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
6720
)
6721
self.disarm_vehicle()
6722
6723
def CompassLearnInFlight(self):
6724
'''check we can learn compass offsets in flight'''
6725
self.context_push()
6726
self.set_parameters({
6727
"COMPASS_OFS_X": 1100,
6728
})
6729
self.assert_prearm_failure("Check mag field", other_prearm_failures_fatal=False)
6730
self.context_pop()
6731
self.wait_ready_to_arm()
6732
self.takeoff(30, mode='TAKEOFF')
6733
self.assert_parameter_value("COMPASS_OFS_X", 20, epsilon=30)
6734
# fly straight and level for a bit to let GSF converge for accurate learning
6735
self.change_mode("FBWB") # not "CRUISE" to avoid heading track with bad compass
6736
self.wait_distance(200, accuracy=20)
6737
old_compass_ofs_x = self.get_parameter('COMPASS_OFS_X')
6738
self.set_parameters({
6739
"COMPASS_OFS_X": 1100,
6740
})
6741
self.send_set_parameter("COMPASS_LEARN", 3) # 3 is in-flight learning
6742
self.wait_parameter_value("COMPASS_LEARN", 0)
6743
self.assert_parameter_value("COMPASS_OFS_X", old_compass_ofs_x, epsilon=30)
6744
self.fly_home_land_and_disarm()
6745
self.reboot_sitl()
6746
self.assert_parameter_value("COMPASS_OFS_X", old_compass_ofs_x, epsilon=30)
6747
6748
def _MAV_CMD_EXTERNAL_WIND_ESTIMATE(self, command):
6749
self.reboot_sitl()
6750
6751
def cmp_with_variance(a, b, p):
6752
return abs(a - b) < p
6753
6754
def check_eq(speed, direction, ret_dir, timeout=1):
6755
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=speed, p3=direction)
6756
6757
tstart = self.get_sim_time()
6758
while True:
6759
if self.get_sim_time_cached() - tstart > timeout:
6760
raise NotAchievedException(
6761
f"Failed to set wind speed or/and direction: speed != {speed} or direction != {direction}")
6762
6763
m = self.assert_receive_message("WIND")
6764
if cmp_with_variance(m.speed, speed, 0.5) and cmp_with_variance(m.direction, ret_dir, 5):
6765
return True
6766
6767
check_eq(1, 45, 45)
6768
check_eq(2, 90, 90)
6769
check_eq(3, 120, 120)
6770
check_eq(4, 180, -180)
6771
check_eq(5, 240, -120)
6772
check_eq(6, 320, -40)
6773
check_eq(7, 360, 0)
6774
6775
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
6776
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
6777
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=-2, p3=-90, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
6778
command(mavutil.mavlink.MAV_CMD_EXTERNAL_WIND_ESTIMATE, p1=2, p3=370, want_result=mavutil.mavlink.MAV_RESULT_DENIED)
6779
6780
def FenceDoubleBreach(self):
6781
'''test breaching the fence twice'''
6782
self.wait_ready_to_arm()
6783
6784
fence_centre_ne = (0, -500)
6785
6786
fence_centre = self.mav.location()
6787
fence_centre = self.offset_location_ne(fence_centre, fence_centre_ne[0], fence_centre_ne[1])
6788
6789
self.set_parameters({
6790
"RTL_AUTOLAND": 2,
6791
})
6792
6793
alt = 50
6794
self.upload_simple_relhome_mission([
6795
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, alt),
6796
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, fence_centre_ne[0], fence_centre_ne[1], alt),
6797
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -750, alt),
6798
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, alt),
6799
self.create_MISSION_ITEM_INT(
6800
mavutil.mavlink.MAV_CMD_DO_LAND_START,
6801
),
6802
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 800, alt),
6803
])
6804
6805
self.upload_fences_from_locations([
6806
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
6807
self.offset_location_ne(fence_centre, -200, -200), # bl
6808
self.offset_location_ne(fence_centre, -200, 200), # br
6809
self.offset_location_ne(fence_centre, 200, 200), # tr
6810
self.offset_location_ne(fence_centre, 200, -200), # tl,
6811
]),
6812
])
6813
6814
self.do_fence_enable()
6815
6816
self.takeoff(mode='FBWA')
6817
self.set_rc(3, 1500)
6818
6819
self.change_mode('AUTO')
6820
6821
self.context_collect('STATUSTEXT')
6822
6823
self.wait_statustext('Polygon fence breached', timeout=300)
6824
self.wait_current_waypoint(6)
6825
self.wait_distance_to_location(fence_centre, 350, 20000)
6826
6827
self.set_current_waypoint(2)
6828
6829
self.wait_statustext('Polygon fence breached', timeout=300)
6830
self.wait_current_waypoint(6, timeout=5)
6831
self.fly_home_land_and_disarm()
6832
6833
def MAV_CMD_EXTERNAL_WIND_ESTIMATE(self):
6834
'''test MAV_CMD_EXTERNAL_WIND_ESTIMATE as a mavlink command'''
6835
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd)
6836
self._MAV_CMD_EXTERNAL_WIND_ESTIMATE(self.run_cmd_int)
6837
6838
def LoggedNamedValueFloat(self):
6839
'''ensure that sent named value floats are logged'''
6840
self.context_push()
6841
self.install_example_script_context('simple_loop.lua')
6842
self.set_parameters({
6843
'SCR_ENABLE': 1,
6844
})
6845
self.reboot_sitl()
6846
self.wait_ready_to_arm()
6847
self.wait_statustext('hello, world')
6848
m = self.assert_received_message_field_values('NAMED_VALUE_FLOAT', {
6849
"name": "Lua Float",
6850
})
6851
dfreader = self.dfreader_for_current_onboard_log()
6852
self.context_pop()
6853
6854
m = dfreader.recv_match(type='NVF')
6855
if m is None:
6856
raise NotAchievedException("Did not find NVF message")
6857
self.progress(f"Received NVF with value {m.Value}")
6858
6859
def LoggedNamedValueString(self):
6860
'''ensure that sent named value strings are logged'''
6861
self.context_push()
6862
self.install_example_script_context('simple_named_string.lua')
6863
self.set_parameters({
6864
'SCR_ENABLE': 1,
6865
})
6866
self.reboot_sitl()
6867
self.wait_ready_to_arm()
6868
m = self.assert_received_message_field_values('NAMED_VALUE_STRING', {
6869
"name": "Lua String",
6870
"value": "Lua String Value",
6871
})
6872
dfreader = self.dfreader_for_current_onboard_log()
6873
self.context_pop()
6874
6875
m = dfreader.recv_match(type='NVS')
6876
if m is None:
6877
raise NotAchievedException("Did not find NVS message")
6878
self.progress(f"Received NVS with value {m.Value}")
6879
if m.Name != 'Lua String':
6880
raise NotAchievedException("Unexpected name in NVS")
6881
if m.Value != 'Lua String Value':
6882
raise NotAchievedException("Unexpected value in NVS")
6883
6884
def GliderPullup(self):
6885
'''test pullup of glider after ALTITUDE_WAIT'''
6886
self.start_subtest("test glider pullup")
6887
6888
self.customise_SITL_commandline(
6889
[],
6890
model="glider",
6891
defaults_filepath="Tools/autotest/default_params/glider.parm",
6892
wipe=True)
6893
6894
self.set_parameter('LOG_DISARMED', 1)
6895
6896
self.set_parameters({
6897
"PUP_ENABLE": 1,
6898
"SERVO6_FUNCTION": 0, # balloon lift
6899
"SERVO10_FUNCTION": 156, # lift release
6900
"EK3_IMU_MASK": 1, # lane switches just make log harder to read
6901
"AHRS_OPTIONS": 4, # don't disable airspeed based on EKF checks
6902
"ARSPD_OPTIONS": 0, # don't disable airspeed
6903
"ARSPD_WIND_GATE": 0,
6904
})
6905
6906
self.set_servo(6, 1000)
6907
6908
self.load_mission("glider-pullup-mission.txt")
6909
self.change_mode("AUTO")
6910
self.wait_ready_to_arm()
6911
self.arm_vehicle()
6912
self.context_collect('STATUSTEXT')
6913
6914
self.progress("Start balloon lift")
6915
self.set_servo(6, 2000)
6916
6917
self.wait_text("Reached altitude", check_context=True, timeout=1000)
6918
self.wait_text("Start pullup airspeed", check_context=True)
6919
self.wait_text("Pullup airspeed", check_context=True)
6920
self.wait_text("Pullup pitch", check_context=True)
6921
self.wait_text("Pullup level", check_context=True)
6922
self.wait_text("Loiter to alt complete", check_context=True, timeout=1000)
6923
self.wait_text("Flare", check_context=True, timeout=400)
6924
self.wait_text("Auto disarmed", check_context=True, timeout=200)
6925
6926
def BadRollChannelDefined(self):
6927
'''ensure we don't die with a bad Roll channel defined'''
6928
self.set_parameter("RCMAP_ROLL", 17)
6929
6930
def MAV_CMD_NAV_LOITER_TO_ALT(self):
6931
'''test loiter to alt mission item'''
6932
self.upload_simple_relhome_mission([
6933
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
6934
(mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 500),
6935
(mavutil.mavlink.MAV_CMD_NAV_LOITER_TO_ALT, 0, 0, 100),
6936
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
6937
])
6938
self.change_mode('AUTO')
6939
self.wait_ready_to_arm()
6940
self.arm_vehicle()
6941
self.wait_altitude(450, 475, relative=True, timeout=600)
6942
self.wait_altitude(75, 125, relative=True, timeout=600)
6943
self.wait_current_waypoint(4)
6944
self.fly_home_land_and_disarm()
6945
6946
def RudderArmedTakeoffRequiresNeutralThrottle(self):
6947
'''auto-takeoff should not occur while rudder continues to be held over'''
6948
self.change_mode('TAKEOFF')
6949
self.wait_ready_to_arm()
6950
self.set_rc(4, 1000)
6951
self.wait_armed()
6952
self.wait_groundspeed(0, 1, minimum_duration=10)
6953
self.set_rc(4, 1500)
6954
self.wait_groundspeed(5, 100)
6955
self.fly_home_land_and_disarm()
6956
6957
def VolzMission(self):
6958
'''test Volz serially-connected servos in a mission'''
6959
volz_motor_mask = ((1 << 0) | (1 << 1) | (1 << 3) | (1 << 8) | (1 << 9) | (1 << 11))
6960
self.set_parameters({
6961
'SERIAL5_PROTOCOL': 14,
6962
'SERVO_VOLZ_MASK': volz_motor_mask,
6963
'RTL_AUTOLAND': 2,
6964
6965
'SIM_VOLZ_ENA': 1,
6966
'SIM_VOLZ_MASK': volz_motor_mask,
6967
})
6968
# defaults file not working?
6969
self.set_parameters({
6970
"SERVO2_REVERSED": 0, # elevator
6971
6972
"SERVO9_FUNCTION": 4,
6973
6974
"SERVO10_FUNCTION": 19, # elevator
6975
6976
"SERVO12_FUNCTION": 21, # rudder
6977
"SERVO12_REVERSED": 1, # rudder
6978
6979
})
6980
self.customise_SITL_commandline([
6981
"--serial5=sim:volz",
6982
], model="plane-redundant",
6983
)
6984
self.wait_ready_to_arm()
6985
self.arm_vehicle()
6986
self.takeoff()
6987
self.fly_home_land_and_disarm()
6988
6989
def DO_CHANGE_ALTITUDE(self):
6990
'''test DO_CHANGE_ALTITUDE mavlink command'''
6991
takeoff_alt = 30
6992
self.takeoff(alt=takeoff_alt, mode='TAKEOFF')
6993
self.wait_altitude(takeoff_alt-1, takeoff_alt+1, minimum_duration=10, relative=True, timeout=60)
6994
6995
self.start_subtest("Home-relative altitude")
6996
target_rel_alt = 40
6997
self.run_cmd(
6998
mavutil.mavlink.MAV_CMD_DO_CHANGE_ALTITUDE,
6999
p1=target_rel_alt,
7000
p2=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
7001
)
7002
self.wait_altitude(
7003
target_rel_alt-1,
7004
target_rel_alt+1,
7005
minimum_duration=10,
7006
relative=True,
7007
timeout=60,
7008
)
7009
7010
self.start_subtest("Absolute altitude")
7011
current_abs_alt = self.get_altitude()
7012
target_abs_alt = current_abs_alt + 30
7013
self.run_cmd(
7014
mavutil.mavlink.MAV_CMD_DO_CHANGE_ALTITUDE,
7015
p1=target_abs_alt,
7016
p2=mavutil.mavlink.MAV_FRAME_GLOBAL,
7017
)
7018
self.wait_altitude(
7019
target_abs_alt-1,
7020
target_abs_alt+1,
7021
minimum_duration=10,
7022
timeout=60,
7023
)
7024
7025
self.start_subtest("Terrain altitude")
7026
current_relative_alt = self.get_altitude(relative=True)
7027
target_terr_alt = current_relative_alt + 10
7028
self.run_cmd(
7029
mavutil.mavlink.MAV_CMD_DO_CHANGE_ALTITUDE,
7030
p1=target_terr_alt,
7031
p2=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
7032
)
7033
self.wait_altitude(
7034
target_terr_alt-1,
7035
target_terr_alt+1,
7036
minimum_duration=10,
7037
relative=True,
7038
altitude_source="TERRAIN_REPORT.current_height",
7039
timeout=120,
7040
)
7041
7042
self.start_subtest("Change alt in loiter")
7043
self.change_mode('LOITER')
7044
current_relative_alt = self.get_altitude(relative=True)
7045
self.wait_altitude(
7046
current_relative_alt-1,
7047
current_relative_alt+1,
7048
minimum_duration=10,
7049
relative=True,
7050
timeout=60,
7051
)
7052
target_loiter_alt = current_relative_alt+5
7053
self.run_cmd(
7054
mavutil.mavlink.MAV_CMD_DO_CHANGE_ALTITUDE,
7055
p1=target_loiter_alt,
7056
p2=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
7057
)
7058
self.wait_altitude(
7059
target_loiter_alt-1,
7060
target_loiter_alt+1,
7061
minimum_duration=10,
7062
relative=True,
7063
timeout=60,
7064
)
7065
7066
self.start_subtest("Change alt in circle")
7067
self.change_mode('CIRCLE')
7068
current_relative_alt = self.get_altitude(relative=True)
7069
self.wait_altitude(
7070
current_relative_alt-1,
7071
current_relative_alt+1,
7072
minimum_duration=10,
7073
relative=True,
7074
timeout=60,
7075
)
7076
target_circle_alt = current_relative_alt-5
7077
self.run_cmd(
7078
mavutil.mavlink.MAV_CMD_DO_CHANGE_ALTITUDE,
7079
p1=target_circle_alt,
7080
p2=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
7081
)
7082
self.wait_altitude(
7083
target_circle_alt-1,
7084
target_circle_alt+1,
7085
minimum_duration=10,
7086
relative=True,
7087
timeout=60,
7088
)
7089
7090
self.start_subtest("Immediately respond to DO_CHANGE_ALTITUDE in a mission")
7091
current_relative_alt = self.get_altitude(relative=True)
7092
mission_alt = current_relative_alt - 10
7093
self.upload_simple_relhome_mission([
7094
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -2000, 0, mission_alt)
7095
])
7096
self.change_mode('AUTO')
7097
self.wait_altitude(
7098
mission_alt-1,
7099
mission_alt+1,
7100
minimum_duration=10,
7101
relative=True,
7102
timeout=240,
7103
)
7104
self.fly_home_land_and_disarm()
7105
7106
def SET_POSITION_TARGET_GLOBAL_INT_for_altitude(self):
7107
'''test changing altitude using SET_POSITION_TARGET_GLOBAL_INT_for_altitude in guided mode'''
7108
self.takeoff(30, mode='TAKEOFF')
7109
self.change_mode('GUIDED')
7110
target_alt = 40
7111
self.mav.mav.set_position_target_global_int_send(
7112
0, # timestamp
7113
self.mav.target_system, # target system_id
7114
self.mav.target_component, # target component id
7115
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
7116
MAV_POS_TARGET_TYPE_MASK.ALT_ONLY,
7117
0, # lat
7118
0, # lon
7119
target_alt, # alt
7120
0, # vx
7121
0, # vy
7122
0, # vz
7123
0, # afx
7124
0, # afy
7125
0, # afz
7126
0, # yaw
7127
0, # yawrate
7128
)
7129
self.wait_altitude(
7130
target_alt-1,
7131
target_alt+1,
7132
minimum_duration=10,
7133
timeout=120,
7134
relative=True,
7135
)
7136
7137
self.progress("Ensure ignore bit is honoured")
7138
self.mav.mav.set_position_target_global_int_send(
7139
0, # timestamp
7140
self.mav.target_system, # target system_id
7141
self.mav.target_component, # target component id
7142
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
7143
MAV_POS_TARGET_TYPE_MASK.IGNORE_ALL, # mask specifying use-only-alt
7144
0, # lat
7145
0, # lon
7146
target_alt, # alt
7147
0, # vx
7148
0, # vy
7149
0, # vz
7150
0, # afx
7151
0, # afy
7152
0, # afz
7153
0, # yaw
7154
0, # yawrate
7155
)
7156
self.wait_altitude(
7157
target_alt-1,
7158
target_alt+1,
7159
timeout=60,
7160
minimum_duration=10,
7161
relative=True,
7162
)
7163
self.fly_home_land_and_disarm()
7164
7165
def mavlink_AIRSPEED(self):
7166
'''check receiving of two airspeed sensors'''
7167
self.set_parameters({
7168
"ARSPD_PIN": 1,
7169
"ARSPD_RATIO": 2,
7170
"ARSPD2_RATIO": 2,
7171
"ARSPD2_TYPE": 100,
7172
"ARSPD2_AUTOCAL": 1,
7173
})
7174
self.reboot_sitl()
7175
7176
# Add listener to airspeed message
7177
airspeed_active = [None, None]
7178
7179
def update_airspeed_active(mav, m):
7180
if m.get_type() != 'AIRSPEED':
7181
return
7182
# 2 here is the correct value of mavutil.mavlink.AIRSPEED_SENSOR_USING
7183
# However it was wrong in the MAVLink spec for a while
7184
airspeed_active[m.id] = (m.flags & 2) != 0
7185
7186
self.install_message_hook_context(update_airspeed_active)
7187
7188
self.wait_ready_to_arm()
7189
7190
self.start_subtest('Ensure we get both instances')
7191
if any(v is None for v in airspeed_active):
7192
raise NotAchievedException("Did not get both airspeed messages %s" % str(airspeed_active))
7193
7194
if airspeed_active != [True, False]:
7195
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7196
7197
self.takeoff(mode="TAKEOFF", alt=100)
7198
7199
self.start_subtest("Now testing sensor 1 is used in flight")
7200
if airspeed_active != [True, False]:
7201
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7202
7203
self.start_subtest("Now testing failure of sensor 1 - fail to many m/s")
7204
self.set_parameter("SIM_ARSPD_FAIL", 60)
7205
7206
# airspeed sensor never becomes unhealthy - we just stop using
7207
# it as EKF3 starts to reject, allow 10 seconds
7208
self.delay_sim_time(10)
7209
if airspeed_active != [False, False]:
7210
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7211
7212
# Re-enable sensors, after some time the sensor should be re-enabled
7213
self.set_parameter("SIM_ARSPD_FAIL", 0)
7214
self.delay_sim_time(60)
7215
if airspeed_active != [True, False]:
7216
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7217
7218
self.start_subtest("Now testing combinations of use and primary params")
7219
7220
# Changing the primary should have no effect as the second sensor is not marked to use
7221
self.set_parameter("ARSPD_PRIMARY", 1)
7222
self.delay_sim_time(10)
7223
if airspeed_active != [True, False]:
7224
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7225
7226
# Allowing the second sensor to be used should not result in a switch when armed despite the primary parameter
7227
self.set_parameter("ARSPD2_USE", 1)
7228
self.delay_sim_time(10)
7229
if airspeed_active != [True, False]:
7230
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7231
7232
# Changing the primary back to the first sensor, and then again to the second
7233
# Now the second can be used it should switch
7234
self.set_parameter("ARSPD_PRIMARY", 0)
7235
self.set_parameter("ARSPD_PRIMARY", 1)
7236
self.delay_sim_time(10)
7237
if airspeed_active != [False, True]:
7238
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7239
7240
# Now stop using the second
7241
self.set_parameter("ARSPD2_USE", 0)
7242
self.delay_sim_time(10)
7243
if airspeed_active != [True, False]:
7244
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7245
7246
self.fly_home_land_and_disarm()
7247
self.change_mode("MANUAL")
7248
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
7249
7250
self.start_subtest("Now testing primary arming check")
7251
7252
# Should not be able to arm with primary sensor not set to use
7253
self.assert_prearm_failure("Airspeed: not using Primary (2)")
7254
7255
self.start_subtest("Testing primary changes when disarmed")
7256
7257
# Now the vehicle is disarmed, enabling use for the primary sensor should result in it being used
7258
self.set_parameter("ARSPD2_USE", 1)
7259
self.delay_sim_time(10)
7260
if airspeed_active != [False, True]:
7261
raise NotAchievedException("Not using expected airspeed sensors %s" % str(airspeed_active))
7262
7263
def RudderArmingWithArmingChecksSkipped(self):
7264
'''check we can't arm with rudder even if all checks are skipped'''
7265
self.set_parameters({
7266
"ARMING_RUDDER": 0,
7267
"ARMING_SKIPCHK": -1,
7268
"RC4_REVERSED": 0,
7269
})
7270
self.reboot_sitl()
7271
self.delay_sim_time(5)
7272
self.set_rc(4, 2000)
7273
w = vehicle_test_suite.WaitAndMaintainDisarmed(
7274
self,
7275
minimum_duration=30,
7276
timeout=60,
7277
)
7278
w.run()
7279
7280
def Volz(self):
7281
'''test Volz serially-connected'''
7282
volz_motor_mask = ((1 << 0) | (1 << 1) | (1 << 3) | (1 << 8) | (1 << 9) | (1 << 11))
7283
self.set_parameters({
7284
'SERIAL5_PROTOCOL': 14,
7285
'SERVO_VOLZ_MASK': volz_motor_mask,
7286
'RTL_AUTOLAND': 2,
7287
7288
'SIM_VOLZ_ENA': 1,
7289
'SIM_VOLZ_MASK': volz_motor_mask,
7290
})
7291
# defaults file not working?
7292
self.set_parameters({
7293
"SERVO2_REVERSED": 0, # elevator
7294
7295
"SERVO9_FUNCTION": 4,
7296
7297
"SERVO10_FUNCTION": 19, # elevator
7298
7299
"SERVO12_FUNCTION": 21, # rudder
7300
"SERVO12_REVERSED": 1, # rudder
7301
7302
})
7303
self.customise_SITL_commandline([
7304
"--serial5=sim:volz",
7305
], model="plane-redundant",
7306
)
7307
self.wait_ready_to_arm()
7308
self.takeoff()
7309
self.change_mode('FBWA')
7310
straight_and_level_text = "straight-and-level"
7311
self.send_statustext(straight_and_level_text)
7312
self.delay_sim_time(2)
7313
self.progress("sticking servo with constant deflection")
7314
self.set_rc(1, 1400)
7315
self.change_mode('MANUAL')
7316
self.delay_sim_time(0.5)
7317
self.progress("Failing servo")
7318
self.set_parameter('SIM_VOLZ_FMASK', 1)
7319
self.set_rc(1, 1500)
7320
self.change_mode('FBWA')
7321
aileron_failed_text = "aileron has been failed"
7322
self.send_statustext(aileron_failed_text)
7323
self.delay_sim_time(15)
7324
self.set_parameter('SIM_VOLZ_FMASK', 0)
7325
7326
log_filepath = self.current_onboard_log_filepath()
7327
# terminate vehicle in-flight so our tests aren't fooled by the
7328
# "flying home" data:
7329
self.reboot_sitl(force=True)
7330
7331
self.progress("Inspecting DFReader to ensure servo failure is recorded in the log")
7332
dfreader = self.dfreader_for_path(log_filepath)
7333
while True:
7334
m = dfreader.recv_match(type=['MSG'])
7335
if m is None:
7336
raise NotAchievedException("Did not see straight_and_level_text")
7337
if m.Message == "SRC=250/250:" + straight_and_level_text:
7338
break
7339
7340
self.progress("Ensuring deflections are close to zero in straight-and-level flight")
7341
chan1_good = False
7342
chan9_good = False
7343
while not (chan1_good and chan9_good):
7344
m = dfreader.recv_match()
7345
if m is None:
7346
raise NotAchievedException("Did not see chan1 and chan9 as close-to-0")
7347
if m.get_type() != 'CSRV':
7348
continue
7349
if m.Id == 0 and abs(m.Pos) < 3:
7350
chan1_good = True
7351
elif m.Id == 8 and abs(m.Pos) < 3:
7352
chan9_good = True
7353
7354
while True:
7355
m = dfreader.recv_match(type=['MSG'])
7356
if m is None:
7357
raise NotAchievedException("Did not see aileron_failed_text")
7358
if m.Message == "SRC=250/250:" + aileron_failed_text:
7359
break
7360
7361
self.progress("Checking servo9 is deflected")
7362
while True:
7363
# m = dfreader.recv_match(type=['CSRV'])
7364
m = dfreader.recv_match()
7365
if m is None:
7366
raise NotAchievedException("Did not see chan9 deflection")
7367
if m.get_type() != 'CSRV':
7368
continue
7369
if m.Id != 8:
7370
continue
7371
if m.Pos < 20:
7372
continue
7373
self.progress(f"Chan9 is deflected ({m})")
7374
break
7375
7376
self.progress("Ensuring the vehicle stabilised with a single aileron")
7377
attitude_good_count = 0
7378
while attitude_good_count < 5:
7379
m = dfreader.recv_match()
7380
if m is None:
7381
raise NotAchievedException("Did not see good attitude")
7382
if m.get_type() != 'ATT':
7383
continue
7384
if abs(m.Roll) >= 5:
7385
attitude_good_count = 0
7386
continue
7387
attitude_good_count += 1
7388
self.progress(f"Attitude is stabilised ({m})")
7389
7390
self.progress("Ensure the roll integrator is wound up")
7391
while True:
7392
m = dfreader.recv_match()
7393
if m is None:
7394
raise NotAchievedException("Did not see wound-up roll integrator")
7395
if m.get_type() != 'PIDR':
7396
continue
7397
if m.I > 5:
7398
self.progress(f"Roll integrator is wound up ({m})")
7399
break
7400
7401
self.progress("Checking that aileron is stuck at some deflection")
7402
good_count = 0
7403
while good_count < 5:
7404
m = dfreader.recv_match()
7405
if m is None:
7406
raise NotAchievedException("Did not see csrv Pos/PosCmd discrepancy")
7407
if m.get_type() != 'CSRV':
7408
continue
7409
if m.Id != 0:
7410
continue
7411
delta = abs(m.Pos - m.PosCmd)
7412
if delta <= 20:
7413
self.progress(f"CSRV Pos/PosCmd {delta=:.2f} BAD {m}")
7414
good_count = 0
7415
continue
7416
self.progress(f"CSRV Pos/PosCmd {delta=:.2f} OK {m}")
7417
good_count += 1
7418
7419
def MAV_CMD_NAV_LOITER_TURNS_zero_turn(self):
7420
'''Ensure air vehicle achieves loiter target before exiting'''
7421
offset = 500
7422
alt = self.get_parameter("RTL_ALTITUDE")
7423
waypoint_radius = 100
7424
7425
loiter_turns_loc_ccw = self.home_relative_loc_ne(offset, offset)
7426
loiter_turns_loc_cw = self.home_relative_loc_ne(offset, -offset)
7427
7428
# upload a mission plan containing zero-turn loiters
7429
self.upload_simple_relhome_mission([
7430
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 10),
7431
self.create_MISSION_ITEM_INT(
7432
mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS,
7433
p1=0, # Turns
7434
p3=-waypoint_radius, # Radius (If positive loiter clockwise, else counter-clockwise)
7435
x=int(loiter_turns_loc_ccw.lat*1e7),
7436
y=int(loiter_turns_loc_ccw.lng*1e7),
7437
z=alt,
7438
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT
7439
),
7440
self.create_MISSION_ITEM_INT(
7441
mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS,
7442
p1=0, # Turns
7443
p3=waypoint_radius, # Radius (If positive loiter clockwise, else counter-clockwise)
7444
x=int(loiter_turns_loc_cw.lat*1e7),
7445
y=int(loiter_turns_loc_cw.lng*1e7),
7446
z=alt,
7447
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT
7448
),
7449
self.create_MISSION_ITEM_INT(
7450
mavutil.mavlink.MAV_CMD_DO_JUMP,
7451
p1=2, # waypoint to jump to
7452
p2=1 # number of jumps (-1: infinite)
7453
),
7454
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -offset, -offset, alt),
7455
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -offset, offset, alt),
7456
])
7457
7458
self.change_mode("AUTO")
7459
self.wait_ready_to_arm()
7460
7461
self.arm_vehicle()
7462
7463
# check the vehicle is flying to each waypoint as expected
7464
self.wait_distance_to_waypoint(2, distance_min=90, distance_max=110, timeout=90) # North East Loiter
7465
self.wait_distance_to_waypoint(3, distance_min=90, distance_max=110, timeout=90) # North West Loiter
7466
7467
# Jump to first 0-Turn Loiter
7468
self.wait_distance_to_waypoint(2, distance_min=90, distance_max=110, timeout=90) # North East Loiter
7469
7470
# Ensure we go back through this loiter point
7471
self.wait_distance_to_waypoint(3, distance_min=90, distance_max=110, timeout=90) # North West Loiter
7472
7473
self.wait_distance_to_waypoint(5, distance_min=10, distance_max=20, timeout=90) # South West Waypoint
7474
self.wait_distance_to_waypoint(6, distance_min=10, distance_max=20, timeout=90) # South East Waypoint
7475
7476
self.fly_home_land_and_disarm()
7477
7478
class ValidateVFRHudClimbAgainstSimState(vehicle_test_suite.TestSuite.MessageHook):
7479
'''monitors VFR_HUD to make sure reported climbrate is in-line with SIM_STATE.vd'''
7480
def __init__(self, suite, max_allowed_divergence=5):
7481
super(AutoTestPlane.ValidateVFRHudClimbAgainstSimState, self).__init__(suite)
7482
self.max_allowed_divergence = max_allowed_divergence # m/s
7483
self.max_divergence = 0
7484
self.vfr_hud = None
7485
self.sim_state = None
7486
self.last_print = 0
7487
self.min_print_interval = 1 # seconds
7488
self.instafail = True
7489
self.failed = False
7490
7491
def progress_prefix(self):
7492
return "VVHCASS: "
7493
7494
def process(self, mav, m):
7495
if m.get_type() == 'VFR_HUD':
7496
self.vfr_hud = m
7497
elif m.get_type() == 'SIM_STATE':
7498
self.sim_state = m
7499
if self.vfr_hud is None:
7500
return
7501
if self.sim_state is None:
7502
return
7503
7504
vfr_hud_climb = self.vfr_hud.climb
7505
sim_state_climb = -self.sim_state.vd
7506
divergence = abs(vfr_hud_climb - sim_state_climb)
7507
if (time.time() - self.last_print > self.min_print_interval or
7508
divergence > self.max_divergence):
7509
self.progress(f"climb delta is {divergence}")
7510
self.last_print = time.time()
7511
if divergence > self.max_divergence:
7512
self.max_divergence = divergence
7513
if divergence > self.max_allowed_divergence:
7514
msg = f"VFR_HUD.climb diverged from SIM_STATE.vd by {divergence}m/s (max={self.max_allowed_divergence}m/s"
7515
if self.instafail:
7516
raise NotAchievedException(msg)
7517
else:
7518
self.failed = True
7519
self.progress(msg)
7520
7521
def hook_removed(self):
7522
if self.vfr_hud is None:
7523
raise ValueError("Did not receive VFR_HUD")
7524
if self.sim_state is None:
7525
raise ValueError("Did not receive SIM_STATE")
7526
msg = f"Maximum divergence was {self.max_divergence}m/s (max={self.max_allowed_divergence}m/s)"
7527
if self.failed:
7528
raise NotAchievedException(msg)
7529
7530
self.progress(msg)
7531
7532
def SoaringClimbRate(self):
7533
'''test displayed climb rate when soaring'''
7534
self.set_parameters({
7535
'RC16_OPTION': 88, # soaring enable
7536
'SOAR_ENABLE': 1,
7537
})
7538
self.set_rc(16, 1000) # disable soaring
7539
self.reboot_sitl()
7540
self.set_message_rate_hz('SIM_STATE', 10)
7541
self.install_message_hook_context(AutoTestPlane.ValidateVFRHudClimbAgainstSimState(self))
7542
self.takeoff(20)
7543
self.change_mode('FBWB')
7544
self.set_rc(2, 1000) # full climb
7545
self.delay_sim_time(10)
7546
self.set_rc(16, 2000) # enable soaring
7547
self.delay_sim_time(10)
7548
7549
self.set_rc(2, 1500)
7550
self.fly_home_land_and_disarm()
7551
7552
def ScriptedArmingChecksApplet(self):
7553
""" Applet for Arming Checks will prevent a vehicle from arming based on scripted checks
7554
"""
7555
self.start_subtest("Scripted Arming Checks Applet validation")
7556
self.context_collect("STATUSTEXT")
7557
7558
"""Initialize the FC"""
7559
self.set_parameter("SCR_ENABLE", 1)
7560
self.install_applet_script_context("arming-checks.lua")
7561
self.reboot_sitl()
7562
self.wait_ekf_happy()
7563
self.wait_text("ArduPilot Ready", check_context=True)
7564
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7565
7566
self.start_subsubtest("ArmCk: MAV_SYSID not set")
7567
self.progress("Currently SYSID is %f" % self.get_parameter('MAV_SYSID'))
7568
self.wait_text("ArmCk: warn: MAV_SYSID not set", timeout=30, check_context=True, regex=True)
7569
""" disable the SYSID check, since autotest doesn't like changing the sysid"""
7570
self.set_parameter("ARM_SYSID", -1)
7571
7572
''' This check comes first since its part of the standard parameters - an invalid scaling speed'''
7573
self.start_subsubtest("ArmCk: SCALING_SPEED close to AIRSPEED_CRUISE")
7574
self.assert_prearm_failure("fail: Scaling spd", other_prearm_failures_fatal=False)
7575
self.set_parameter("SCALING_SPEED", 22)
7576
self.wait_text("clear: Scaling spd", check_context=True)
7577
7578
self.start_subsubtest("ArmCk: FOLL_SYSID must be set if FOLL_ENABLE = 1")
7579
self.set_parameter("FOLL_ENABLE", 1)
7580
self.set_parameter("FOLL_OFS_X", 10)
7581
self.assert_prearm_failure("FOLL_SYSID not set", other_prearm_failures_fatal=False)
7582
self.set_parameter("FOLL_SYSID", 3)
7583
self.wait_text("clear: FOLL_SYSID not set", check_context=True)
7584
self.set_parameter("FOLL_SYSID", -1)
7585
7586
self.start_subsubtest("ArmCk: FOLL_OFS_[XYZ] must be set if FOLL_ENABLE = 1")
7587
self.set_parameter("FOLL_OFS_X", 0)
7588
self.assert_prearm_failure("FOLL_OFS_[XYZ] = 0", other_prearm_failures_fatal=False)
7589
self.set_parameter("FOLL_OFS_X", 10)
7590
self.wait_text("clear: FOLL_OFS_[XYZ] = 0", check_context=True)
7591
self.set_parameter("FOLL_OFS_X", 0)
7592
self.assert_prearm_failure("FOLL_OFS_[XYZ] = 0", other_prearm_failures_fatal=False)
7593
self.set_parameter("FOLL_OFS_Y", 10)
7594
self.wait_text("clear: FOLL_OFS_[XYZ] = 0", check_context=True)
7595
self.set_parameter("FOLL_OFS_Y", 0)
7596
self.assert_prearm_failure("FOLL_OFS_[XYZ] = 0", other_prearm_failures_fatal=False)
7597
self.set_parameter("FOLL_OFS_Z", 10)
7598
self.wait_text("clear: FOLL_OFS_[XYZ] = 0", check_context=True)
7599
""" clear these checks to make the context cleaner for subsequent tests """
7600
self.set_parameters({
7601
"ARM_SYSID": -1,
7602
"ARM_FOLL_SYSID": -1,
7603
"ARM_FOLL_SYSID_X": -1,
7604
"ARM_FOLL_OFS_DEF": -1,
7605
})
7606
7607
self.start_subsubtest("ArmCk: RTL_ALTITUDE must be legal")
7608
self.progress("Currently ARM_P_RTL_ALT is %f" % self.get_parameter('ARM_P_RTL_ALT'))
7609
self.set_parameter("RTL_ALTITUDE", 150)
7610
self.assert_prearm_failure("ArmCk: fail: RTL_ALTITUDE too high", other_prearm_failures_fatal=False)
7611
self.set_parameter("RTL_ALTITUDE", 120)
7612
self.wait_text("clear: RTL_ALT", check_context=True)
7613
7614
self.start_subsubtest("ArmCk: RTL_CLIMB_MIN must be legal")
7615
self.set_parameter("RTL_CLIMB_MIN", 150)
7616
self.wait_text("ArmCk: warn: RTL_CLIMB_MIN too high", check_context=True)
7617
self.set_parameter("RTL_CLIMB_MIN", 120)
7618
self.wait_text("clear: RTL_CLIMB_MIN too high", check_context=True)
7619
7620
self.start_subsubtest("ArmCk: AIRSPEED stall < min < cruise < max")
7621
''' Airspeed parameter start out as
7622
AIRSPEED_STALL = 0
7623
AIRSPEED_MIN = 10
7624
AIRSPEED_CRUISE = 22
7625
AIRSPEED_MAX = 30
7626
'''
7627
self.start_subsubtest("ArmCk: AIRSPEED max < others")
7628
self.set_parameter("AIRSPEED_MAX", 5)
7629
self.assert_prearm_failure("ArmCk: fail: stall < min", other_prearm_failures_fatal=False)
7630
self.set_parameter("AIRSPEED_MAX", 30)
7631
self.wait_text("clear: stall < min", check_context=True)
7632
self.start_subsubtest("ArmCk: AIRSPEED cruise < min")
7633
self.set_parameter("AIRSPEED_MIN", 25)
7634
self.assert_prearm_failure("ArmCk: fail: stall < min", other_prearm_failures_fatal=False)
7635
self.set_parameter("AIRSPEED_MIN", 10)
7636
self.wait_text("clear: stall < min", check_context=True)
7637
self.start_subsubtest("ArmCk: AIRSPEED cruise > max")
7638
self.set_parameter("AIRSPEED_CRUISE", 40)
7639
self.set_parameter("SCALING_SPEED", 40)
7640
self.assert_prearm_failure("ArmCk: fail: stall < min", other_prearm_failures_fatal=False)
7641
self.set_parameter("AIRSPEED_CRUISE", 22)
7642
self.set_parameter("SCALING_SPEED", 22)
7643
self.wait_text("clear: stall < min", check_context=True)
7644
7645
self.start_subsubtest("ArmCk: AIRSPEED_MIN must be > AIRSPEED_STALL")
7646
''' only applies if AIRSPEED_STALL is non zero'''
7647
self.set_parameter("AIRSPEED_STALL", 2)
7648
self.wait_text("ArmCk: info: Min Speed not", check_context=True)
7649
self.set_parameter("AIRSPEED_STALL", 8)
7650
7651
self.start_subsubtest("ArmCk: Mount SYSID must not match FOLL_SYSID")
7652
self.set_parameter("ARM_SYSID", -1)
7653
''' to fail the check MNTx_SYSID_DFLT must be non zero but not= FOLL_SYSID'''
7654
self.set_parameter("MNT1_SYSID_DFLT", 1)
7655
''' Need a healthy camera mount defined for this to work '''
7656
self.setup_servo_mount()
7657
self.progress("rebooting to enable MNT1")
7658
self.reboot_sitl() # to handle MNT_TYPE changing
7659
self.wait_ekf_happy()
7660
self.wait_text("ArduPilot Ready", check_context=True)
7661
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7662
self.progress("Currently FOLL_SYSID is %f" % self.get_parameter('FOLL_SYSID'))
7663
self.progress("Currently MNT1_SYSID_DFLT is %f" % self.get_parameter('MNT1_SYSID_DFLT'))
7664
self.set_parameter("ARM_SYSID", -1)
7665
self.progress("Currently FOLL_SYSID is %f" % self.get_parameter('FOLL_SYSID'))
7666
self.progress("Currently MNT1_SYSID_DFLT is %f" % self.get_parameter('MNT1_SYSID_DFLT'))
7667
self.wait_text("warn: MNTx_SYSID != FOLL", check_context=True)
7668
7669
self.start_subsubtest("ArmCk: Fence must be enabled or autoenabled (warning)")
7670
self.reboot_sitl()
7671
self.wait_ekf_happy()
7672
self.wait_text("ArduPilot Ready", check_context=True)
7673
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7674
self.load_fence("CMAC-fence.txt")
7675
self.wait_statustext("warn: Fence not enabled", check_context=True)
7676
self.set_parameter("FENCE_ENABLE", 1)
7677
self.wait_statustext("clear: Fence not enabled", check_context=True)
7678
self.set_parameter("FENCE_ENABLE", 0)
7679
self.wait_statustext("warn: Fence not enabled", check_context=True)
7680
self.set_parameter("FENCE_AUTOENABLE", 1)
7681
self.wait_text("clear: Fence not enabled", check_context=True)
7682
self.set_parameter("FENCE_AUTOENABLE", 0)
7683
self.wait_text("warn: Fence not enabled", check_context=True)
7684
7685
def ScriptedArmingChecksAppletEStop(self):
7686
""" Applet for Arming Checks will prevent a vehicle from arming based on scripted checks
7687
"""
7688
self.start_subtest("Scripted Arming Checks Applet validation")
7689
self.context_collect("STATUSTEXT")
7690
7691
"""Initialize the FC"""
7692
self.set_parameter("SCR_ENABLE", 1)
7693
self.install_applet_script_context("arming-checks.lua")
7694
self.reboot_sitl()
7695
self.wait_ekf_happy()
7696
self.wait_text("ArduPilot Ready", check_context=True)
7697
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7698
self.set_parameters({
7699
"ARM_SYSID": -1,
7700
"ARM_FOLL_SYSID": -1,
7701
"ARM_FOLL_SYSID_X": -1,
7702
"ARM_FOLL_OFS_DEF": -1,
7703
"ARM_P_SCALING": -1,
7704
})
7705
7706
self.start_subsubtest("ArmCk: Cannot arm while motors estopped")
7707
self.set_parameter("RC6_OPTION", 165)
7708
self.progress("rebooting to enable RC channel")
7709
self.reboot_sitl() # to handle RC option changing
7710
self.wait_ekf_happy()
7711
self.wait_text("ArduPilot Ready", check_context=True)
7712
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7713
self.set_parameters({
7714
"ARM_SYSID": -1,
7715
"ARM_FOLL_SYSID": -1,
7716
"ARM_FOLL_SYSID_X": -1,
7717
"ARM_FOLL_OFS_DEF": -1,
7718
"ARM_P_SCALING": -1,
7719
})
7720
self.set_rc(6, 1000)
7721
self.assert_prearm_failure("ArmCk: fail: Motors EStopped", other_prearm_failures_fatal=False)
7722
self.set_rc(6, 2000)
7723
self.wait_text("clear: Motors EStopped", timeout=30, check_context=True, regex=True)
7724
self.wait_ready_to_arm()
7725
7726
def ScriptedArmingChecksAppletRally(self):
7727
""" Applet for Arming Checks will prevent a vehicle from arming based on scripted checks
7728
"""
7729
self.start_subtest("Scripted Arming Checks Applet validation")
7730
self.context_collect("STATUSTEXT")
7731
7732
"""Initialize the FC"""
7733
self.set_parameter("SCR_ENABLE", 1)
7734
self.install_applet_script_context("arming-checks.lua")
7735
self.reboot_sitl()
7736
self.wait_ekf_happy()
7737
self.wait_text("ArduPilot Ready", check_context=True)
7738
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
7739
7740
self.start_subsubtest("ArmCk: MAV_SYSID not set")
7741
self.progress("Currently SYSID is %f" % self.get_parameter('MAV_SYSID'))
7742
self.wait_text("ArmCk: warn: MAV_SYSID not set", timeout=30, check_context=True, regex=True)
7743
""" disable the SYSID check, since autotest doesn't like changing the sysid"""
7744
self.set_parameters({
7745
"ARM_SYSID": -1,
7746
"ARM_FOLL_SYSID": -1,
7747
"ARM_FOLL_SYSID_X": -1,
7748
"ARM_FOLL_OFS_DEF": -1,
7749
"ARM_P_SCALING": -1,
7750
})
7751
7752
self.start_subsubtest("ArmCk: Rally Point must be < ARM_V_RALLY_MAX meters away")
7753
self.progress("Currently RALLY_LIMIT_KM is %f" % self.get_parameter('RALLY_LIMIT_KM'))
7754
loc = self.home_relative_loc_ne(6500, -50)
7755
self.upload_rally_points_from_locations([loc])
7756
self.wait_text("warn: Rally too far", check_context=True)
7757
self.set_parameter("RALLY_LIMIT_KM", 7)
7758
self.wait_text("clear: Rally too far", check_context=True)
7759
7760
def PlaneFollowAppletSanity(self):
7761
'''PLane Follow Sanity Check, not a detailed test'''
7762
self.start_subtest("Plane Follow Script Load and Start")
7763
7764
self.install_applet_script_context("plane_follow.lua")
7765
self.install_script_module(self.script_modules_source_path("pid.lua"), "pid.lua")
7766
self.install_script_module(self.script_modules_source_path("mavlink_attitude.lua"), "mavlink_attitude.lua")
7767
self.install_mavlink_module()
7768
7769
self.set_parameters({
7770
"SCR_ENABLE": 1,
7771
"SIM_SPEEDUP": 20, # need to give some cycles to lua
7772
"RC7_OPTION": 301,
7773
})
7774
7775
self.context_collect("STATUSTEXT")
7776
7777
self.reboot_sitl()
7778
7779
self.wait_text("Plane Follow .* script loaded", timeout=30, regex=True, check_context=True)
7780
7781
self.wait_ready_to_arm()
7782
self.set_rc(7, 2000)
7783
self.wait_text("PFollow: must be armed", check_context=True)
7784
self.set_rc(7, 1000)
7785
self.arm_vehicle()
7786
self.set_rc(7, 2000)
7787
self.wait_text("PFollow: enabled", check_context=True)
7788
self.set_rc(7, 1000)
7789
self.wait_text("PFollow: disabled", check_context=True)
7790
self.disarm_vehicle()
7791
7792
self.reboot_sitl()
7793
# remove the installed modules.
7794
self.remove_installed_script_module("pid.lua")
7795
self.remove_installed_script_module("mavlink_attitude.lua")
7796
7797
def PreflightRebootComponent(self):
7798
'''Ensure that PREFLIGHT_REBOOT commands sent to components don't reboot Autopilot'''
7799
self.run_cmd_int(
7800
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
7801
p1=1, # Reboot autopilot
7802
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
7803
target_compid=mavutil.mavlink.MAV_COMP_ID_GIMBAL
7804
)
7805
7806
def tests(self):
7807
'''return list of all tests'''
7808
ret = []
7809
ret.extend(self.tests1a())
7810
ret.extend(self.tests1b())
7811
ret.extend(self.tests1c())
7812
return ret
7813
7814
def tests1a(self):
7815
ret = []
7816
ret = super(AutoTestPlane, self).tests()
7817
ret.extend([
7818
self.AuxModeSwitch,
7819
self.TestRCCamera,
7820
self.TestRCRelay,
7821
self.ThrottleFailsafe,
7822
self.NeedEKFToArm,
7823
self.ThrottleFailsafeFence,
7824
self.SoaringClimbRate,
7825
self.TestFlaps,
7826
self.DO_CHANGE_SPEED,
7827
self.DO_REPOSITION,
7828
self.GuidedRequest,
7829
self.MainFlight,
7830
self.TestGripperMission,
7831
self.Parachute,
7832
self.ParachuteSinkRate,
7833
self.DO_PARACHUTE,
7834
self.PitotBlockage,
7835
self.AIRSPEED_AUTOCAL,
7836
self.RangeFinder,
7837
self.FenceStatic,
7838
self.FenceRTL,
7839
self.FenceRTLRally,
7840
self.FenceRetRally,
7841
self.FenceAltCeilFloor,
7842
self.FenceMinAltAutoEnable,
7843
self.FenceMinAltEnableAutoland,
7844
self.FenceMinAltAutoEnableAbort,
7845
self.FenceAutoEnableDisableSwitch,
7846
Test(self.FenceCircleExclusionAutoEnable, speedup=20),
7847
self.FenceEnableDisableSwitch,
7848
self.FenceEnableDisableAux,
7849
self.FenceBreachedChangeMode,
7850
self.FenceNoFenceReturnPoint,
7851
self.FenceNoFenceReturnPointInclusion,
7852
self.FenceDisableUnderAction,
7853
self.ADSBFailActionRTL,
7854
self.ADSBResumeActionResumeLoiter,
7855
self.SimADSB,
7856
self.Button,
7857
self.FRSkySPort,
7858
self.FRSkyPassThroughStatustext,
7859
self.FRSkyPassThroughSensorIDs,
7860
self.FRSkyMAVlite,
7861
self.FRSkyD,
7862
self.LTM,
7863
self.DEVO,
7864
self.AdvancedFailsafe,
7865
self.LOITER,
7866
self.MAV_CMD_NAV_LOITER_TURNS,
7867
self.MAV_CMD_NAV_LOITER_TO_ALT,
7868
self.DeepStall,
7869
self.WatchdogHome,
7870
self.LargeMissions,
7871
self.Soaring,
7872
self.Terrain,
7873
self.TerrainMission,
7874
self.TerrainMissionInterrupt,
7875
self.UniversalAutoLandScript,
7876
])
7877
return ret
7878
7879
def tests1b(self):
7880
return [
7881
self.TerrainLoiter,
7882
self.VectorNavEAHRS,
7883
self.MicroStrainEAHRS5,
7884
self.MicroStrainEAHRS7,
7885
self.InertialLabsEAHRS,
7886
self.GpsSensorPreArmEAHRS,
7887
self.Deadreckoning,
7888
self.EKFlaneswitch,
7889
self.AirspeedDrivers,
7890
self.RTL_CLIMB_MIN,
7891
self.ClimbBeforeTurn,
7892
self.IMUTempCal,
7893
self.MAV_CMD_DO_AUX_FUNCTION,
7894
self.SmartBattery,
7895
self.FlyEachFrame,
7896
self.AutoLandMode,
7897
self.RCDisableAirspeedUse,
7898
self.AHRS_ORIENTATION,
7899
self.AHRSTrim,
7900
self.LandingDrift,
7901
self.TakeoffAuto1,
7902
self.TakeoffAuto2,
7903
self.TakeoffAuto3,
7904
self.TakeoffAuto4,
7905
self.TakeoffTakeoff1,
7906
self.TakeoffTakeoff2,
7907
self.TakeoffTakeoff3,
7908
self.TakeoffTakeoff4,
7909
self.TakeoffTakeoff5,
7910
self.TakeoffGround,
7911
self.TakeoffIdleThrottle,
7912
self.TakeoffBadLevelOff,
7913
self.TakeoffLevelOffWind,
7914
self.ForcedDCM,
7915
self.DCMFallback,
7916
self.MAVFTP,
7917
self.AUTOTUNE,
7918
self.AutotuneFiltering,
7919
self.MegaSquirt,
7920
self.Hirth,
7921
self.MSP_DJI,
7922
self.SpeedToFly,
7923
self.AltitudeSlopeMaxHeight,
7924
self.HIGH_LATENCY2,
7925
self.MidAirDisarmDisallowed,
7926
self.AerobaticsScripting,
7927
self.MANUAL_CONTROL,
7928
self.RunMissionScript,
7929
self.WindEstimates,
7930
self.AltResetBadGPS,
7931
self.AirspeedCal,
7932
self.MissionJumpTags,
7933
Test(self.GCSFailsafe, speedup=8),
7934
self.SDCardWPTest,
7935
self.NoArmWithoutMissionItems,
7936
self.RudderArmedTakeoffRequiresNeutralThrottle,
7937
self.MODE_SWITCH_RESET,
7938
self.ExternalPositionEstimate,
7939
self.SagetechMXS,
7940
self.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
7941
self.MAV_CMD_PREFLIGHT_CALIBRATION,
7942
self.MAV_CMD_DO_INVERTED_FLIGHT,
7943
self.MAV_CMD_DO_AUTOTUNE_ENABLE,
7944
self.MAV_CMD_DO_GO_AROUND,
7945
self.MAV_CMD_DO_FLIGHTTERMINATION,
7946
self.MAV_CMD_DO_LAND_START,
7947
self.MAV_CMD_NAV_ALTITUDE_WAIT,
7948
self.InteractTest,
7949
self.CompassLearnInFlight,
7950
self.MAV_CMD_MISSION_START,
7951
self.TerrainRally,
7952
self.MAV_CMD_NAV_LOITER_UNLIM,
7953
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
7954
self.MinThrottle,
7955
self.ClimbThrottleSaturation,
7956
self.GuidedAttitudeNoGPS,
7957
self.ScriptStats,
7958
self.GPSPreArms,
7959
self.SetHomeAltChange,
7960
self.SetHomeAltChange2,
7961
self.SetHomeAltChange3,
7962
self.ForceArm,
7963
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
7964
self.GliderPullup,
7965
self.BadRollChannelDefined,
7966
self.VolzMission,
7967
self.mavlink_AIRSPEED,
7968
self.Volz,
7969
self.LoggedNamedValueFloat,
7970
self.LoggedNamedValueString,
7971
self.AdvancedFailsafeBadBaro,
7972
self.DO_CHANGE_ALTITUDE,
7973
self.SET_POSITION_TARGET_GLOBAL_INT_for_altitude,
7974
self.MAV_CMD_NAV_LOITER_TURNS_zero_turn,
7975
self.RudderArmingWithArmingChecksSkipped,
7976
self.TerrainLoiterToCircle,
7977
self.FenceDoubleBreach,
7978
self.ScriptedArmingChecksApplet,
7979
self.ScriptedArmingChecksAppletEStop,
7980
self.ScriptedArmingChecksAppletRally,
7981
self.PlaneFollowAppletSanity,
7982
self.PreflightRebootComponent,
7983
]
7984
7985
def tests1c(self):
7986
'''kind of reserved for flapping tests which we still have hopes for'''
7987
return [
7988
self.DeadreckoningNoAirSpeed,
7989
]
7990
7991
def disabled_tests(self):
7992
return {
7993
"LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054",
7994
"InteractTest": "requires user interaction",
7995
"ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass",
7996
"SoaringClimbRate": "very bad sink rate",
7997
}
7998
7999
8000
class AutoTestPlaneTests1a(AutoTestPlane):
8001
def tests(self):
8002
return self.tests1a()
8003
8004
8005
class AutoTestPlaneTests1b(AutoTestPlane):
8006
def tests(self):
8007
return self.tests1b()
8008
8009
8010
class AutoTestPlaneTests1c(AutoTestPlane):
8011
def tests(self):
8012
return self.tests1c()
8013
8014