Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/quadplane.py
9659 views
1
'''
2
Fly ArduPlane QuadPlane in SITL
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
import os
9
import numpy
10
import math
11
import copy
12
13
from pymavlink import mavutil
14
from pymavlink.rotmat import Vector3
15
16
import vehicle_test_suite
17
from vehicle_test_suite import Test
18
from vehicle_test_suite import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException
19
20
import operator
21
22
23
# get location of scripts
24
testdir = os.path.dirname(os.path.realpath(__file__))
25
WIND = "0,180,0.2" # speed,direction,variance
26
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
27
28
29
class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
30
31
@staticmethod
32
def get_not_armable_mode_list():
33
return []
34
35
@staticmethod
36
def get_not_disarmed_settable_modes_list():
37
return []
38
39
@staticmethod
40
def get_no_position_not_settable_modes_list():
41
return []
42
43
@staticmethod
44
def get_position_armable_modes_list():
45
return []
46
47
@staticmethod
48
def get_normal_armable_modes_list():
49
return []
50
51
def vehicleinfo_key(self):
52
return 'ArduPlane'
53
54
def default_frame(self):
55
return "quadplane"
56
57
def test_filepath(self):
58
return os.path.realpath(__file__)
59
60
def sitl_start_location(self):
61
return SITL_START_LOCATION
62
63
def default_speedup(self):
64
'''QuadPlane seems to be race-free'''
65
return 100
66
67
def log_name(self):
68
return "QuadPlane"
69
70
def set_current_test_name(self, name):
71
self.current_test_name_directory = "ArduPlane_Tests/" + name + "/"
72
73
def apply_defaultfile_parameters(self):
74
# plane passes in a defaults_filepath in place of applying
75
# parameters afterwards.
76
pass
77
78
def defaults_filepath(self):
79
return self.model_defaults_filepath(self.frame)
80
81
def is_plane(self):
82
return True
83
84
def get_stick_arming_channel(self):
85
return int(self.get_parameter("RCMAP_YAW"))
86
87
def get_disarm_delay(self):
88
return int(self.get_parameter("LAND_DISARMDELAY"))
89
90
def set_autodisarm_delay(self, delay):
91
self.set_parameter("LAND_DISARMDELAY", delay)
92
93
def AirMode(self):
94
"""Check that plane.air_mode turns on and off as required"""
95
self.progress("########## Testing AirMode operation")
96
self.set_parameter("AHRS_EKF_TYPE", 10)
97
self.change_mode('QSTABILIZE')
98
self.wait_ready_to_arm()
99
100
"""
101
SPIN_ARM and SPIN_MIN default to 0.10 and 0.15
102
when armed with zero throttle in AirMode, motor PWM should be at SPIN_MIN
103
If AirMode is off, motor PWM will drop to SPIN_ARM
104
"""
105
106
self.progress("Verify that SERVO5 is Motor1 (default)")
107
motor1_servo_function_lp = 33
108
if (self.get_parameter('SERVO5_FUNCTION') != motor1_servo_function_lp):
109
raise PreconditionFailedException("SERVO5_FUNCTION not %d" % motor1_servo_function_lp)
110
111
self.progress("Verify that flightmode channel is 5 (default)")
112
default_fltmode_ch = 5
113
if (self.get_parameter("FLTMODE_CH") != default_fltmode_ch):
114
raise PreconditionFailedException("FLTMODE_CH not %d" % default_fltmode_ch)
115
116
"""When disarmed, motor PWM will drop to min_pwm"""
117
min_pwm = self.get_parameter("Q_M_PWM_MIN")
118
119
self.progress("Verify Motor1 is at min_pwm when disarmed")
120
self.wait_servo_channel_value(5, min_pwm, comparator=operator.eq)
121
122
armdisarm_option = 154
123
arm_ch = 8
124
self.set_parameter("RC%d_OPTION" % arm_ch, armdisarm_option)
125
self.progress("Configured RC%d as ARMDISARM switch" % arm_ch)
126
127
"""arm with GCS, record Motor1 SPIN_ARM PWM output and disarm"""
128
spool_delay = self.get_parameter("Q_M_SPOOL_TIME") + 0.25
129
self.zero_throttle()
130
self.arm_vehicle()
131
self.progress("Waiting for Motor1 to spool up to SPIN_ARM")
132
self.delay_sim_time(spool_delay)
133
spin_arm_pwm = self.wait_servo_channel_value(5, min_pwm, comparator=operator.gt)
134
self.progress("spin_arm_pwm: %d" % spin_arm_pwm)
135
self.disarm_vehicle()
136
137
"""arm with switch, record Motor1 SPIN_MIN PWM output and disarm"""
138
self.set_rc(8, 2000)
139
self.delay_sim_time(spool_delay)
140
self.progress("Waiting for Motor1 to spool up to SPIN_MIN")
141
spin_min_pwm = self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.gt)
142
self.progress("spin_min_pwm: %d" % spin_min_pwm)
143
self.set_rc(8, 1000)
144
145
if (spin_arm_pwm >= spin_min_pwm):
146
raise PreconditionFailedException("SPIN_MIN pwm not greater than SPIN_ARM pwm")
147
148
self.start_subtest("Test auxswitch arming with AirMode Switch")
149
for mode in ('QSTABILIZE', 'QACRO'):
150
"""verify that arming with switch results in higher PWM output"""
151
self.progress("Testing %s mode" % mode)
152
self.change_mode(mode)
153
self.zero_throttle()
154
self.progress("Arming with switch at zero throttle")
155
self.arm_motors_with_switch(arm_ch)
156
self.progress("Waiting for Motor1 to speed up")
157
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
158
159
self.progress("Verify that rudder disarm is disabled")
160
try:
161
self.disarm_motors_with_rc_input()
162
except NotAchievedException:
163
pass
164
if not self.armed():
165
raise NotAchievedException("Rudder disarm not disabled")
166
167
self.progress("Disarming with switch")
168
self.disarm_motors_with_switch(arm_ch)
169
self.progress("Waiting for Motor1 to stop")
170
self.wait_servo_channel_value(5, min_pwm, comparator=operator.le)
171
self.wait_ready_to_arm()
172
173
self.start_subtest("Verify that arming with switch does not spin motors in other modes")
174
# disable compass magnetic field arming check that is triggered by the simulated lean of vehicle
175
# this is required because adjusting the AHRS_TRIM values only affects the IMU and not external compasses
176
arming_magthresh = self.get_parameter("ARMING_MAGTHRESH")
177
self.set_parameter("ARMING_MAGTHRESH", 0)
178
# introduce a large attitude error to verify that stabilization is not active
179
ahrs_trim_x = self.get_parameter("AHRS_TRIM_X")
180
self.set_parameter("AHRS_TRIM_X", math.radians(-60))
181
self.wait_roll(60, 1)
182
# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE and QLAND and QRTL
183
# QRTL and QLAND aren't tested because we can't arm in that mode
184
for mode in (
185
'ACRO',
186
'AUTOTUNE',
187
'AVOID_ADSB',
188
'CIRCLE',
189
'CRUISE',
190
'FBWA',
191
'FBWB',
192
'GUIDED',
193
'LOITER',
194
'QHOVER',
195
'QLOITER',
196
'STABILIZE',
197
'TRAINING',
198
):
199
self.progress("Testing %s mode" % mode)
200
self.change_mode(mode)
201
self.zero_throttle()
202
self.progress("Arming with switch at zero throttle")
203
self.arm_motors_with_switch(arm_ch)
204
self.progress("Waiting for Motor1 to (not) speed up")
205
self.delay_sim_time(spool_delay)
206
self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.le)
207
self.wait_servo_channel_value(6, spin_arm_pwm, comparator=operator.le)
208
self.wait_servo_channel_value(7, spin_arm_pwm, comparator=operator.le)
209
self.wait_servo_channel_value(8, spin_arm_pwm, comparator=operator.le)
210
211
self.progress("Disarming with switch")
212
self.disarm_motors_with_switch(arm_ch)
213
self.progress("Waiting for Motor1 to stop")
214
self.wait_servo_channel_value(5, min_pwm, comparator=operator.le)
215
self.wait_ready_to_arm()
216
# remove attitude error and reinstance compass arming check
217
self.set_parameter("AHRS_TRIM_X", ahrs_trim_x)
218
self.set_parameter("ARMING_MAGTHRESH", arming_magthresh)
219
220
self.start_subtest("verify that AIRMODE auxswitch turns airmode on/off while armed")
221
"""set RC7_OPTION to AIRMODE"""
222
option_airmode = 84
223
self.set_parameter("RC7_OPTION", option_airmode)
224
225
for mode in ('QSTABILIZE', 'QACRO'):
226
self.progress("Testing %s mode" % mode)
227
self.change_mode(mode)
228
self.zero_throttle()
229
self.progress("Arming with GCS at zero throttle")
230
self.arm_vehicle()
231
232
self.progress("Turn airmode on with auxswitch")
233
self.set_rc(7, 2000)
234
self.progress("Waiting for Motor1 to speed up")
235
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
236
237
self.progress("Turn airmode off with auxswitch")
238
self.set_rc(7, 1000)
239
self.progress("Waiting for Motor1 to slow down")
240
self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.le)
241
self.disarm_vehicle()
242
self.wait_ready_to_arm()
243
244
self.start_subtest("Test GCS arming")
245
for mode in ('QSTABILIZE', 'QACRO'):
246
self.progress("Testing %s mode" % mode)
247
self.change_mode(mode)
248
self.zero_throttle()
249
self.progress("Arming with GCS at zero throttle")
250
self.arm_vehicle()
251
252
self.progress("Turn airmode on with auxswitch")
253
self.set_rc(7, 2000)
254
self.progress("Waiting for Motor1 to speed up")
255
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
256
257
self.disarm_vehicle_expect_fail()
258
self.arm_vehicle()
259
260
self.progress("Verify that airmode is still on")
261
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
262
self.disarm_vehicle(force=True)
263
self.wait_ready_to_arm()
264
265
def TestMotorMask(self):
266
"""Check operation of output_motor_mask"""
267
"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""
268
if not (int(self.get_parameter('Q_TILT_MASK')) & 1):
269
self.progress("output_motor_mask not in use")
270
return
271
self.progress("Testing output_motor_mask")
272
self.wait_ready_to_arm()
273
274
"""Default channel for Motor1 is 5"""
275
self.progress('Assert that SERVO5 is Motor1')
276
assert 33 == self.get_parameter('SERVO5_FUNCTION')
277
278
modes = ('MANUAL', 'FBWA', 'QHOVER')
279
for mode in modes:
280
self.progress("Testing %s mode" % mode)
281
self.change_mode(mode)
282
self.arm_vehicle()
283
self.progress("Raising throttle")
284
self.set_rc(3, 1800)
285
self.progress("Waiting for Motor1 to start")
286
self.wait_servo_channel_value(5, 1100, comparator=operator.gt)
287
288
self.set_rc(3, 1000)
289
self.disarm_vehicle()
290
self.wait_ready_to_arm()
291
292
def fly_mission(self, filename, fence=None, height_accuracy=-1):
293
"""Fly a mission from a file."""
294
self.progress("Flying mission %s" % filename)
295
num_wp = self.load_mission(filename)
296
if self.mavproxy is not None:
297
self.mavproxy.send('wp list\n')
298
if fence is not None:
299
self.load_fence(fence)
300
if self.mavproxy is not None:
301
self.mavproxy.send('fence list\n')
302
# self.install_terrain_handlers_context()
303
self.change_mode('AUTO')
304
self.wait_ready_to_arm()
305
self.arm_vehicle()
306
self.wait_waypoint(1, num_wp-1)
307
self.wait_disarmed(timeout=120) # give quadplane a long time to land
308
309
def EXTENDED_SYS_STATE_SLT(self):
310
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10)
311
self.change_mode("QHOVER")
312
self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,
313
mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)
314
self.change_mode("FBWA")
315
self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,
316
mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)
317
self.change_mode("QHOVER")
318
319
self.wait_ready_to_arm()
320
self.arm_vehicle()
321
322
# should not change just because we arm:
323
self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,
324
mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)
325
self.change_mode("MANUAL")
326
self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,
327
mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)
328
self.change_mode("QHOVER")
329
330
self.progress("Taking off")
331
self.set_rc(3, 1750)
332
self.wait_altitude(1, 5, relative=True)
333
self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,
334
mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)
335
self.wait_altitude(10, 15, relative=True)
336
337
self.progress("Transitioning to fixed wing")
338
self.change_mode("FBWA")
339
self.set_rc(3, 1900) # apply spurs
340
self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_TRANSITION_TO_FW,
341
mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)
342
self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,
343
mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)
344
345
self.progress("Transitioning to multicopter")
346
self.set_rc(3, 1500) # apply reins
347
self.change_mode("QHOVER")
348
# for a standard quadplane there is no transition-to-mc stage.
349
# tailsitters do have such a state.
350
self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,
351
mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)
352
self.change_mode("QLAND")
353
self.wait_altitude(0, 2, relative=True, timeout=60)
354
self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,
355
mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,
356
timeout=30)
357
self.mav.motors_disarmed_wait()
358
359
def EXTENDED_SYS_STATE(self):
360
'''Check extended sys state works'''
361
self.EXTENDED_SYS_STATE_SLT()
362
363
def QAUTOTUNE(self):
364
'''test Plane QAutoTune mode'''
365
366
# adjust tune so QAUTOTUNE can cope
367
self.set_parameters({
368
"Q_AUTOTUNE_AGGR": 0.1,
369
"Q_AUTOTUNE_MIN_D": 0.0004,
370
"Q_A_RAT_RLL_P" : 0.15,
371
"Q_A_RAT_RLL_I" : 0.25,
372
"Q_A_RAT_RLL_D" : 0.002,
373
"Q_A_RAT_PIT_P" : 0.15,
374
"Q_A_RAT_PIT_I" : 0.25,
375
"Q_A_RAT_PIT_D" : 0.002,
376
"Q_A_RAT_YAW_P" : 0.18,
377
"Q_A_RAT_YAW_I" : 0.018,
378
"Q_A_ANG_RLL_P" : 4.5,
379
"Q_A_ANG_PIT_P" : 4.5,
380
})
381
382
# this is a list of all parameters modified by QAUTOTUNE. Set
383
# them so that when the context is popped we get the original
384
# values back:
385
parameter_values = self.get_parameters([
386
"Q_A_RAT_RLL_P",
387
"Q_A_RAT_RLL_I",
388
"Q_A_RAT_RLL_D",
389
"Q_A_ANG_RLL_P",
390
"Q_A_ACCEL_R_MAX",
391
"Q_A_RAT_PIT_P",
392
"Q_A_RAT_PIT_I",
393
"Q_A_RAT_PIT_D",
394
"Q_A_ANG_PIT_P",
395
"Q_A_ACCEL_P_MAX",
396
"Q_A_RAT_YAW_P",
397
"Q_A_RAT_YAW_I",
398
"Q_A_RAT_YAW_FLTE",
399
"Q_A_ANG_YAW_P",
400
"Q_A_ACCEL_Y_MAX",
401
])
402
self.set_parameters(parameter_values)
403
404
self.takeoff(15, mode='GUIDED')
405
self.set_rc(3, 1500)
406
self.change_mode("QLOITER")
407
tstart = self.get_sim_time()
408
self.context_collect('STATUSTEXT')
409
self.change_mode("QAUTOTUNE")
410
self.wait_text(
411
"AutoTune: (Success|Failed to level).*",
412
timeout=5000,
413
check_context=True,
414
regex=True,
415
)
416
if self.re_match.group(1) != "Success":
417
raise NotAchievedException("autotune did not succeed")
418
now = self.get_sim_time()
419
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
420
self.context_clear_collection('STATUSTEXT')
421
422
self.progress("Landing to save gains")
423
self.set_rc(3, 1200)
424
self.wait_speed_vector(
425
Vector3(float('nan'), float('nan'), 1.4),
426
timeout=5,
427
)
428
self.wait_speed_vector(
429
Vector3(0.0, 0.0, 0.0),
430
timeout=20,
431
)
432
distance = self.distance_to_home()
433
if distance > 20:
434
raise NotAchievedException("wandered from home (distance=%f)" %
435
(distance,))
436
self.set_rc(3, 1000)
437
tstart = self.get_sim_time()
438
while True:
439
now = self.get_sim_time_cached()
440
if now - tstart > 500:
441
raise NotAchievedException("Did not get success message")
442
self.send_mavlink_disarm_command()
443
try:
444
self.wait_text(
445
"AutoTune: Saved gains for Roll Pitch Yaw.*",
446
timeout=0.5,
447
check_context=True,
448
regex=True,
449
)
450
except AutoTestTimeoutException:
451
continue
452
break
453
454
self.wait_disarmed()
455
self.reboot_sitl() # far from home
456
457
def takeoff(self, height, mode, timeout=30):
458
"""climb to specified height and set throttle to 1500"""
459
self.set_current_waypoint(0, check_afterwards=False)
460
self.change_mode(mode)
461
self.wait_ready_to_arm()
462
self.arm_vehicle()
463
if mode == 'GUIDED':
464
self.user_takeoff(alt_min=height, timeout=timeout)
465
return
466
self.set_rc(3, 1800)
467
self.wait_altitude(height,
468
height+5,
469
relative=True,
470
timeout=timeout)
471
self.set_rc(3, 1500)
472
473
def do_RTL(self):
474
self.change_mode("QRTL")
475
self.wait_altitude(-5, 1, relative=True, timeout=60)
476
self.wait_disarmed()
477
self.zero_throttle()
478
479
def fly_home_land_and_disarm(self, timeout=30):
480
self.context_push()
481
self.change_mode('LOITER')
482
self.set_parameter('RTL_AUTOLAND', 2)
483
filename = "QuadPlaneDalbyRTL.txt"
484
self.progress("Using %s to fly home" % filename)
485
self.load_generic_mission(filename)
486
self.send_cmd_do_set_mode("RTL")
487
self.wait_mode('AUTO')
488
self.wait_current_waypoint(4)
489
self.wait_statustext('Land descend started')
490
self.wait_statustext('Land final started', timeout=60)
491
self.wait_disarmed(timeout=timeout)
492
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
493
# the following command is accepted, but doesn't actually
494
# work! Should be able to remove check_afterwards!
495
self.set_current_waypoint(0, check_afterwards=False)
496
self.change_mode('MANUAL')
497
self.context_pop()
498
499
def wait_level_flight(self, accuracy=5, timeout=30):
500
"""Wait for level flight."""
501
tstart = self.get_sim_time()
502
self.progress("Waiting for level flight")
503
self.set_rc(1, 1500)
504
self.set_rc(2, 1500)
505
self.set_rc(4, 1500)
506
while self.get_sim_time_cached() < tstart + timeout:
507
m = self.assert_receive_message('ATTITUDE')
508
roll = math.degrees(m.roll)
509
pitch = math.degrees(m.pitch)
510
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
511
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
512
self.progress("Attained level flight")
513
return
514
raise NotAchievedException("Failed to attain level flight")
515
516
def fly_left_circuit(self):
517
"""Fly a left circuit, 200m on a side."""
518
self.mavproxy.send('switch 4\n')
519
self.change_mode('FBWA')
520
self.set_rc(3, 1700)
521
self.wait_level_flight()
522
523
self.progress("Flying left circuit")
524
# do 4 turns
525
for i in range(0, 4):
526
# hard left
527
self.progress("Starting turn %u" % i)
528
self.set_rc(1, 1000)
529
self.wait_heading(270 - (90*i), accuracy=10)
530
self.set_rc(1, 1500)
531
self.progress("Starting leg %u" % i)
532
self.wait_distance(100, accuracy=20)
533
self.progress("Circuit complete")
534
self.change_mode('QHOVER')
535
self.set_rc(3, 1100)
536
self.wait_altitude(10, 15,
537
relative=True,
538
timeout=60)
539
self.set_rc(3, 1500)
540
541
def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, fftLength=32, peakhz=None):
542
543
# find a motor peak
544
self.takeoff(10, mode="QHOVER")
545
546
hover_time = 15
547
tstart = self.get_sim_time()
548
self.progress("Hovering for %u seconds" % hover_time)
549
while self.get_sim_time_cached() < tstart + hover_time:
550
self.assert_receive_message('ATTITUDE')
551
vfr_hud = self.assert_receive_message('VFR_HUD')
552
tend = self.get_sim_time()
553
554
self.do_RTL()
555
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
556
557
# batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin
558
scale = 1000. / 1024.
559
sminhz = int(minhz * scale)
560
smaxhz = int(maxhz * scale)
561
freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz]
562
peakdb = numpy.amax(psd["X"][sminhz:smaxhz])
563
if peakdb < dblevel or (peakhz is not None and abs(freq - peakhz) / peakhz > 0.05):
564
raise NotAchievedException("No motor peak, found %fHz at %fdB" % (freq, peakdb))
565
else:
566
self.progress("motor peak %fHz, thr %f%%, %fdB" % (freq, vfr_hud.throttle, peakdb))
567
568
# we have a peak make sure that the FFT detected something close
569
# logging is at 10Hz
570
mlog = self.dfreader_for_current_onboard_log()
571
# accuracy is determined by sample rate and fft length, given our use of quinn we could probably use half of this
572
freqDelta = 1000. / fftLength
573
pkAvg = freq
574
freqs = []
575
576
while True:
577
m = mlog.recv_match(
578
type='FTN1',
579
blocking=True,
580
condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6))
581
if m is None:
582
break
583
freqs.append(m.PkAvg)
584
585
# peak within resolution of FFT length
586
pkAvg = numpy.median(numpy.asarray(freqs))
587
if abs(pkAvg - freq) > freqDelta:
588
raise NotAchievedException("FFT did not detect a motor peak at %f, found %f, wanted %f" % (dblevel, pkAvg, freq))
589
590
return freq
591
592
def GyroFFT(self):
593
"""Use dynamic harmonic notch to control motor noise."""
594
# basic gyro sample rate test
595
self.progress("Flying with gyro FFT - Gyro sample rate")
596
597
# magic tridge EKF type that dramatically speeds up the test
598
self.set_parameters({
599
"AHRS_EKF_TYPE": 10,
600
601
"INS_LOG_BAT_MASK": 3,
602
"INS_LOG_BAT_OPT": 0,
603
"INS_GYRO_FILTER": 100,
604
"LOG_BITMASK": 45054,
605
"LOG_DISARMED": 0,
606
"SIM_DRIFT_SPEED": 0,
607
"SIM_DRIFT_TIME": 0,
608
# enable a noisy motor peak
609
"SIM_GYR1_RND": 20,
610
# enabling FFT will also enable the arming check: self-testing the functionality
611
"FFT_ENABLE": 1,
612
"FFT_MINHZ": 80,
613
"FFT_MAXHZ": 350,
614
"FFT_SNR_REF": 10,
615
"FFT_WINDOW_SIZE": 128,
616
"FFT_WINDOW_OLAP": 0.75,
617
})
618
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
619
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
620
# a 250Hz peak should be detectable within 5%
621
self.set_parameters({
622
"SIM_VIB_FREQ_X": 250,
623
"SIM_VIB_FREQ_Y": 250,
624
"SIM_VIB_FREQ_Z": 250,
625
})
626
self.reboot_sitl()
627
628
# find a motor peak
629
self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)
630
631
# Step 2: inject actual motor noise and use the standard length FFT to track it
632
self.set_parameters({
633
"SIM_VIB_MOT_MAX": 350,
634
"FFT_WINDOW_SIZE": 32,
635
"FFT_WINDOW_OLAP": 0.5,
636
})
637
self.reboot_sitl()
638
# find a motor peak
639
freq = self.hover_and_check_matched_frequency(-15, 200, 300, 32)
640
641
# Step 3: add a FFT dynamic notch and check that the peak is squashed
642
self.set_parameters({
643
"INS_LOG_BAT_OPT": 2,
644
"INS_HNTCH_ENABLE": 1,
645
"INS_HNTCH_FREQ": freq,
646
"INS_HNTCH_REF": 1.0,
647
"INS_HNTCH_ATT": 50,
648
"INS_HNTCH_BW": freq/2,
649
"INS_HNTCH_MODE": 4,
650
})
651
self.reboot_sitl()
652
653
self.takeoff(10, mode="QHOVER")
654
hover_time = 15
655
ignore_bins = 20
656
657
self.progress("Hovering for %u seconds" % hover_time)
658
tstart = self.get_sim_time()
659
while self.get_sim_time_cached() < tstart + hover_time:
660
self.assert_receive_message('ATTITUDE')
661
tend = self.get_sim_time()
662
663
self.do_RTL()
664
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
665
freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins]
666
peakdB = numpy.amax(psd["X"][ignore_bins:])
667
if peakdB < -10:
668
self.progress("No motor peak, %f at %f dB" % (freq, peakdB))
669
else:
670
raise NotAchievedException("Detected peak at %f Hz of %.2f dB" % (freq, peakdB))
671
672
# Step 4: take off as a copter land as a plane, make sure we track
673
self.progress("Flying with gyro FFT - vtol to plane")
674
self.load_mission("quadplane-gyro-mission.txt")
675
if self.mavproxy is not None:
676
self.mavproxy.send('wp list\n')
677
self.change_mode('AUTO')
678
self.wait_ready_to_arm()
679
self.arm_vehicle()
680
self.wait_waypoint(1, 7, max_dist=60, timeout=1200)
681
self.wait_disarmed(timeout=120) # give quadplane a long time to land
682
683
# prevent update parameters from messing with the settings when we pop the context
684
self.set_parameter("FFT_ENABLE", 0)
685
self.reboot_sitl()
686
687
def PIDTuning(self):
688
'''Test PID Tuning'''
689
self.change_mode("FBWA") # we don't update PIDs in MANUAL
690
super(AutoTestQuadPlane, self).PIDTuning()
691
692
def ParameterChecks(self):
693
'''basic parameter checks'''
694
self.test_parameter_checks_poscontrol("Q_P")
695
696
self.context_push()
697
self.set_parameters({
698
"Q_RTL_MODE": 1,
699
"RTL_AUTOLAND": 2,
700
})
701
self.assert_prearm_failure("unset one of RTL_AUTOLAND or Q_RTL_MODE")
702
self.context_pop()
703
self.wait_ready_to_arm()
704
705
def rc_defaults(self):
706
ret = super(AutoTestQuadPlane, self).rc_defaults()
707
ret[3] = 1000
708
return ret
709
710
def default_mode(self):
711
return "MANUAL"
712
713
def disabled_tests(self):
714
return {
715
"FRSkyPassThrough": "Currently failing",
716
"CPUFailsafe": "servo channel values not scaled like ArduPlane",
717
"GyroFFT": "flapping test",
718
"ConfigErrorLoop": "failing because RC values not settable",
719
}
720
721
def BootInAUTO(self):
722
'''Test behaviour when booting in auto'''
723
self.load_mission("mission.txt")
724
self.set_parameters({
725
})
726
self.set_rc(5, 1000)
727
self.wait_mode('AUTO')
728
self.reboot_sitl()
729
self.wait_ready_to_arm()
730
self.delay_sim_time(20)
731
self.assert_current_waypoint(1)
732
self.arm_vehicle()
733
self.wait_altitude(9, 11, relative=True) # value from mission file is 10
734
distance = self.distance_to_home()
735
# this distance check is very, very loose. At time of writing
736
# the vehicle actually pitches ~6 degrees on trakeoff,
737
# wandering over 1m.
738
if distance > 2:
739
raise NotAchievedException("wandered from home (distance=%f)" %
740
(distance,))
741
self.change_mode('QLAND')
742
self.wait_disarmed(timeout=60)
743
744
def PilotYaw(self):
745
'''Test pilot yaw in various modes'''
746
self.takeoff(10, mode="QLOITER")
747
self.set_parameter("STICK_MIXING", 0)
748
self.set_rc(4, 1700)
749
for mode in "QLOITER", "QHOVER":
750
self.wait_heading(45)
751
self.wait_heading(90)
752
self.wait_heading(180)
753
self.wait_heading(275)
754
self.set_rc(4, 1500)
755
self.do_RTL()
756
757
def FwdThrInVTOL(self):
758
'''test use of fwd motor throttle into wind'''
759
self.set_parameters({"SIM_WIND_SPD": 25, # need very strong wind for this test
760
"SIM_WIND_DIR": 360,
761
"Q_WVANE_ENABLE": 1,
762
"Q_WVANE_GAIN": 1,
763
"STICK_MIXING": 0,
764
"Q_FWD_THR_USE": 2})
765
766
self.takeoff(10, mode="QLOITER")
767
self.set_rc(2, 1000)
768
self.delay_sim_time(10)
769
# Check that it is using some forward throttle
770
fwd_thr_pwm = self.get_servo_channel_value(3)
771
if fwd_thr_pwm < 1150 :
772
raise NotAchievedException("fwd motor pwm command low, want >= 1150 got %f" % (fwd_thr_pwm))
773
# check that pitch is on limit
774
m = self.assert_receive_message('ATTITUDE')
775
pitch = math.degrees(m.pitch)
776
if abs(pitch + 3.0) > 0.5 :
777
raise NotAchievedException("pitch should be -3.0 +- 0.5 deg, got %f" % (pitch))
778
self.set_rc(2, 1500)
779
self.delay_sim_time(5)
780
loc1 = self.mav.location()
781
self.set_parameter("SIM_ENGINE_FAIL", 1 << 2) # simulate a complete loss of forward motor thrust
782
self.delay_sim_time(20)
783
self.change_mode('QLAND')
784
self.wait_disarmed(timeout=60)
785
loc2 = self.mav.location()
786
position_drift = self.get_distance(loc1, loc2)
787
if position_drift > 5.0 :
788
raise NotAchievedException("position drift high, want < 5.0 m got %f m" % (position_drift))
789
790
def Weathervane(self):
791
'''test nose-into-wind functionality'''
792
# We test nose into wind code paths and yaw direction in copter autotest,
793
# so we shall test the side into wind yaw direction and plane code paths here.
794
self.set_parameters({"SIM_WIND_SPD": 10,
795
"SIM_WIND_DIR": 240,
796
"Q_WVANE_ENABLE": 3, # WVANE_ENABLE = 3 gives direction of side into wind
797
"Q_WVANE_GAIN": 3,
798
"STICK_MIXING": 0})
799
800
self.takeoff(10, mode="QLOITER")
801
802
# Turn aircraft to heading 90 deg
803
self.set_rc(4, 1700)
804
self.wait_heading(90)
805
self.set_rc(4, 1500)
806
807
# Now wait for weathervaning to activate and turn side-on to wind at 240 deg therefore heading 150 deg
808
self.wait_heading(150, accuracy=5, timeout=180)
809
810
self.do_RTL()
811
812
def CPUFailsafe(self):
813
'''In lockup Plane should copy RC inputs to RC outputs'''
814
self.plane_CPUFailsafe()
815
816
def QAssist(self):
817
'''QuadPlane Assist tests'''
818
self.takeoff(50, mode="QHOVER", timeout=120)
819
self.set_rc(3, 1800)
820
self.change_mode("FBWA")
821
822
# disable stall prevention so roll angle is not limited
823
self.set_parameter("STALL_PREVENTION", 0)
824
825
thr_min_pwm = self.get_parameter("Q_M_PWM_MIN")
826
lim_roll_deg = self.get_parameter("ROLL_LIMIT_DEG")
827
lim_pitch_down_deg = self.get_parameter("PTCH_LIM_MIN_DEG")
828
lim_pitch_up_deg = self.get_parameter("PTCH_LIM_MAX_DEG")
829
self.progress("Waiting for motors to stop (transition completion)")
830
self.wait_servo_channel_value(5,
831
thr_min_pwm,
832
timeout=30,
833
comparator=operator.eq)
834
self.delay_sim_time(5)
835
self.wait_servo_channel_value(5,
836
thr_min_pwm,
837
timeout=30,
838
comparator=operator.eq)
839
self.progress("Stopping forward motor to kill airspeed below limit")
840
self.set_rc(3, 1000)
841
self.progress("Waiting for qassist to kick in")
842
self.wait_servo_channel_value(5, 1400, timeout=30, comparator=operator.gt)
843
self.progress("Move forward again, check qassist stops")
844
self.set_rc(3, 1800)
845
self.progress("Checking qassist stops")
846
self.wait_servo_channel_value(5,
847
thr_min_pwm,
848
timeout=30,
849
comparator=operator.eq)
850
self.set_rc(3, 1300)
851
852
self.start_subtest("Test angle assist (roll)")
853
self.context_push()
854
self.context_collect('STATUSTEXT')
855
self.progress("Rolling over to %.0f degrees" % -lim_roll_deg)
856
self.set_rc(1, 1000)
857
self.wait_roll(-lim_roll_deg, 5)
858
self.progress("Killing aileron servo output to force qassist to help")
859
self.set_parameter("SERVO1_MIN", 1480)
860
self.set_parameter("SERVO1_MAX", 1480)
861
self.set_parameter("SERVO1_TRIM", 1480)
862
self.progress("Trying to roll over hard the other way")
863
self.set_rc(1, 2000)
864
self.progress("Waiting for qassist (angle) to kick in")
865
self.wait_servo_channel_value(5, 1100, timeout=30, comparator=operator.gt)
866
self.wait_statustext('Angle assist', check_context=True)
867
self.wait_roll(lim_roll_deg, 5)
868
self.context_pop()
869
self.set_rc(1, 1500)
870
self.progress("Checking qassist stops")
871
# we must push RC3 here or the translational drag from the
872
# motors keeps us at ~17m/s, below the airspeed assist speed!
873
self.set_rc(3, 1800)
874
self.wait_servo_channel_value(
875
5,
876
thr_min_pwm,
877
timeout=60,
878
comparator=operator.eq,
879
)
880
self.set_rc(3, 1300)
881
882
self.start_subtest("Test angle assist (pitch-down)")
883
self.context_push()
884
self.context_collect('STATUSTEXT')
885
self.progress("Pitching down to %.0f degrees" % lim_pitch_down_deg)
886
self.set_rc(2, 1000)
887
self.wait_pitch(lim_pitch_down_deg, accuracy=5)
888
self.progress("Killing elevator servo output to force qassist to help")
889
self.set_parameters({
890
"SERVO2_MIN": 1480,
891
"SERVO2_MAX": 1480,
892
"SERVO2_TRIM": 1480,
893
})
894
self.progress("Trying to pitch up hard")
895
self.set_rc(2, 2000)
896
self.progress("Waiting for qassist (angle) to kick in")
897
self.wait_servo_channel_value(5, 1100, timeout=30, comparator=operator.gt)
898
self.wait_statustext('Angle assist', check_context=True)
899
self.set_rc(2, 1500)
900
self.wait_pitch(0, accuracy=5)
901
self.context_pop()
902
self.progress("Checking qassist stops")
903
# we must push RC3 here or the translational drag from the
904
# motors keeps us at ~17m/s, below the airspeed assist speed!
905
self.set_rc(3, 1800)
906
self.wait_servo_channel_value(
907
5,
908
thr_min_pwm,
909
timeout=30,
910
comparator=operator.eq,
911
)
912
self.set_rc(3, 1300)
913
914
self.start_subtest("Test angle assist (pitch-up)")
915
self.context_push()
916
self.context_collect('STATUSTEXT')
917
self.progress("Pitching up to %.0f degrees" % lim_pitch_up_deg)
918
self.set_rc(3, 2000)
919
self.delay_sim_time(5)
920
self.change_mode('MANUAL')
921
self.context_push()
922
self.set_parameter("SIM_SPEEDUP", 1)
923
self.set_rc(2, 1550)
924
self.wait_pitch(lim_pitch_up_deg+5, accuracy=5)
925
self.context_pop()
926
self.progress("Killing elevator servo output to force qassist to help")
927
servo2_out = self.get_servo_channel_value(2)
928
self.set_parameters({
929
"SERVO2_MIN": servo2_out,
930
"SERVO2_MAX": servo2_out,
931
"SERVO2_TRIM": servo2_out,
932
})
933
self.change_mode('FBWA')
934
self.progress("Trying to pitch down hard")
935
self.set_rc(2, 1000)
936
self.progress("Waiting for qassist (angle) to kick in")
937
self.wait_servo_channel_value(5, 1100, timeout=30, comparator=operator.gt)
938
self.wait_statustext('Angle assist', check_context=True)
939
self.set_rc(2, 1500)
940
self.wait_pitch(0, accuracy=5)
941
self.context_pop()
942
self.progress("Checking qassist stops")
943
# we must push RC3 here or the translational drag from the
944
# motors keeps us at ~17m/s, below the airspeed assist speed!
945
self.set_rc(3, 1800)
946
self.wait_servo_channel_value(
947
5,
948
thr_min_pwm,
949
timeout=30,
950
comparator=operator.eq,
951
)
952
self.set_rc(3, 1300)
953
954
# Test alt assist, climb to 60m and set assist alt to 50m
955
self.context_push()
956
guided_loc = self.home_relative_loc_ne(0, 0)
957
guided_loc.alt = 60
958
self.change_mode("GUIDED")
959
self.send_do_reposition(guided_loc)
960
self.wait_altitude(58, 62, relative=True, timeout=120)
961
self.set_parameter("Q_ASSIST_ALT", 50)
962
963
# Try and descent to 40m
964
guided_loc.alt = 40
965
self.send_do_reposition(guided_loc)
966
967
# Expect alt assist to kick in, eg "Alt assist 48.9m"
968
self.wait_statustext(r"Alt assist \d*.\d*m", regex=True, timeout=100)
969
970
# Test transition timeout, should switch to QRTL
971
self.set_parameter("Q_TRANS_FAIL_ACT", 1)
972
self.set_parameter("Q_TRANS_FAIL", 10)
973
self.wait_mode("QRTL")
974
975
self.context_pop()
976
977
self.wait_disarmed(timeout=200)
978
979
def LoiterAltQLand(self):
980
'''test loitering and qland with terrain involved'''
981
self.LoiterAltQLand_Terrain(
982
home="LakeGeorgeLookout",
983
ofs_n=0,
984
ofs_e=300,
985
)
986
# self.LoiterAltQLand_Terrain(
987
# home="KalaupapaCliffs",
988
# ofs_n=500,
989
# ofs_e=500,
990
# )
991
self.LoiterAltQLand_Relative()
992
993
def LoiterAltQLand_Relative(self):
994
'''test failsafe where vehicle loiters in fixed-wing mode to a
995
specific altitude then changes mode to QLAND'''
996
self.set_parameters({
997
'BATT_MONITOR': 4, # LoiterAltQLand
998
'BATT_FS_LOW_ACT': 6, # LoiterAltQLand
999
})
1000
self.reboot_sitl()
1001
takeoff_alt = 5
1002
self.takeoff(takeoff_alt, mode='QLOITER')
1003
loc = self.mav.location()
1004
self.location_offset_ne(loc, 500, 500)
1005
new_alt = 100
1006
initial_altitude = self.get_altitude(relative=False, timeout=2)
1007
self.run_cmd_int(
1008
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1009
0,
1010
1, # reposition flags; 1 means "change to guided"
1011
0,
1012
0,
1013
int(loc.lat * 1e7),
1014
int(loc.lng * 1e7),
1015
new_alt, # alt
1016
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
1017
)
1018
self.wait_altitude(
1019
new_alt-1,
1020
new_alt+1,
1021
timeout=60,
1022
relative=True,
1023
minimum_duration=10)
1024
self.wait_location(loc, timeout=120, accuracy=100)
1025
self.progress("Triggering failsafe")
1026
self.set_parameter('BATT_LOW_VOLT', 50)
1027
self.wait_mode(25) # LoiterAltQLand
1028
self.drain_mav()
1029
m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)
1030
q_rtl_alt = self.get_parameter('Q_RTL_ALT')
1031
expected_alt = initial_altitude - takeoff_alt + q_rtl_alt
1032
1033
if abs(m.alt - expected_alt) > 20:
1034
raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %
1035
(expected_alt, m.alt))
1036
self.assert_mode('LOITERALTQLAND')
1037
self.wait_mode('QLAND')
1038
alt = self.get_altitude(relative=True)
1039
if abs(alt - q_rtl_alt) > 2:
1040
raise NotAchievedException("qland too late; want=%f got=%f" %
1041
(alt, q_rtl_alt))
1042
1043
self.wait_disarmed(timeout=300)
1044
1045
def LoiterAltQLand_Terrain(self,
1046
home=None,
1047
ofs_n=None,
1048
ofs_e=None,
1049
reposition_alt=100):
1050
'''test failsafe where vehicle loiters in fixed-wing mode to a
1051
specific altitude then changes mode to QLAND'''
1052
self.context_push()
1053
self.install_terrain_handlers_context()
1054
self.set_parameters({
1055
'BATT_MONITOR': 4, # LoiterAltQLand
1056
'BATT_FS_LOW_ACT': 6, # LoiterAltQLand
1057
'TERRAIN_FOLLOW': 1, # enabled in all modes
1058
})
1059
self.customise_SITL_commandline(
1060
["--home", home]
1061
)
1062
takeoff_alt = 5
1063
self.takeoff(takeoff_alt, mode='QLOITER')
1064
loc = self.mav.location()
1065
self.location_offset_ne(loc, ofs_n, ofs_e)
1066
initial_altitude = self.get_altitude(relative=False, timeout=2)
1067
self.run_cmd_int(
1068
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1069
0,
1070
1, # reposition flags; 1 means "change to guided"
1071
0,
1072
0,
1073
int(loc.lat * 1e7),
1074
int(loc.lng * 1e7),
1075
reposition_alt, # alt
1076
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
1077
)
1078
self.wait_altitude(
1079
reposition_alt-1,
1080
reposition_alt+1,
1081
timeout=60,
1082
relative=True,
1083
minimum_duration=10)
1084
1085
self.wait_location(loc, timeout=500, accuracy=100)
1086
1087
self.progress("Triggering failsafe")
1088
self.set_parameter('BATT_LOW_VOLT', 50)
1089
self.wait_mode(25) # LoiterAltQLand
1090
terrain_alt = self.get_terrain_height(verbose=True)
1091
self.drain_mav()
1092
m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)
1093
q_rtl_alt = self.get_parameter('Q_RTL_ALT')
1094
expected_alt = terrain_alt + q_rtl_alt
1095
1096
if abs(m.alt - expected_alt) > 20:
1097
raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %
1098
(expected_alt, m.alt))
1099
self.assert_mode('LOITERALTQLAND')
1100
self.wait_mode('QLAND')
1101
alt = initial_altitude + self.get_altitude(relative=True)
1102
if abs(alt - expected_alt) > 10:
1103
raise NotAchievedException("qland too late; want=%f got=%f" %
1104
(expected_alt, alt))
1105
1106
self.wait_disarmed(timeout=300)
1107
self.zero_throttle()
1108
self.reset_SITL_commandline()
1109
self.context_pop()
1110
1111
def GUIDEDToAUTO(self):
1112
'''Test using GUIDED mode for takeoff before shifting to auto'''
1113
self.load_mission("mission.txt")
1114
self.takeoff(30, mode='GUIDED')
1115
1116
# extra checks would go here
1117
self.assert_not_receiving_message('CAMERA_FEEDBACK')
1118
1119
self.change_mode('AUTO')
1120
self.wait_current_waypoint(3)
1121
self.change_mode('QRTL')
1122
self.wait_disarmed(timeout=240)
1123
1124
def Tailsitter(self):
1125
'''tailsitter test'''
1126
self.set_parameter('Q_FRAME_CLASS', 10)
1127
self.set_parameter('Q_ENABLE', 1)
1128
self.set_parameter('Q_TAILSIT_ENABLE', 1)
1129
1130
self.reboot_sitl()
1131
self.wait_ready_to_arm()
1132
value_before = self.get_servo_channel_value(3)
1133
self.progress("Before: %u" % value_before)
1134
self.change_mode('QHOVER')
1135
tstart = self.get_sim_time()
1136
while True:
1137
now = self.get_sim_time_cached()
1138
if now - tstart > 60:
1139
break
1140
value_after = self.get_servo_channel_value(3)
1141
self.progress("After: t=%f output=%u" % ((now - tstart), value_after))
1142
if value_before != value_after:
1143
raise NotAchievedException("Changed throttle output on mode change to QHOVER")
1144
self.disarm_vehicle()
1145
1146
def CopterTailsitter(self):
1147
'''copter tailsitter test'''
1148
self.customise_SITL_commandline(
1149
[],
1150
defaults_filepath=self.model_defaults_filepath('quadplane-copter_tailsitter'),
1151
model="quadplane-copter_tailsitter",
1152
wipe=True,
1153
)
1154
1155
self.reboot_sitl()
1156
self.wait_ready_to_arm()
1157
self.takeoff(60, mode='GUIDED')
1158
self.context_collect("STATUSTEXT")
1159
self.progress("Starting QLAND")
1160
self.change_mode("QLAND")
1161
self.wait_statustext("Rangefinder engaged", check_context=True)
1162
self.wait_disarmed(timeout=100)
1163
1164
def setup_ICEngine_vehicle(self):
1165
'''restarts SITL with an IC Engine setup'''
1166
model = "quadplane-ice"
1167
self.customise_SITL_commandline(
1168
[],
1169
model=model,
1170
defaults_filepath=self.model_defaults_filepath(model),
1171
wipe=False,
1172
)
1173
1174
def ICEngine(self):
1175
'''Test ICE Engine support'''
1176
rc_engine_start_chan = 11
1177
self.setup_ICEngine_vehicle()
1178
1179
self.wait_ready_to_arm()
1180
self.wait_rpm(1, 0, 0, minimum_duration=1)
1181
self.arm_vehicle()
1182
self.wait_rpm(1, 0, 0, minimum_duration=1)
1183
self.context_collect("STATUSTEXT")
1184
self.progress("Setting engine-start RC switch to HIGH")
1185
self.set_rc(rc_engine_start_chan, 2000)
1186
self.wait_statustext("Starting engine", check_context=True)
1187
self.wait_rpm(1, 300, 400, minimum_duration=1)
1188
self.progress("Setting engine-start RC switch to MID")
1189
self.set_rc(rc_engine_start_chan, 1500)
1190
self.progress("Setting full throttle")
1191
self.set_rc(3, 2000)
1192
self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40)
1193
self.progress("Setting min-throttle")
1194
self.set_rc(3, 1000)
1195
self.wait_rpm(1, 65, 75, minimum_duration=1)
1196
self.progress("Setting engine-start RC switch to LOW")
1197
self.set_rc(rc_engine_start_chan, 1000)
1198
self.wait_rpm(1, 0, 0, minimum_duration=1)
1199
# ICE provides forward thrust, which can make us think we're flying:
1200
self.disarm_vehicle(force=True)
1201
self.reboot_sitl()
1202
1203
self.start_subtest("Testing throttle out in manual mode")
1204
self.change_mode('MANUAL')
1205
self.set_rc(3, 1700)
1206
self.wait_servo_channel_value(3, 2000)
1207
self.set_parameter("ICE_OPTIONS", 4)
1208
# remember that throttle is reversed!
1209
self.wait_servo_channel_value(3, 1300)
1210
self.change_mode('FBWA')
1211
self.wait_servo_channel_value(3, 2000)
1212
1213
self.start_subtest("Testing automatic restart")
1214
# Limit start attempts to 4
1215
max_tries = 4
1216
self.set_parameter("ICE_STRT_MX_RTRY", max_tries)
1217
# Make the engine unable to run (by messing up the RPM sensor)
1218
rpm_chan = self.get_parameter("ICE_RPM_CHAN")
1219
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
1220
self.set_rc(rc_engine_start_chan, 2000)
1221
self.wait_statustext("Uncommanded engine stop")
1222
self.wait_statustext("Starting engine")
1223
# Restore the engine
1224
self.set_parameter("ICE_RPM_CHAN", rpm_chan)
1225
# Make sure the engine continues to run for the next 30 seconds
1226
try:
1227
self.wait_statustext("Uncommanded engine stop", timeout=30)
1228
# The desired result is for the wait_statustext raise AutoTestTimeoutException
1229
raise NotAchievedException("Engine stopped unexpectedly")
1230
except AutoTestTimeoutException:
1231
pass
1232
self.context_stop_collecting("STATUSTEXT")
1233
1234
self.start_subtest("Testing automatic starter attempt limit")
1235
# Try this test twice.
1236
# For the first run, since the engine has been running successfully in
1237
# the previous test for 30 seconds, the limit should reset. For the
1238
# second run, after commanding an engine stop, the limit should reset.
1239
for i in range(2):
1240
self.context_collect("STATUSTEXT")
1241
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
1242
self.set_rc(rc_engine_start_chan, 2000)
1243
self.wait_statustext("Engine max crank attempts reached", check_context=True, timeout=30)
1244
self.delay_sim_time(30) # wait for another 30 seconds to make sure the engine doesn't restart
1245
messages = self.context_get().collections["STATUSTEXT"]
1246
self.context_stop_collecting("STATUSTEXT")
1247
# check for the exact number of starter attempts
1248
attempts = 0
1249
for m in messages:
1250
if "Starting engine" == m.text:
1251
attempts += 1
1252
if attempts != max_tries:
1253
raise NotAchievedException(f"Run {i+1}: Expected {max_tries} attempts, got {attempts}")
1254
# Command an engine stop
1255
self.context_collect("STATUSTEXT")
1256
self.set_rc(rc_engine_start_chan, 1000)
1257
self.wait_statustext("ignition:0", check_context=True)
1258
self.context_stop_collecting("STATUSTEXT")
1259
1260
def ICEngineMission(self):
1261
'''Test ICE Engine Mission support'''
1262
rc_engine_start_chan = 11
1263
self.setup_ICEngine_vehicle()
1264
1265
self.load_mission("mission.txt")
1266
self.wait_ready_to_arm()
1267
self.set_rc(rc_engine_start_chan, 2000)
1268
self.arm_vehicle()
1269
self.change_mode('AUTO')
1270
self.wait_disarmed(timeout=300)
1271
1272
def ICEngineRPMGovernor(self):
1273
'''Test ICE idle and redline governor'''
1274
self.setup_ICEngine_vehicle()
1275
1276
# allow running while disarmed
1277
options = int(self.get_parameter("ICE_OPTIONS"))
1278
options |= 1 << 2
1279
self.set_parameter("ICE_OPTIONS", options)
1280
1281
self.start_subtest("ICEngine idle governor")
1282
# idle governor should work even in non-manual mode
1283
self.change_mode('QHOVER')
1284
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1)
1285
1286
deadband = 50
1287
self.set_parameter("ICE_IDLE_DB", deadband)
1288
# Test two RPM settings to make sure we don't pass as a fluke
1289
for idle_rpm in (1000, 1500):
1290
self.set_parameter("ICE_IDLE_RPM", idle_rpm)
1291
self.wait_rpm(
1292
1,
1293
idle_rpm - 1.1 * deadband,
1294
idle_rpm + 1.1 * deadband,
1295
timeout=60,
1296
minimum_duration=15,
1297
)
1298
1299
self.start_subtest("ICEngine redline governor")
1300
self.change_mode('MANUAL')
1301
# The redline governor only works properly while armed
1302
self.wait_ready_to_arm()
1303
self.arm_vehicle()
1304
self.set_rc(3, 2000)
1305
for redline_rpm in (6500, 6000):
1306
self.set_parameter("ICE_REDLINE_RPM", redline_rpm)
1307
self.wait_rpm(
1308
1,
1309
redline_rpm - 2 * deadband,
1310
redline_rpm,
1311
timeout=60,
1312
minimum_duration=15,
1313
)
1314
self.set_rc(3, 1000)
1315
self.disarm_vehicle()
1316
1317
def MAV_CMD_DO_ENGINE_CONTROL(self):
1318
'''test MAV_CMD_DO_ENGINE_CONTROL mavlink command'''
1319
1320
expected_idle_rpm_min = 65
1321
expected_idle_rpm_max = 75
1322
expected_starter_rpm_min = 345
1323
expected_starter_rpm_max = 355
1324
1325
rc_engine_start_chan = 11
1326
self.setup_ICEngine_vehicle()
1327
1328
self.wait_ready_to_arm()
1329
1330
for method in self.run_cmd, self.run_cmd_int:
1331
self.change_mode('MANUAL')
1332
self.set_rc(rc_engine_start_chan, 1500) # allow motor to run
1333
self.wait_rpm(1, 0, 0, minimum_duration=1)
1334
self.arm_vehicle()
1335
self.wait_rpm(1, 0, 0, minimum_duration=1)
1336
self.start_subtest("Start motor")
1337
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1)
1338
self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max)
1339
self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=10)
1340
1341
# starting the motor while it is running is failure
1342
# (probably wrong, but that's how this works):
1343
self.start_subtest("try start motor again")
1344
self.context_collect('STATUSTEXT')
1345
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)
1346
self.wait_statustext("already running", check_context=True)
1347
self.context_stop_collecting('STATUSTEXT')
1348
# shouldn't affect run state:
1349
self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=1)
1350
1351
self.start_subtest("Stop motor")
1352
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1353
self.wait_rpm(1, 0, 0, minimum_duration=1)
1354
1355
self.start_subtest("Stop motor (again)")
1356
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1357
self.wait_rpm(1, 0, 0, minimum_duration=1)
1358
1359
self.start_subtest("Check start chan control disable")
1360
old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan)
1361
self.set_rc(rc_engine_start_chan, 1000)
1362
self.delay_sim_time(1) # Make sure the RC change has registered
1363
self.context_collect('STATUSTEXT')
1364
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)
1365
self.wait_statustext("start control disabled", check_context=True)
1366
self.context_stop_collecting('STATUSTEXT')
1367
self.set_rc(rc_engine_start_chan, old_start_channel_value)
1368
self.wait_rpm(1, 0, 0, minimum_duration=1)
1369
1370
self.start_subtest("test start-at-height")
1371
self.wait_rpm(1, 0, 0, minimum_duration=1)
1372
self.context_collect('STATUSTEXT')
1373
method(
1374
mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL,
1375
p1=1, # start
1376
p3=15.5, # ... at 15.5 metres
1377
)
1378
self.wait_statustext("height set to 15.5m", check_context=True)
1379
self.wait_rpm(1, 0, 0, minimum_duration=2)
1380
1381
self.takeoff(20, mode='GUIDED')
1382
self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max, minimum_duration=1)
1383
self.wait_statustext("Engine running", check_context=True)
1384
self.context_stop_collecting('STATUSTEXT')
1385
1386
# stop the motor again:
1387
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1388
self.wait_rpm(1, 0, 0, minimum_duration=1)
1389
1390
self.change_mode('QLAND')
1391
self.wait_disarmed()
1392
1393
def Ship(self):
1394
'''Ensure we can take off from simulated ship'''
1395
self.context_push()
1396
self.set_parameters({
1397
'SIM_SHIP_ENABLE': 1,
1398
'SIM_SHIP_SPEED': 1, # the default of 3 will break this test
1399
})
1400
self.change_mode('QLOITER')
1401
self.wait_ready_to_arm()
1402
self.arm_vehicle()
1403
self.set_rc(3, 1700)
1404
# self.delay_sim_time(1)
1405
# self.send_debug_trap()
1406
# output here is a bit weird as we also receive altitude from
1407
# the simulated ship....
1408
self.wait_altitude(20, 30, relative=True)
1409
self.disarm_vehicle(force=True)
1410
self.context_pop()
1411
self.reboot_sitl()
1412
1413
def MidAirDisarmDisallowed(self):
1414
'''Check disarm behaviour in Q-mode'''
1415
self.start_subtest("Basic arm in qloiter")
1416
self.set_parameter("FLIGHT_OPTIONS", 0)
1417
self.change_mode('QLOITER')
1418
self.wait_ready_to_arm()
1419
self.arm_vehicle()
1420
self.disarm_vehicle()
1421
1422
self.context_push()
1423
self.start_subtest("Ensure disarming in q-modes on ground works")
1424
self.set_parameter("FLIGHT_OPTIONS", 1 << 11)
1425
self.arm_vehicle()
1426
self.disarm_vehicle() # should be OK as we're not flying yet
1427
self.context_pop()
1428
1429
self.start_subtest("Ensure no disarming mid-air")
1430
self.arm_vehicle()
1431
self.set_rc(3, 2000)
1432
self.wait_altitude(5, 50, relative=True)
1433
self.set_rc(3, 1000)
1434
disarmed = False
1435
try:
1436
self.disarm_vehicle()
1437
disarmed = True
1438
except ValueError as e:
1439
self.progress("Got %s" % repr(e))
1440
if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e):
1441
raise e
1442
if disarmed:
1443
raise NotAchievedException("Disarmed when we shouldn't have")
1444
1445
self.change_mode('QLAND')
1446
self.wait_disarmed()
1447
1448
self.start_subtest("Check we can disarm after a short period on the ground")
1449
self.takeoff(5, 'QHOVER')
1450
self.change_mode('QLAND')
1451
try:
1452
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10)
1453
self.wait_extended_sys_state(
1454
landed_state=mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,
1455
vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC,
1456
timeout=60
1457
)
1458
except Exception:
1459
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 0)
1460
raise
1461
1462
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1)
1463
self.disarm_vehicle()
1464
1465
def MAV_CMD_NAV_LOITER_TO_ALT(self, target_system=1, target_component=1):
1466
'''ensure consecutive loiter to alts work'''
1467
self.load_mission('mission.txt')
1468
self.change_mode('AUTO')
1469
self.wait_ready_to_arm()
1470
self.arm_vehicle()
1471
self.wait_current_waypoint(4, timeout=240)
1472
self.assert_altitude(120, accuracy=5, relative=True)
1473
self.delay_sim_time(30)
1474
self.assert_altitude(120, accuracy=5, relative=True)
1475
self.set_current_waypoint(5)
1476
self.wait_altitude(altitude_min=65, altitude_max=75, relative=True)
1477
if self.current_waypoint() != 5:
1478
raise NotAchievedException("Should pass 90m before passing waypoint 5")
1479
self.wait_disarmed(timeout=300)
1480
1481
def Mission(self):
1482
'''fly the OBC 2016 mission in Dalby'''
1483
self.load_mission("Dalby-OBC2016.txt")
1484
self.load_fence("Dalby-OBC2016-fence.txt")
1485
if self.mavproxy is not None:
1486
self.mavproxy.send('wp list\n')
1487
self.install_terrain_handlers_context()
1488
self.wait_ready_to_arm()
1489
self.arm_vehicle()
1490
self.change_mode('AUTO')
1491
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
1492
1493
self.wait_disarmed(timeout=120) # give quadplane a long time to land
1494
# wait for blood sample here
1495
self.set_current_waypoint(20)
1496
self.wait_ready_to_arm()
1497
self.arm_vehicle()
1498
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
1499
1500
self.wait_disarmed(timeout=120) # give quadplane a long time to land
1501
self.progress("Mission OK")
1502
1503
def VTOLLandSpiral(self):
1504
'''check spiral-to-alt option for landing'''
1505
self.fly_mission('mission.txt')
1506
self.set_parameter('WP_LOITER_RAD', -self.get_parameter('WP_LOITER_RAD'))
1507
self.set_current_waypoint(0, check_afterwards=False)
1508
self.fly_mission('mission.txt')
1509
1510
def VTOLQuicktune(self):
1511
'''VTOL Quicktune'''
1512
self.install_applet_script_context("VTOL-quicktune.lua")
1513
1514
self.set_parameters({
1515
"SCR_ENABLE": 1,
1516
"SIM_SPEEDUP": 20, # need to give some cycles to lua
1517
"RC7_OPTION": 300,
1518
})
1519
1520
self.reboot_sitl()
1521
1522
self.context_collect('STATUSTEXT')
1523
self.set_parameters({
1524
"QUIK_ENABLE" : 1,
1525
"QUIK_DOUBLE_TIME" : 5, # run faster for autotest
1526
})
1527
1528
self.scripting_restart()
1529
self.wait_text("Quicktune for quadplane loaded", check_context=True)
1530
1531
self.wait_ready_to_arm()
1532
self.change_mode("QLOITER")
1533
self.arm_vehicle()
1534
self.takeoff(20, 'QLOITER')
1535
1536
# use rc switch to start tune
1537
self.set_rc(7, 1500)
1538
1539
self.wait_text("Tuning: starting tune", check_context=True)
1540
for axis in ['RLL', 'PIT', 'YAW']:
1541
self.wait_text("Starting %s tune" % axis, check_context=True)
1542
self.wait_text("Tuning: %s_D done" % axis, check_context=True, timeout=120)
1543
self.wait_text("Tuning: %s_P done" % axis, check_context=True, timeout=120)
1544
self.wait_text("Tuning: %s done" % axis, check_context=True, timeout=120)
1545
self.wait_text("Tuning: YAW done", check_context=True, timeout=120)
1546
1547
# to test aux function method, use aux fn for save
1548
self.run_auxfunc(300, 2)
1549
self.wait_text("Tuning: saved", check_context=True)
1550
self.change_mode("QLAND")
1551
1552
self.wait_disarmed(timeout=120)
1553
1554
def VTOLQuicktune_CPP(self):
1555
'''VTOL Quicktune in C++'''
1556
self.set_parameters({
1557
"RC7_OPTION": 181,
1558
"QWIK_ENABLE" : 1,
1559
"QWIK_DOUBLE_TIME" : 5, # run faster for autotest
1560
})
1561
1562
self.context_push()
1563
self.context_collect('STATUSTEXT')
1564
1565
# reduce roll/pitch gains by 2
1566
gain_mul = 0.5
1567
soften_params = ['Q_A_RAT_RLL_P', 'Q_A_RAT_RLL_I', 'Q_A_RAT_RLL_D',
1568
'Q_A_RAT_PIT_P', 'Q_A_RAT_PIT_I', 'Q_A_RAT_PIT_D',
1569
'Q_A_RAT_YAW_P', 'Q_A_RAT_YAW_I']
1570
1571
original_values = self.get_parameters(soften_params)
1572
1573
softened_values = {}
1574
for p in original_values.keys():
1575
softened_values[p] = original_values[p] * gain_mul
1576
self.set_parameters(softened_values)
1577
1578
self.wait_ready_to_arm()
1579
self.change_mode("QLOITER")
1580
self.set_rc(7, 1000)
1581
self.arm_vehicle()
1582
self.takeoff(20, 'QLOITER')
1583
1584
# use rc switch to start tune
1585
self.set_rc(7, 1500)
1586
1587
self.wait_text("Quicktune: starting tune", check_context=True)
1588
for axis in ['Roll', 'Pitch', 'Yaw']:
1589
self.wait_text("Starting %s tune" % axis, check_context=True)
1590
self.wait_text("Quicktune: %s D done" % axis, check_context=True, timeout=120)
1591
self.wait_text("Quicktune: %s P done" % axis, check_context=True, timeout=120)
1592
self.wait_text("Quicktune: %s done" % axis, check_context=True, timeout=120)
1593
1594
new_values = self.get_parameters(soften_params)
1595
for p in original_values.keys():
1596
threshold = 0.8 * original_values[p]
1597
self.progress("tuned param %s %.4f need %.4f" % (p, new_values[p], threshold))
1598
if new_values[p] < threshold:
1599
raise NotAchievedException(
1600
"parameter %s %.4f not increased over %.4f" %
1601
(p, new_values[p], threshold))
1602
1603
self.progress("ensure we are not overtuned")
1604
self.set_parameters({
1605
'SIM_ENGINE_MUL': 0.9,
1606
'SIM_ENGINE_FAIL': 1 << 0,
1607
})
1608
1609
self.delay_sim_time(5)
1610
1611
# and restore it
1612
self.set_parameter('SIM_ENGINE_MUL', 1)
1613
1614
for i in range(5):
1615
self.wait_heartbeat()
1616
1617
if self.statustext_in_collections("ABORTING"):
1618
raise NotAchievedException("tune has aborted, overtuned")
1619
1620
self.progress("using aux fn for save tune")
1621
1622
# to test aux function method, use aux fn for save
1623
self.run_auxfunc(181, 2)
1624
self.wait_text("Quicktune: saved", check_context=True)
1625
self.change_mode("QLAND")
1626
1627
self.wait_disarmed(timeout=120)
1628
self.set_parameter("QWIK_ENABLE", 0)
1629
self.context_pop()
1630
self.reboot_sitl()
1631
1632
def PrecisionLanding(self):
1633
'''VTOL precision landing'''
1634
1635
self.install_applet_script_context("plane_precland.lua")
1636
1637
here = self.mav.location()
1638
target = self.offset_location_ne(here, 20, 0)
1639
1640
self.set_parameters({
1641
"SCR_ENABLE": 1,
1642
"PLND_ENABLED": 1,
1643
"PLND_TYPE": 4,
1644
"SIM_PLD_ENABLE": 1,
1645
"SIM_PLD_LAT" : target.lat,
1646
"SIM_PLD_LON" : target.lng,
1647
"SIM_PLD_HEIGHT" : 0,
1648
"SIM_PLD_ALT_LMT" : 50,
1649
"SIM_PLD_DIST_LMT" : 30,
1650
"RNGFND1_TYPE": 100,
1651
"RNGFND1_PIN" : 0,
1652
"RNGFND1_SCALING" : 12.2,
1653
"RNGFND1_MAX" : 50.00,
1654
"RNGFND_LANDING" : 1,
1655
})
1656
1657
self.reboot_sitl()
1658
1659
self.set_parameters({
1660
"PLND_ALT_CUTOFF" : 5,
1661
"SIM_SPEEDUP" : 10,
1662
})
1663
1664
self.context_collect('STATUSTEXT')
1665
1666
self.scripting_restart()
1667
self.wait_text("PLND: Loaded", check_context=True)
1668
1669
self.wait_ready_to_arm()
1670
self.change_mode("GUIDED")
1671
self.arm_vehicle()
1672
self.takeoff(60, 'GUIDED')
1673
self.wait_altitude(58, 62, relative=True)
1674
self.drain_mav()
1675
self.change_mode("QRTL")
1676
1677
self.wait_text("PLND: Target Acquired", check_context=True, timeout=60)
1678
1679
self.wait_disarmed(timeout=180)
1680
loc2 = self.mav.location()
1681
error = self.get_distance(target, loc2)
1682
self.progress("Target error %.1fm" % error)
1683
if error > 2:
1684
raise NotAchievedException("too far from target %.1fm" % error)
1685
1686
def ShipLanding(self):
1687
'''ship landing test'''
1688
self.install_applet_script_context("plane_ship_landing.lua")
1689
1690
self.set_parameters({
1691
"SCR_ENABLE": 1,
1692
"SIM_SHIP_ENABLE": 1,
1693
"SIM_SHIP_SPEED": 5,
1694
"Q_WP_SPEED": 700,
1695
"Q_P_NE_POS_P": 0.25,
1696
"Q_P_NE_VEL_D": 0.25,
1697
"Q_P_NE_VEL_I": 0.25,
1698
"Q_P_NE_VEL_P": 1.0,
1699
"SIM_SHIP_DSIZE": 10,
1700
"FOLL_ENABLE": 1,
1701
"FOLL_SYSID": 17,
1702
"FOLL_OFS_TYPE": 1,
1703
"SIM_TERRAIN" : 0,
1704
"TERRAIN_ENABLE" : 0,
1705
})
1706
1707
self.load_mission("takeoff100.txt")
1708
1709
self.reboot_sitl(check_position=False)
1710
1711
self.context_collect('STATUSTEXT')
1712
self.set_parameters({
1713
"SHIP_ENABLE" : 1,
1714
"SIM_SPEEDUP" : 10,
1715
})
1716
1717
self.scripting_restart()
1718
self.wait_text("ShipLanding: loaded", check_context=True)
1719
1720
self.wait_ready_to_arm()
1721
self.change_mode("AUTO")
1722
self.arm_vehicle()
1723
self.wait_altitude(95, 105, relative=True, timeout=90)
1724
self.drain_mav()
1725
1726
self.wait_text("Mission complete, changing mode to RTL", check_context=True, timeout=60)
1727
self.wait_text("Descending for approach", check_context=True, timeout=60)
1728
self.wait_text("Reached target altitude", check_context=True, timeout=120)
1729
self.wait_text("Starting approach", check_context=True, timeout=120)
1730
self.wait_text("Land complete", check_context=True, timeout=120)
1731
1732
self.wait_disarmed(timeout=180)
1733
1734
# we confirm successful landing on the ship from our ground speed. The
1735
# deck is just 10m in size, so we must be within 10m if we are moving
1736
# with the deck
1737
self.wait_groundspeed(4.8, 5.2)
1738
1739
tstart = self.get_sim_time_cached()
1740
ship_gpi = None
1741
vehicle_gpi = None
1742
while ship_gpi is None or vehicle_gpi is None:
1743
if self.get_sim_time_cached() - tstart > 5:
1744
raise NotAchievedException("Did not get GPI for ship")
1745
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
1746
if gpi.get_srcSystem() == 17:
1747
ship_gpi = gpi
1748
elif gpi.get_srcSystem() == 1:
1749
vehicle_gpi = gpi
1750
1751
distance = self.get_distance_int(vehicle_gpi, ship_gpi)
1752
self.progress(f"{distance=}")
1753
max_distance = 1.2
1754
if distance > max_distance:
1755
raise NotAchievedException(f"Did not land within {max_distance}m of ship {distance=}")
1756
1757
def RCDisableAirspeedUse(self):
1758
'''check disabling airspeed using RC switch'''
1759
self.set_parameter("RC9_OPTION", 106)
1760
self.delay_sim_time(5)
1761
self.set_rc(9, 1000)
1762
self.wait_sensor_state(
1763
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1764
True,
1765
True,
1766
True)
1767
self.set_rc(9, 2000)
1768
self.wait_sensor_state(
1769
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1770
True,
1771
False,
1772
True)
1773
self.set_rc(9, 1000)
1774
self.wait_sensor_state(
1775
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1776
True,
1777
True,
1778
True)
1779
1780
self.progress("Disabling airspeed sensor")
1781
self.context_push()
1782
self.set_rc(9, 2000)
1783
self.set_parameters({
1784
"COMPASS_ENABLE": 0,
1785
"EK2_ENABLE": 0,
1786
"AHRS_EKF_TYPE": 3,
1787
"COMPASS_USE": 0,
1788
"COMPASS_USE2": 0,
1789
"COMPASS_USE3": 0,
1790
"ARMING_SKIPCHK": 1 << 2, # disables compass
1791
})
1792
1793
self.reboot_sitl()
1794
1795
self.context_collect('STATUSTEXT')
1796
self.wait_prearm_sys_status_healthy(timeout=120)
1797
self.change_mode('QLOITER')
1798
self.arm_vehicle()
1799
self.set_rc(3, 2000)
1800
self.wait_altitude(10, 30, relative=True)
1801
self.change_mode('FBWA')
1802
self.wait_statustext('Transition done')
1803
# the vehicle stays in DCM until there's velocity - make sure
1804
# we did go to EK3 evenutally, 'though:
1805
self.wait_statustext('EKF3 active', check_context=True)
1806
1807
self.disarm_vehicle(force=True)
1808
self.context_pop()
1809
self.reboot_sitl()
1810
1811
def mission_MAV_CMD_DO_VTOL_TRANSITION(self):
1812
'''mission item forces transition'''
1813
wps = self.create_simple_relhome_mission([
1814
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1815
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, 30),
1816
self.create_MISSION_ITEM_INT(
1817
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
1818
p1=mavutil.mavlink.MAV_VTOL_STATE_MC
1819
),
1820
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 200, 30),
1821
self.create_MISSION_ITEM_INT(
1822
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
1823
p1=mavutil.mavlink.MAV_VTOL_STATE_FW
1824
),
1825
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 100, 200, 30),
1826
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1827
])
1828
self.check_mission_upload_download(wps)
1829
1830
self.change_mode('AUTO')
1831
self.wait_ready_to_arm()
1832
1833
self.arm_vehicle()
1834
self.wait_current_waypoint(4)
1835
self.wait_servo_channel_value(5, 1200, comparator=operator.gt)
1836
self.wait_current_waypoint(6)
1837
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1838
1839
self.fly_home_land_and_disarm()
1840
1841
def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self):
1842
'''mavlink command forces transition during mission'''
1843
wps = self.create_simple_relhome_mission([
1844
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1845
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1846
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1847
])
1848
self.check_mission_upload_download(wps)
1849
1850
self.change_mode('AUTO')
1851
self.wait_ready_to_arm()
1852
1853
self.arm_vehicle()
1854
self.wait_current_waypoint(2)
1855
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1856
1857
for command in self.run_cmd, self.run_cmd_int:
1858
command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_MC)
1859
self.wait_servo_channel_value(5, 1200, comparator=operator.gt, timeout=300)
1860
command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_FW)
1861
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1862
1863
self.fly_home_land_and_disarm()
1864
1865
def TransitionMinThrottle(self):
1866
'''Ensure that TKOFF_THR_MIN is applied during the forward transition'''
1867
wps = self.create_simple_relhome_mission([
1868
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1869
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1870
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1871
])
1872
self.check_mission_upload_download(wps)
1873
self.set_parameter('TKOFF_THR_MIN', 80)
1874
1875
self.change_mode('AUTO')
1876
self.wait_ready_to_arm()
1877
1878
self.arm_vehicle()
1879
self.wait_current_waypoint(2)
1880
# Wait for 5 seconds into the transition.
1881
self.delay_sim_time(5)
1882
# Ensure TKOFF_THR_MIN is still respected.
1883
thr_min = self.get_parameter('TKOFF_THR_MIN')
1884
self.wait_servo_channel_value(3, 1000+thr_min*10, comparator=operator.eq)
1885
1886
self.fly_home_land_and_disarm()
1887
1888
def BackTransitionMinThrottle(self):
1889
'''Ensure min throttle is applied during back transition.'''
1890
wps = self.create_simple_relhome_mission([
1891
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1892
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1893
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1894
])
1895
self.check_mission_upload_download(wps)
1896
self.set_parameter('Q_RTL_MODE', 1)
1897
1898
trim_pwm = 1000 + 10*self.get_parameter("TRIM_THROTTLE")
1899
min_pwm = 1000 + 10*self.get_parameter("THR_MIN")
1900
1901
self.change_mode('AUTO')
1902
self.wait_ready_to_arm()
1903
1904
self.arm_vehicle()
1905
self.context_collect('STATUSTEXT')
1906
1907
self.wait_statustext("VTOL airbrake", check_context=True, timeout=300)
1908
self.wait_servo_channel_value(3, trim_pwm, comparator=operator.le, timeout=1)
1909
1910
self.wait_statustext("VTOL position1", check_context=True, timeout=10)
1911
self.wait_servo_channel_value(3, min_pwm+10, comparator=operator.le, timeout=1)
1912
1913
self.wait_disarmed(timeout=60)
1914
1915
def MAV_CMD_NAV_TAKEOFF(self):
1916
'''test issuing takeoff command via mavlink'''
1917
self.change_mode('GUIDED')
1918
self.wait_ready_to_arm()
1919
1920
self.arm_vehicle()
1921
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=5)
1922
self.wait_altitude(4.5, 5.5, minimum_duration=5, relative=True)
1923
self.change_mode('QLAND')
1924
self.wait_disarmed()
1925
1926
self.start_subtest("Check NAV_TAKEOFF is above current location, not home location")
1927
self.change_mode('GUIDED')
1928
self.wait_ready_to_arm()
1929
1930
# reset home 20 metres above current location
1931
current_alt_abs = self.get_altitude(relative=False)
1932
1933
loc = self.mav.location()
1934
1935
home_z_ofs = 20
1936
self.run_cmd(
1937
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
1938
p5=loc.lat,
1939
p6=loc.lng,
1940
p7=current_alt_abs + home_z_ofs,
1941
)
1942
1943
self.arm_vehicle()
1944
takeoff_alt = 5
1945
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=takeoff_alt)
1946
self.wait_altitude(
1947
current_alt_abs + takeoff_alt - 0.5,
1948
current_alt_abs + takeoff_alt + 0.5,
1949
minimum_duration=5,
1950
relative=False,
1951
)
1952
self.change_mode('QLAND')
1953
self.wait_disarmed()
1954
1955
self.reboot_sitl() # unlock home position
1956
1957
def Q_GUIDED_MODE(self):
1958
'''test moving in VTOL mode with SET_POSITION_TARGET_GLOBAL_INT'''
1959
self.set_parameter('Q_GUIDED_MODE', 1)
1960
self.change_mode('GUIDED')
1961
self.wait_ready_to_arm()
1962
self.arm_vehicle()
1963
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=15)
1964
self.wait_altitude(14, 16, relative=True)
1965
1966
loc = self.mav.location()
1967
self.location_offset_ne(loc, 50, 50)
1968
1969
# set position target
1970
self.run_cmd_int(
1971
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1972
0,
1973
1, # reposition flags; 1 means "change to guided"
1974
0,
1975
0,
1976
int(loc.lat * 1e7),
1977
int(loc.lng * 1e7),
1978
30, # alt
1979
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
1980
)
1981
self.wait_location(loc, timeout=120)
1982
1983
self.fly_home_land_and_disarm()
1984
1985
def DCMClimbRate(self):
1986
'''Test the climb rate measurement in DCM with and without GPS'''
1987
self.wait_ready_to_arm()
1988
1989
self.change_mode('QHOVER')
1990
self.arm_vehicle()
1991
self.set_rc(3, 2000)
1992
self.wait_altitude(30, 50, relative=True)
1993
1994
# Start Descending
1995
self.set_rc(3, 1000)
1996
self.wait_climbrate(-5, -0.5, timeout=10)
1997
1998
# Switch to DCM
1999
self.set_parameter('AHRS_EKF_TYPE', 0)
2000
self.delay_sim_time(5)
2001
2002
# Start Climbing
2003
self.set_rc(3, 2000)
2004
self.wait_climbrate(0.5, 5, timeout=10)
2005
2006
# Kill any GPSs
2007
self.set_parameters({
2008
'SIM_GPS1_ENABLE': 0,
2009
'SIM_GPS2_ENABLE': 0,
2010
})
2011
self.delay_sim_time(5)
2012
2013
# Start Descending
2014
self.set_rc(3, 1000)
2015
self.wait_climbrate(-5, -0.5, timeout=10)
2016
2017
# reboot SITL
2018
self.reboot_sitl(force=True)
2019
2020
def RTL_AUTOLAND_1(self):
2021
'''test behaviour when RTL_AUTOLAND==1'''
2022
2023
self.set_parameters({
2024
"RTL_AUTOLAND": 1,
2025
})
2026
2027
# when RTL is entered and RTL_AUTOLAND is 1 we should fly home
2028
# then to the landing sequence. This mission puts the landing
2029
# sequence well to the West of home so if we go directly there
2030
# we won't come within 200m of home
2031
wps = self.create_simple_relhome_mission([
2032
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
2033
# fly North
2034
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),
2035
# add a waypoint 1km North (which we will look for and trigger RTL
2036
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),
2037
2038
# *exciting* landing sequence is ~1km West and points away from Home.
2039
self.create_MISSION_ITEM_INT(
2040
mavutil.mavlink.MAV_CMD_DO_LAND_START,
2041
),
2042
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),
2043
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),
2044
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),
2045
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),
2046
])
2047
self.check_mission_upload_download(wps)
2048
2049
self.change_mode('AUTO')
2050
self.wait_ready_to_arm()
2051
2052
self.arm_vehicle()
2053
self.wait_current_waypoint(3) # will be 2km North here
2054
self.change_mode('RTL')
2055
2056
self.wait_distance_to_home(100, 200, timeout=120)
2057
self.wait_current_waypoint(7)
2058
2059
self.fly_home_land_and_disarm()
2060
2061
def send_reposition_to_loc(self, loc):
2062
self.run_cmd_int(
2063
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
2064
0,
2065
1, # reposition flags; 1 means "change to guided"
2066
0,
2067
0,
2068
int(loc.lat * 1e7),
2069
int(loc.lng * 1e7),
2070
20, # alt
2071
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
2072
)
2073
2074
def reposition_to_loc(self, loc, accuracy=100):
2075
self.send_reposition_to_loc(loc)
2076
self.wait_location(
2077
loc,
2078
accuracy=accuracy,
2079
minimum_duration=20,
2080
timeout=120,
2081
)
2082
2083
def AHRSFlyForwardFlag(self):
2084
'''ensure FlyForward flag is set appropriately'''
2085
self.set_parameters({
2086
"LOG_DISARMED": 1,
2087
"LOG_REPLAY": 1,
2088
})
2089
self.reboot_sitl()
2090
2091
self.assert_mode_is('FBWA')
2092
self.delay_sim_time(10)
2093
self.change_mode('QHOVER')
2094
self.delay_sim_time(10)
2095
2096
self.wait_ready_to_arm()
2097
self.arm_vehicle()
2098
self.set_rc(3, 2000)
2099
self.wait_altitude(20, 50, relative=True)
2100
self.context_collect('STATUSTEXT')
2101
self.change_mode('CRUISE')
2102
self.set_rc(3, 1500)
2103
self.wait_statustext('Transition started airspeed', check_context=True)
2104
self.wait_statustext('Transition airspeed reached', check_context=True)
2105
self.wait_statustext('Transition done', check_context=True)
2106
self.delay_sim_time(5)
2107
self.change_mode('QHOVER')
2108
self.wait_airspeed(0, 5)
2109
self.delay_sim_time(5)
2110
mlog_path = self.current_onboard_log_filepath()
2111
self.fly_home_land_and_disarm(timeout=600)
2112
2113
mlog = self.dfreader_for_path(mlog_path)
2114
2115
stage_require_fbwa = "require_fbwa"
2116
stage_wait_qhover = "wait_qhover"
2117
stage_verify_qhover_ff = "verify_qhover_ff"
2118
stage_wait_cruise = "wait_cruise"
2119
stage_cruise_wait_ff = "cruise_wait_ff"
2120
stage_qhover2 = "qhover2"
2121
stage_done = "done"
2122
stage = stage_require_fbwa
2123
msgs = {}
2124
seen_flag_set_in_cruise = False
2125
FF_BIT_MASK = (1 << 2)
2126
while stage != stage_done:
2127
m = mlog.recv_match()
2128
if m is None:
2129
raise NotAchievedException(f"Stuck in stage {stage}")
2130
m_type = m.get_type()
2131
msgs[m_type] = m
2132
2133
if stage == stage_require_fbwa:
2134
if m_type == 'MODE':
2135
if m.ModeNum == self.get_mode_from_mode_mapping('MANUAL'):
2136
# manual to start with
2137
continue
2138
fbwa_num = self.get_mode_from_mode_mapping('FBWA')
2139
print(f"{m.ModeNum=} {fbwa_num=}")
2140
if m.ModeNum != fbwa_num:
2141
raise ValueError(f"wanted mode={fbwa_num} got={m.ModeNum}")
2142
continue
2143
if m_type == 'RFRN':
2144
if not m.Flags & FF_BIT_MASK:
2145
raise ValueError("Expected FF to be set in FBWA")
2146
stage = stage_wait_qhover
2147
continue
2148
continue
2149
2150
if stage == stage_wait_qhover:
2151
if m_type == 'MODE':
2152
qhover_num = self.get_mode_from_mode_mapping('QHOVER')
2153
print(f"want={qhover_num} got={m.ModeNum}")
2154
if m.ModeNum == qhover_num:
2155
stage = stage_verify_qhover_ff
2156
continue
2157
continue
2158
continue
2159
2160
if stage == stage_verify_qhover_ff:
2161
if m_type == 'RFRN':
2162
if m.Flags & FF_BIT_MASK:
2163
raise ValueError("Expected FF to be unset in QHOVER")
2164
stage = stage_wait_cruise
2165
continue
2166
continue
2167
2168
if stage == stage_wait_cruise:
2169
if m_type == 'MODE':
2170
want_num = self.get_mode_from_mode_mapping('CRUISE')
2171
if m.ModeNum == want_num:
2172
stage = stage_cruise_wait_ff
2173
cruise_wait_ff_start = msgs['ATT'].TimeUS*1e-6
2174
continue
2175
continue
2176
continue
2177
2178
if stage == stage_cruise_wait_ff:
2179
if m_type == 'MODE':
2180
want_num = self.get_mode_from_mode_mapping('CRUISE')
2181
if want_num != m.ModeNum:
2182
if not seen_flag_set_in_cruise:
2183
raise ValueError("Never saw FF get set")
2184
if m.ModeNum == self.get_mode_from_mode_mapping('QHOVER'):
2185
stage = stage_qhover2
2186
continue
2187
continue
2188
if m_type == 'RFRN':
2189
flag_set = m.Flags & FF_BIT_MASK
2190
now = msgs['ATT'].TimeUS*1e-6
2191
delta_t = now - cruise_wait_ff_start
2192
if delta_t < 8:
2193
if flag_set:
2194
raise ValueError("Should not see bit set")
2195
if delta_t > 10:
2196
if not flag_set and not seen_flag_set_in_cruise:
2197
raise ValueError("Should see bit set")
2198
seen_flag_set_in_cruise = True
2199
continue
2200
continue
2201
2202
if stage == stage_qhover2:
2203
'''bit should stay low for qhover 2'''
2204
if m_type == 'RFRN':
2205
flag_set = m.Flags & FF_BIT_MASK
2206
if flag_set:
2207
raise ValueError("ff should be low in qhover")
2208
continue
2209
if m_type == 'MODE':
2210
if m.ModeNum != self.get_mode_from_mode_mapping('QHOVER'):
2211
stage = stage_done
2212
continue
2213
continue
2214
continue
2215
2216
raise NotAchievedException("Bad stage")
2217
2218
def RTL_AUTOLAND_1_FROM_GUIDED(self):
2219
'''test behaviour when RTL_AUTOLAND==1 and entering from guided'''
2220
2221
self.set_parameters({
2222
"RTL_AUTOLAND": 1,
2223
})
2224
2225
# when RTL is entered and RTL_AUTOLAND is 1 we should fly home
2226
# then to the landing sequence. This mission puts the landing
2227
# sequence well to the West of home so if we go directly there
2228
# we won't come within 200m of home
2229
wps = self.create_simple_relhome_mission([
2230
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
2231
# fly North
2232
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),
2233
# add a waypoint 1km North (which we will look for and trigger RTL
2234
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),
2235
2236
# *exciting* landing sequence is ~1km West and points away from Home.
2237
self.create_MISSION_ITEM_INT(
2238
mavutil.mavlink.MAV_CMD_DO_LAND_START,
2239
),
2240
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),
2241
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),
2242
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),
2243
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),
2244
])
2245
self.check_mission_upload_download(wps)
2246
self.set_current_waypoint(0, check_afterwards=False)
2247
2248
self.change_mode('AUTO')
2249
self.wait_ready_to_arm()
2250
2251
here = self.mav.location()
2252
guided_loc = self.offset_location_ne(here, 500, -500)
2253
2254
self.arm_vehicle()
2255
self.wait_current_waypoint(3) # will be 2km North here
2256
self.reposition_to_loc(guided_loc)
2257
self.send_cmd_do_set_mode('RTL')
2258
2259
self.wait_distance_to_home(100, 200, timeout=120)
2260
self.wait_current_waypoint(7)
2261
2262
self.fly_home_land_and_disarm()
2263
2264
def WindEstimateConsistency(self):
2265
'''test that DCM and EKF3 roughly agree on wind speed and direction'''
2266
self.set_parameters({
2267
'SIM_WIND_SPD': 10, # metres/second
2268
'SIM_WIND_DIR': 315, # from the North-West
2269
})
2270
self.change_mode('TAKEOFF')
2271
self.wait_ready_to_arm()
2272
self.arm_vehicle()
2273
self.delay_sim_time(180)
2274
mlog = self.dfreader_for_current_onboard_log()
2275
self.fly_home_land_and_disarm()
2276
2277
self.progress("Inspecting dataflash log")
2278
match_start_time = None
2279
dcm = None
2280
xkf2 = None
2281
while True:
2282
m = mlog.recv_match(
2283
type=['DCM', 'XKF2'],
2284
blocking=True,
2285
)
2286
if m is None:
2287
raise NotAchievedException("Did not see wind estimates match")
2288
2289
m_type = m.get_type()
2290
if m_type == 'DCM':
2291
dcm = m
2292
else:
2293
xkf2 = m
2294
if dcm is None or xkf2 is None:
2295
continue
2296
2297
now = m.TimeUS * 1e-6
2298
2299
matches_east = abs(dcm.VWE-xkf2.VWE) < 1.5
2300
matches_north = abs(dcm.VWN-xkf2.VWN) < 1.5
2301
2302
matches = matches_east and matches_north
2303
2304
if not matches:
2305
match_start_time = None
2306
continue
2307
2308
if match_start_time is None:
2309
match_start_time = now
2310
continue
2311
2312
if now - match_start_time > 60:
2313
self.progress("Wind estimates correlated")
2314
break
2315
2316
def QLoiterRecovery(self):
2317
'''test QLOITER recovery from bad attitude'''
2318
self.context_push()
2319
self.install_example_script_context("sim_arming_pos.lua")
2320
self.install_terrain_handlers_context()
2321
2322
self.set_parameters({
2323
"SCR_ENABLE": 1,
2324
"AHRS_EKF_TYPE": 10,
2325
"EK3_ENABLE": 0,
2326
"LOG_DISARMED": 1,
2327
"Q_LAND_FINAL_SPD" : 2,
2328
"HOME_RESET_ALT" : -1,
2329
})
2330
2331
self.reboot_sitl(check_position=True)
2332
2333
self.context_collect('STATUSTEXT')
2334
self.set_parameters({
2335
"SIM_APOS_ENABLE" : 1,
2336
"SIM_APOS_PIT" : -70,
2337
"SIM_APOS_POS_D" : -200,
2338
"SIM_APOS_POS_E" : 400,
2339
"SIM_APOS_POS_N" : 200,
2340
"SIM_APOS_RLL" : 150,
2341
"SIM_APOS_VEL_X" : 40.0,
2342
"SIM_APOS_VEL_Y" : 0.0,
2343
"SIM_APOS_VEL_Z" : 0.0,
2344
"SIM_APOS_YAW" : 250,
2345
"SIM_APOS_GX" : 0,
2346
"SIM_APOS_GY" : 0,
2347
"SIM_APOS_GZ" : 0,
2348
"SIM_APOS_MODE" : 19, # QLOITER
2349
})
2350
2351
self.scripting_restart()
2352
self.wait_text("Loaded arm pose", check_context=True)
2353
self.wait_ready_to_arm()
2354
2355
# try to climb once in QLOITER
2356
self.set_rc(3, 2000)
2357
2358
# don't start QAssist, let QLOITER do the recovery
2359
self.set_parameter("Q_ASSIST_SPEED", 0)
2360
2361
NTESTS = 20
2362
for t in range(NTESTS):
2363
self.change_mode("FBWA")
2364
self.delay_sim_time(3)
2365
self.progress("Fast Recovery test %u" % t)
2366
self.arm_vehicle(force=True)
2367
self.wait_groundspeed(0, 2, timeout=15)
2368
final_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2369
if final_alt < 100:
2370
raise NotAchievedException(f"Final alt {final_alt:.1f}")
2371
2372
self.disarm_vehicle(force=True)
2373
2374
self.progress("Setup for inverted slow recovery")
2375
self.set_parameters({
2376
"SIM_APOS_ENABLE" : 1,
2377
"SIM_APOS_PIT" : 0,
2378
"SIM_APOS_POS_D" : -200,
2379
"SIM_APOS_POS_E" : 400,
2380
"SIM_APOS_POS_N" : 200,
2381
"SIM_APOS_RLL" : 180,
2382
"SIM_APOS_VEL_X" : 0.0,
2383
"SIM_APOS_VEL_Y" : 0.0,
2384
"SIM_APOS_VEL_Z" : 0.0,
2385
"SIM_APOS_GX" : 0,
2386
"SIM_APOS_GY" : 0,
2387
"SIM_APOS_GZ" : 0,
2388
"SIM_APOS_MODE" : 19, # QLOITER
2389
})
2390
2391
for t in range(NTESTS):
2392
self.change_mode("FBWA")
2393
self.delay_sim_time(3)
2394
self.progress("Slow Recovery test %u" % t)
2395
self.arm_vehicle(force=True)
2396
self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=5)
2397
self.wait_groundspeed(0, 2, timeout=10)
2398
final_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2399
if final_alt < 100:
2400
raise NotAchievedException(f"Final alt {final_alt:.1f}")
2401
self.disarm_vehicle(force=True)
2402
2403
self.set_parameter("SIM_APOS_ENABLE", 0)
2404
self.arm_vehicle(force=True)
2405
self.change_mode("QLAND")
2406
self.wait_disarmed(timeout=300) # give quadplane a long time to land
2407
self.context_pop()
2408
2409
def CruiseRecovery(self):
2410
'''test QAssist recovery in CRUISE mode from bad attitude'''
2411
self.context_push()
2412
self.install_example_script_context("sim_arming_pos.lua")
2413
self.install_terrain_handlers_context()
2414
2415
self.set_parameters({
2416
"SCR_ENABLE": 1,
2417
"AHRS_EKF_TYPE": 10,
2418
"EK3_ENABLE": 0,
2419
"LOG_DISARMED": 1,
2420
"Q_LAND_FINAL_SPD" : 2,
2421
"HOME_RESET_ALT" : -1,
2422
})
2423
2424
self.reboot_sitl(check_position=True)
2425
2426
self.context_collect('STATUSTEXT')
2427
self.set_parameters({
2428
"SIM_APOS_ENABLE" : 1,
2429
"SIM_APOS_PIT" : -70,
2430
"SIM_APOS_POS_D" : -200,
2431
"SIM_APOS_POS_E" : 400,
2432
"SIM_APOS_POS_N" : 200,
2433
"SIM_APOS_RLL" : 150,
2434
"SIM_APOS_VEL_X" : 40.0,
2435
"SIM_APOS_VEL_Y" : 0.0,
2436
"SIM_APOS_VEL_Z" : 0.0,
2437
"SIM_APOS_YAW" : 250,
2438
"SIM_APOS_GX" : 0,
2439
"SIM_APOS_GY" : 0,
2440
"SIM_APOS_GZ" : 0,
2441
"SIM_APOS_MODE" : 7, # CRUISE
2442
})
2443
2444
self.scripting_restart()
2445
self.wait_text("Loaded arm pose", check_context=True)
2446
self.wait_ready_to_arm()
2447
2448
# set cruise target airspeed
2449
self.set_rc(3, 1500)
2450
2451
target_airspeed = self.get_parameter("AIRSPEED_CRUISE")
2452
2453
NTESTS = 20
2454
for t in range(NTESTS):
2455
self.change_mode("FBWA")
2456
self.delay_sim_time(3)
2457
self.progress("Fast CRUISE Recovery test %u" % t)
2458
self.arm_vehicle(force=True)
2459
self.delay_sim_time(3)
2460
# reset target alt and heading using stick inputs
2461
self.set_rc(2, 1600)
2462
self.set_rc(2, 1500)
2463
self.set_rc(1, 1600)
2464
self.set_rc(1, 1500)
2465
self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=10)
2466
self.wait_airspeed(target_airspeed-1, target_airspeed+1)
2467
final_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2468
if final_alt < 100:
2469
raise NotAchievedException(f"Final alt {final_alt:.1f}")
2470
2471
self.disarm_vehicle(force=True)
2472
2473
self.progress("Setup for inverted slow recovery")
2474
self.set_parameters({
2475
"SIM_APOS_ENABLE" : 1,
2476
"SIM_APOS_PIT" : 0,
2477
"SIM_APOS_POS_D" : -200,
2478
"SIM_APOS_POS_E" : 400,
2479
"SIM_APOS_POS_N" : 200,
2480
"SIM_APOS_RLL" : 180,
2481
"SIM_APOS_VEL_X" : 0.0,
2482
"SIM_APOS_VEL_Y" : 0.0,
2483
"SIM_APOS_VEL_Z" : 0.0,
2484
"SIM_APOS_GX" : 0,
2485
"SIM_APOS_GY" : 0,
2486
"SIM_APOS_GZ" : 0,
2487
"SIM_APOS_MODE" : 7, # CRUISE
2488
})
2489
2490
for t in range(NTESTS):
2491
self.change_mode("FBWA")
2492
self.delay_sim_time(3)
2493
self.progress("Slow CRUISE Recovery test %u" % t)
2494
self.arm_vehicle(force=True)
2495
self.delay_sim_time(3)
2496
# reset target alt and heading using stick inputs
2497
self.set_rc(2, 1600)
2498
self.set_rc(2, 1500)
2499
self.set_rc(1, 1600)
2500
self.set_rc(1, 1500)
2501
self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=10)
2502
self.wait_airspeed(target_airspeed-1, target_airspeed+1)
2503
final_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2504
if final_alt < 100:
2505
raise NotAchievedException(f"Final alt {final_alt:.1f}")
2506
self.disarm_vehicle(force=True)
2507
2508
self.set_parameter("SIM_APOS_ENABLE", 0)
2509
self.arm_vehicle(force=True)
2510
self.change_mode("QLAND")
2511
self.wait_disarmed(timeout=300) # give quadplane a long time to land
2512
self.context_pop()
2513
2514
def FastInvertedRecovery(self):
2515
'''test recovery from inverted flight is fast'''
2516
2517
self.set_parameters({
2518
"Q_A_ACCEL_R_MAX": 20000,
2519
"Q_A_ACCEL_P_MAX": 20000,
2520
"Q_A_ACCEL_Y_MAX": 20000,
2521
"Q_A_RATE_R_MAX": 50,
2522
"Q_A_RATE_P_MAX": 50,
2523
"Q_A_RATE_Y_MAX": 50,
2524
})
2525
2526
self.wait_ready_to_arm()
2527
self.takeoff(60, mode='GUIDED', timeout=100)
2528
2529
self.context_collect('STATUSTEXT')
2530
self.set_rc(3, 1500)
2531
self.change_mode('CRUISE')
2532
self.wait_statustext("Transition done", check_context=True)
2533
2534
self.progress("Go to inverted flight")
2535
self.run_auxfunc(43, 2)
2536
self.wait_roll(180, 3, absolute_value=True)
2537
self.delay_sim_time(10)
2538
2539
initial_altitude = self.get_altitude(relative=True, timeout=2)
2540
self.change_mode('QHOVER')
2541
2542
self.wait_roll(0, 3, absolute_value=True)
2543
2544
recovery_altitude = self.get_altitude(relative=True, timeout=2)
2545
alt_change = initial_altitude - recovery_altitude
2546
2547
self.progress("Recovery AltChange %.1fm" % alt_change)
2548
2549
max_alt_change = 3
2550
if alt_change > max_alt_change:
2551
raise NotAchievedException("Recovery AltChange too high %.1f > %.1f" % (alt_change, max_alt_change))
2552
self.fly_home_land_and_disarm()
2553
2554
def DoRepositionTerrain(self):
2555
'''test handling of DO_REPOSITION with terrain alt'''
2556
self.install_terrain_handlers_context()
2557
self.start_subtest("test reposition with terrain alt")
2558
self.wait_ready_to_arm()
2559
2560
dest = copy.copy(SITL_START_LOCATION)
2561
dest.alt = 45
2562
2563
self.set_parameters({
2564
'Q_GUIDED_MODE': 1,
2565
})
2566
2567
self.takeoff(30, mode='GUIDED')
2568
2569
# fly to higher ground
2570
self.send_do_reposition(dest, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
2571
self.wait_location(
2572
dest,
2573
accuracy=200,
2574
timeout=600,
2575
height_accuracy=10,
2576
)
2577
self.delay_sim_time(20)
2578
2579
self.wait_altitude(
2580
dest.alt-10, # NOTE: reuse of alt from abovE
2581
dest.alt+10, # use a 10m buffer as the plane needs to go up and down a bit to maintain terrain distance
2582
minimum_duration=10,
2583
timeout=30,
2584
relative=False,
2585
altitude_source="TERRAIN_REPORT.current_height"
2586
)
2587
2588
# remember the range of heights we go through in the tests
2589
start_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2590
terrain_height_min = start_alt
2591
terrain_height_max = start_alt
2592
2593
def terrain_height_range(mav, m):
2594
if m.get_type() == 'TERRAIN_REPORT':
2595
nonlocal terrain_height_min, terrain_height_max
2596
terrain_height_min = min(terrain_height_min, m.current_height)
2597
terrain_height_max = max(terrain_height_max, m.current_height)
2598
2599
self.install_message_hook_context(terrain_height_range)
2600
2601
# two locations 500m apart
2602
loc1 = copy.copy(dest)
2603
self.location_offset_ne(loc1, -250, 0)
2604
loc1.alt = 100
2605
2606
loc2 = copy.copy(dest)
2607
self.location_offset_ne(loc2, 250, 0)
2608
loc2.alt = 150
2609
2610
loc3 = copy.copy(loc2)
2611
loc3.alt = 100
2612
2613
positions = [
2614
("Loc1", loc1),
2615
("Loc2", loc2),
2616
("Loc1", loc1),
2617
("Loc3", loc3),
2618
("Loc1", loc1),
2619
("Loc3", loc3),
2620
("Loc1", loc1),
2621
("Loc3", loc3),
2622
("Loc2", loc2),
2623
("Loc3", loc3),
2624
("Loc2", loc2),
2625
]
2626
for (name, loc) in positions:
2627
start_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2628
terrain_height_min = start_alt
2629
terrain_height_max = start_alt
2630
2631
self.progress(f"Flying to {name} at {loc.alt:.1f} from {start_alt:.1f}")
2632
self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
2633
2634
self.wait_location(
2635
loc,
2636
accuracy=10,
2637
timeout=600,
2638
height_accuracy=10,
2639
)
2640
self.delay_sim_time(10)
2641
self.wait_altitude(
2642
loc.alt-5,
2643
loc.alt+5,
2644
minimum_duration=10,
2645
timeout=30,
2646
relative=False,
2647
altitude_source="TERRAIN_REPORT.current_height"
2648
)
2649
self.wait_groundspeed(0, 2)
2650
self.wait_altitude(
2651
loc.alt-5,
2652
loc.alt+5,
2653
minimum_duration=10,
2654
timeout=30,
2655
relative=False,
2656
altitude_source="TERRAIN_REPORT.current_height"
2657
)
2658
min_alt_ok = min(start_alt, loc.alt) - 10
2659
max_alt_ok = max(start_alt, loc.alt) + 10
2660
self.progress(f"theight {terrain_height_min:.0f} to {terrain_height_max:.0f} accept {min_alt_ok:.0f}:{max_alt_ok:.0f}") # noqa:E501
2661
if terrain_height_min < min_alt_ok or terrain_height_max > max_alt_ok:
2662
raise NotAchievedException(f"terrain range breach {start_alt:.1f} {terrain_height_min:.1f} {terrain_height_max:.1f}") # noqa:E501
2663
2664
self.change_mode("QLAND")
2665
self.mav.motors_disarmed_wait()
2666
2667
def DoRepositionTerrain2(self):
2668
'''test handling of DO_REPOSITION terrain alt2'''
2669
self.install_terrain_handlers_context()
2670
self.start_subtest("test reposition terrain alt2")
2671
2672
takeoff_loc = mavutil.location(-35.28243788, 149.00502473, 583.7)
2673
self.customise_SITL_commandline(
2674
["--home", f"{takeoff_loc.lat},{takeoff_loc.lng},{takeoff_loc.alt},0"]
2675
)
2676
self.reboot_sitl(check_position=False)
2677
self.wait_ready_to_arm()
2678
2679
dest = copy.copy(takeoff_loc)
2680
dest.alt = 45
2681
2682
self.set_parameters({
2683
'Q_GUIDED_MODE': 1,
2684
})
2685
2686
self.takeoff(75, mode='GUIDED', timeout=60)
2687
2688
# remember the range of heights we go through in the tests
2689
start_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2690
terrain_height_min = start_alt
2691
terrain_height_max = start_alt
2692
2693
def terrain_height_range(mav, m):
2694
if m.get_type() == 'TERRAIN_REPORT':
2695
nonlocal terrain_height_min, terrain_height_max
2696
terrain_height_min = min(terrain_height_min, m.current_height)
2697
terrain_height_max = max(terrain_height_max, m.current_height)
2698
2699
self.install_message_hook_context(terrain_height_range)
2700
2701
loc1 = mavutil.location(-35.27502040, 148.98635977, 75)
2702
loc2 = mavutil.location(-35.28505202, 148.98604378, 75)
2703
2704
loc3 = mavutil.location(-35.27502040, 148.98635977, 120)
2705
loc4 = mavutil.location(-35.28505202, 148.98604378, 120)
2706
2707
loc5 = mavutil.location(-35.28505202, 148.98604378, 100)
2708
2709
positions = [
2710
("Loc1", loc1),
2711
("Loc2", loc2),
2712
("Loc1", loc1),
2713
("Loc2", loc2),
2714
("Loc1", loc1),
2715
("Loc4", loc4),
2716
("Loc3", loc3),
2717
("Loc2", loc2),
2718
("Loc5", loc5),
2719
("Loc1", loc1),
2720
("Loc5", loc5),
2721
("Loc1", loc1),
2722
]
2723
for (name, loc) in positions:
2724
start_alt = self.assert_receive_message('TERRAIN_REPORT').current_height
2725
terrain_height_min = start_alt
2726
terrain_height_max = start_alt
2727
2728
self.progress(f"Flying to {name} at {loc.alt:.1f} from {start_alt:.1f}")
2729
self.send_do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT)
2730
2731
self.wait_location(
2732
loc,
2733
accuracy=10,
2734
timeout=600,
2735
height_accuracy=10,
2736
)
2737
self.delay_sim_time(10)
2738
self.wait_altitude(
2739
loc.alt-5,
2740
loc.alt+5,
2741
minimum_duration=10,
2742
timeout=30,
2743
relative=False,
2744
altitude_source="TERRAIN_REPORT.current_height"
2745
)
2746
2747
self.wait_groundspeed(0, 2)
2748
self.wait_altitude(
2749
loc.alt-5,
2750
loc.alt+5,
2751
minimum_duration=10,
2752
timeout=30,
2753
relative=False,
2754
altitude_source="TERRAIN_REPORT.current_height"
2755
)
2756
min_alt_ok = min(start_alt, loc.alt) - 10
2757
max_alt_ok = max(start_alt, loc.alt) + 25
2758
self.progress(f"theight {terrain_height_min:.0f} to {terrain_height_max:.0f} accept {min_alt_ok:.0f}:{max_alt_ok:.0f}") # noqa:E501
2759
if terrain_height_min < min_alt_ok or terrain_height_max > max_alt_ok:
2760
raise NotAchievedException(f"terrain range breach {start_alt:.1f} {terrain_height_min:.1f} {terrain_height_max:.1f}") # noqa:E501
2761
2762
self.change_mode("QLAND")
2763
self.mav.motors_disarmed_wait()
2764
self.reset_SITL_commandline()
2765
2766
def RudderArmedTakeoffRequiresNeutralThrottle(self):
2767
'''check rudder must be neutral before VTOL takeoff allowed'''
2768
self.upload_simple_relhome_mission([
2769
(mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0, 0, 10),
2770
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, 0, 0),
2771
])
2772
self.upload_simple_relhome_mission
2773
self.change_mode('AUTO')
2774
self.wait_ready_to_arm()
2775
self.set_rc(4, 2000)
2776
self.wait_armed()
2777
self.wait_altitude(-1, 1, relative=True, minimum_duration=10)
2778
self.set_rc(4, 1500)
2779
self.wait_altitude(5, 1000, relative=True)
2780
self.zero_throttle()
2781
self.wait_disarmed(timeout=60)
2782
2783
def RudderArmingWithARMING_CHECK_THROTTLEUnset(self) -> None:
2784
'''check arming behaviour with ARMING_CHECK_THROTTLE unset'''
2785
self.wait_ready_to_arm()
2786
2787
self.start_subtest("Should not be able to arm with mid-stick throttle")
2788
self.set_rc(3, 1500)
2789
self.set_rc(4, 2000)
2790
w = vehicle_test_suite.WaitAndMaintainDisarmed(self, minimum_duration=10)
2791
w.run()
2792
self.set_rc(4, 1500)
2793
self.disarm_vehicle()
2794
2795
self.clear_parameter_bit("RC_OPTIONS", 5)
2796
self.start_subtest("Should be able to arm with mid-stick throttle")
2797
self.set_rc(3, 1500)
2798
self.set_rc(4, 2000)
2799
self.wait_armed()
2800
self.set_rc(4, 1500)
2801
self.disarm_vehicle()
2802
2803
def ScriptedArmingChecksApplet(self):
2804
""" Applet for Arming Checks will prevent a vehicle from arming based on scripted checks
2805
"""
2806
self.start_subtest("Scripted Arming Checks Applet validation")
2807
self.context_collect("STATUSTEXT")
2808
2809
applet_script = "arming-checks.lua"
2810
"""Initialize the FC"""
2811
self.set_parameter("SCR_ENABLE", 1)
2812
self.install_applet_script_context(applet_script)
2813
self.reboot_sitl()
2814
self.wait_ekf_happy()
2815
self.wait_text("ArduPilot Ready", check_context=True)
2816
self.wait_text("Arming Checks .* loaded", timeout=30, check_context=True, regex=True)
2817
'''self.install_messageprinter_handlers_context(['PARAM_VALUE'])'''
2818
2819
self.start_subsubtest("ArmCk: Q_RTL_ALT must be legal")
2820
self.set_parameter("SCALING_SPEED", 22)
2821
self.set_parameter("Q_RTL_ALT", 150)
2822
self.assert_prearm_failure("ArmCk: fail: Q_RTL_ALT too high", other_prearm_failures_fatal=False)
2823
self.set_parameter("Q_RTL_ALT", 120)
2824
self.wait_text("clear: Q_RTL_ALT", check_context=True)
2825
2826
self.start_subsubtest("ArmCk: Q_RTL vs QLand")
2827
''' this is only a warning'''
2828
self.set_parameter("Q_OPTIONS", 33)
2829
self.wait_text("ArmCk: note: Q will RTL", check_context=True)
2830
self.set_parameter("Q_OPTIONS", 1)
2831
self.wait_text("ArmCk: note: Q will land", check_context=True)
2832
2833
def TerrainAvoidApplet(self):
2834
'''Terrain Avoidance with CMTC'''
2835
self.start_subtest("Terrain Avoidance Load and Start")
2836
2837
# We do this in a real-world scenario in Alaska where we take off from the Top of the World
2838
# and fly a mission that goes down into the valley to purposefully trigger Pitcing, Quading and CMTC events
2839
topofworld_loc = mavutil.location(64.1624778, -139.8402246, 1109.0)
2840
self.customise_SITL_commandline(
2841
["--home", f"{topofworld_loc.lat},{topofworld_loc.lng},{topofworld_loc.alt},0"]
2842
)
2843
2844
self.context_collect("STATUSTEXT")
2845
2846
# want 30m STRM data. This has to be set before install_terrain_handlers_context() is called
2847
self.set_parameters({
2848
"TERRAIN_ENABLE": 1,
2849
"TERRAIN_SPACING": 30,
2850
"TERRAIN_FOLLOW": 1,
2851
"TERRAIN_OFS_MAX": 0,
2852
})
2853
2854
self.install_terrain_handlers_context()
2855
self.reboot_sitl(check_position=False)
2856
2857
self.set_parameters({
2858
"SCR_ENABLE": 1,
2859
"SIM_SPEEDUP": 20, # need to give some cycles to lua
2860
"RC7_OPTION": 305,
2861
"RTL_AUTOLAND": 2,
2862
"RNGFND1_TYPE": 100,
2863
})
2864
2865
self.install_applet_script_context("quadplane_terrain_avoid.lua")
2866
self.install_script_module(self.script_modules_source_path("mavlink_wrappers.lua"), "mavlink_wrappers.lua")
2867
self.reboot_sitl(check_position=False)
2868
self.wait_ready_to_arm()
2869
2870
self.wait_text("Terrain Avoid .* script loaded", regex=True, check_context=True)
2871
self.set_parameters({
2872
"TA_CMTC_ENABLE": 1,
2873
"TA_CMTC_RAD": 80,
2874
"TA_ALT_MAX": 250,
2875
"WP_LOITER_RAD": 150,
2876
"RNGFND1_SCALING": 10,
2877
"RNGFND1_PIN": 0,
2878
"RNGFND1_MAX": 100,
2879
"SIM_SONAR_SCALE": 10,
2880
})
2881
2882
# This mission triggers an interesting selection of "Pitching", "Quading" and "CMTC" events
2883
# it's not always consistent, perhaps due to wind, so the tests try to accommodate variances.
2884
filename = "TopOfTheWorldShort.waypoints"
2885
self.progress("Flying mission %s" % filename)
2886
num_wp = self.load_mission(filename)
2887
self.progress("Mission items %d" % num_wp)
2888
2889
self.change_mode("AUTO")
2890
2891
# check that we got terrain data, this test doesn't work if we don't have the correct terrain.
2892
loc = self.mav.location()
2893
2894
lng_int = int(loc.lng * 1e7)
2895
lat_int = int(loc.lat * 1e7)
2896
2897
tstart = self.get_sim_time_cached()
2898
last_terrain_report_pending = -1
2899
while True:
2900
now = self.get_sim_time_cached()
2901
if now - tstart > 600:
2902
raise NotAchievedException("Did not get correct terrain report")
2903
2904
self.mav.mav.terrain_check_send(lat_int, lng_int)
2905
2906
report = self.assert_receive_message('TERRAIN_REPORT', timeout=60)
2907
self.progress(self.dump_message_verbose(report))
2908
if report.spacing != 0:
2909
break
2910
2911
# we will keep trying to long as the number of pending
2912
# tiles is dropping:
2913
if last_terrain_report_pending == -1:
2914
last_terrain_report_pending = report.pending
2915
elif report.pending < last_terrain_report_pending:
2916
last_terrain_report_pending = report.pending
2917
tstart = now
2918
2919
self.delay_sim_time(1)
2920
2921
self.progress(self.dump_message_verbose(report))
2922
self.wait_ready_to_arm()
2923
2924
# TopOfTheWord "ground" is at over 1km altitude
2925
expected_terrain_height = 1101
2926
if abs(report.terrain_height - expected_terrain_height) > 1.0:
2927
raise NotAchievedException("Expected terrain height=%f got=%f" %
2928
(expected_terrain_height, report.terrain_height))
2929
2930
self.set_rc(7, 1000)
2931
self.wait_text("TerrAvoid: activated", check_context=True)
2932
self.set_rc(7, 2000)
2933
self.wait_text("TerrAvoid: deactivated", check_context=True)
2934
self.set_rc(7, 1000)
2935
self.wait_text("TerrAvoid: activated", check_context=True)
2936
2937
self.progress("TERRAIN_FOLLOW is %f" % self.get_parameter('TERRAIN_FOLLOW'))
2938
self.progress("TERRAIN_LOOKAHD is %f" % self.get_parameter('TERRAIN_LOOKAHD'))
2939
self.progress("TERRAIN_OFS_MAX is %f" % self.get_parameter('TERRAIN_OFS_MAX'))
2940
self.progress("ROLL_LIMIT_DEG is %f" % self.get_parameter('ROLL_LIMIT_DEG'))
2941
2942
self.wait_ready_to_arm()
2943
self.arm_vehicle()
2944
self.wait_text("TerrAvoid: close to home", check_context=True)
2945
self.wait_waypoint(2, 4, max_dist=100)
2946
self.wait_text("TerrAvoid: away from home", check_context=True, regex=True)
2947
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2948
self.progress("CMTC alt #1 is %f" % self.get_altitude(relative=False, timeout=2))
2949
# wait for CMTC to gain altitude 1170m +-20
2950
self.wait_altitude(1150, 1190, timeout=60, relative=False, minimum_duration=5)
2951
2952
self.wait_text("TerrAvoid: CMTC Done|TerrAvoid: Quading overrides CMTC", check_context=True, regex=True, timeout=60)
2953
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True, timeout=60)
2954
self.progress("CMTC alt #2 is %f" % self.get_altitude(relative=False, timeout=2))
2955
# wait for CMTC to gain altitude to 1125m +- 55
2956
self.wait_altitude(1070, 1180, timeout=60, relative=False, minimum_duration=5)
2957
self.wait_text("TerrAvoid: CMTC Done|TerrAvoid: Quading overrides CMTC", check_context=True, regex=True)
2958
2959
self.wait_text("TerrAvoid: high terrain detected", check_context=True, regex=True, timeout=60)
2960
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2961
self.progress("CMTC alt #3 is %f" % self.get_altitude(relative=False, timeout=2))
2962
# 1020 +- 20
2963
self.wait_altitude(1000, 1040, timeout=120, relative=False, minimum_duration=5)
2964
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
2965
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
2966
2967
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2968
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
2969
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
2970
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2971
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
2972
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
2973
2974
self.wait_text("TerrAvoid: high terrain detected", check_context=True, regex=True, timeout=60)
2975
2976
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2977
self.progress("CMTC alt #4 is %f" % self.get_altitude(relative=False, timeout=2))
2978
self.wait_text("TerrAvoid: high terrain detected", check_context=True, regex=True, timeout=60)
2979
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2980
self.progress("CMTC alt #6 is %f" % self.get_altitude(relative=False, timeout=2))
2981
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
2982
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
2983
2984
self.progress("alt is %f" % self.get_altitude(relative=False, timeout=2))
2985
2986
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
2987
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
2988
2989
self.progress("#Pitching alt is %f" % self.get_altitude(relative=False, timeout=2))
2990
self.wait_text("TerrAvoid: Pitching Started", check_context=True, regex=True, timeout=600)
2991
self.wait_text("TerrAvoid: Terrain Ok", check_context=True, regex=True, timeout=60)
2992
self.wait_text("TerrAvoid: CMTC loiter left", check_context=True, regex=True)
2993
self.progress("CMTC alt #7 is %f" % self.get_altitude(relative=False, timeout=2))
2994
self.wait_text("TerrAvoid: Pitching DONE", check_context=True, regex=True)
2995
self.progress("#Pitching DONE alt is %f" % self.get_altitude(relative=False, timeout=2))
2996
2997
# After Pitching CMTC to 1170m +- 30
2998
self.wait_altitude(1140, 1200, timeout=120, relative=False, minimum_duration=5)
2999
3000
self.wait_text("TerrAvoid: CMTC STOP", check_context=True, regex=True)
3001
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
3002
# wait for 1 more CMTC's
3003
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
3004
3005
# now we get a guaranteed quadding
3006
self.wait_text("TerrAvoid: Pitching started", check_context=True, regex=True, timeout=120)
3007
self.progress("Pitching alt #1 is %f" % self.get_altitude(relative=False, timeout=2))
3008
self.wait_text("TerrAvoid: Pitching DONE", check_context=True, regex=True)
3009
self.progress("Pitching alt #2 is %f" % self.get_altitude(relative=False, timeout=2))
3010
3011
# wait for 1 more CMTC
3012
self.wait_text("TerrAvoid: CMTC Done", check_context=True, regex=True)
3013
3014
self.wait_statustext('Land complete', timeout=600)
3015
self.wait_disarmed(timeout=120) # give quadplane a long time to land
3016
3017
# autotest doesn't like this location, so need to move back to Dalby before finishing
3018
self.customise_SITL_commandline(
3019
["--home", "-27.274439,151.290064,343.0,0"]
3020
)
3021
self.reboot_sitl()
3022
# remove the installed module. Pretty sure Autotest will remove the script itself
3023
self.remove_installed_script_module("mavlink_wrappers.lua")
3024
3025
def TakeoffCheck(self):
3026
'''Test takeoff check - auto mode'''
3027
self.set_parameters({
3028
"AHRS_EKF_TYPE": 10,
3029
'SIM_ESC_TELEM': 1,
3030
})
3031
3032
self.start_subtest("Test blocking doesn't occur with in-range RPM")
3033
self.context_push()
3034
self.set_parameters({
3035
'SIM_VIB_MOT_MAX': 150, # Hz, 9000 RPM, ensures the test fails if check occurs after takeoff starts
3036
'SIM_ESC_ARM_RPM': 1000,
3037
'Q_TKOFF_RPM_MIN': 900,
3038
'Q_TKOFF_RPM_MAX': 1100,
3039
})
3040
self.upload_simple_relhome_mission([
3041
(mavutil.mavlink.MAV_CMD_NAV_VTOL_TAKEOFF, 0, 0, 1),
3042
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, 0, 0),
3043
])
3044
self.change_mode('AUTO')
3045
self.wait_ready_to_arm()
3046
self.arm_vehicle()
3047
self.wait_current_waypoint(2)
3048
self.wait_disarmed()
3049
self.set_current_waypoint(0, check_afterwards=False)
3050
self.context_pop()
3051
3052
self.start_subtest("Ensure blocked if motors don't spool up")
3053
self.context_push()
3054
self.set_parameters({
3055
'SIM_ESC_ARM_RPM': 500,
3056
'Q_TKOFF_RPM_MIN': 1000,
3057
})
3058
self.upload_simple_relhome_mission([
3059
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
3060
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
3061
])
3062
self.test_takeoff_check_mode("AUTO", force_disarm=True)
3063
self.context_pop()
3064
3065
self.start_subtest("Ensure blocked if virtual motors are missing virtual props")
3066
self.context_push()
3067
self.set_parameters({
3068
'Q_TKOFF_RPM_MIN': 1,
3069
'Q_TKOFF_RPM_MAX': 3,
3070
})
3071
self.test_takeoff_check_mode("AUTO", force_disarm=True)
3072
self.context_pop()
3073
3074
def tests(self):
3075
'''return list of all tests'''
3076
3077
ret = super(AutoTestQuadPlane, self).tests()
3078
ret.extend([
3079
self.FwdThrInVTOL,
3080
self.AirMode,
3081
self.TestMotorMask,
3082
self.PilotYaw,
3083
self.ParameterChecks,
3084
self.QAUTOTUNE,
3085
self.TestLogDownload,
3086
self.TestLogDownloadWrap,
3087
self.EXTENDED_SYS_STATE,
3088
self.Mission,
3089
self.Weathervane,
3090
self.QAssist,
3091
self.GyroFFT,
3092
self.Tailsitter,
3093
self.CopterTailsitter,
3094
self.ICEngine,
3095
self.ICEngineMission,
3096
self.ICEngineRPMGovernor,
3097
self.MAV_CMD_DO_ENGINE_CONTROL,
3098
self.MidAirDisarmDisallowed,
3099
self.GUIDEDToAUTO,
3100
self.BootInAUTO,
3101
self.Ship,
3102
self.WindEstimateConsistency,
3103
self.MAV_CMD_NAV_LOITER_TO_ALT,
3104
self.LoiterAltQLand,
3105
self.VTOLLandSpiral,
3106
self.VTOLQuicktune,
3107
self.VTOLQuicktune_CPP,
3108
self.PrecisionLanding,
3109
self.ShipLanding,
3110
Test(self.MotorTest, kwargs={ # tests motors 4 and 2
3111
"mot1_servo_chan": 8, # quad-x second motor cw from f-r
3112
"mot4_servo_chan": 6, # quad-x third motor cw from f-r
3113
"wait_finish_text": False,
3114
"quadplane": True,
3115
}),
3116
self.RCDisableAirspeedUse,
3117
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
3118
self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,
3119
self.TransitionMinThrottle,
3120
self.BackTransitionMinThrottle,
3121
self.MAV_CMD_NAV_TAKEOFF,
3122
self.Q_GUIDED_MODE,
3123
self.DCMClimbRate,
3124
self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence
3125
self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence
3126
self.AHRSFlyForwardFlag,
3127
self.DoRepositionTerrain,
3128
self.DoRepositionTerrain2,
3129
self.QLoiterRecovery,
3130
self.FastInvertedRecovery,
3131
self.CruiseRecovery,
3132
self.RudderArmedTakeoffRequiresNeutralThrottle,
3133
self.RudderArmingWithARMING_CHECK_THROTTLEUnset,
3134
self.ScriptedArmingChecksApplet,
3135
self.TerrainAvoidApplet,
3136
self.TakeoffCheck,
3137
])
3138
return ret
3139
3140