CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

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

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/quadplane.py
Views: 1798
1
'''
2
Fly ArduPlane QuadPlane in SITL
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
from __future__ import print_function
9
import os
10
import numpy
11
import math
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_A_RAT_RLL_P" : 0.15,
369
"Q_A_RAT_RLL_I" : 0.25,
370
"Q_A_RAT_RLL_D" : 0.002,
371
"Q_A_RAT_PIT_P" : 0.15,
372
"Q_A_RAT_PIT_I" : 0.25,
373
"Q_A_RAT_PIT_D" : 0.002,
374
"Q_A_RAT_YAW_P" : 0.18,
375
"Q_A_RAT_YAW_I" : 0.018,
376
"Q_A_ANG_RLL_P" : 4.5,
377
"Q_A_ANG_PIT_P" : 4.5,
378
})
379
380
# this is a list of all parameters modified by QAUTOTUNE. Set
381
# them so that when the context is popped we get the original
382
# values back:
383
parameter_values = self.get_parameters([
384
"Q_A_RAT_RLL_P",
385
"Q_A_RAT_RLL_I",
386
"Q_A_RAT_RLL_D",
387
"Q_A_ANG_RLL_P",
388
"Q_A_ACCEL_R_MAX",
389
"Q_A_RAT_PIT_P",
390
"Q_A_RAT_PIT_I",
391
"Q_A_RAT_PIT_D",
392
"Q_A_ANG_PIT_P",
393
"Q_A_ACCEL_P_MAX",
394
"Q_A_RAT_YAW_P",
395
"Q_A_RAT_YAW_I",
396
"Q_A_RAT_YAW_FLTE",
397
"Q_A_ANG_YAW_P",
398
"Q_A_ACCEL_Y_MAX",
399
])
400
self.set_parameters(parameter_values)
401
402
self.takeoff(15, mode='GUIDED')
403
self.set_rc(3, 1500)
404
self.change_mode("QLOITER")
405
self.change_mode("QAUTOTUNE")
406
tstart = self.get_sim_time()
407
self.context_collect('STATUSTEXT')
408
while True:
409
now = self.get_sim_time_cached()
410
if now - tstart > 5000:
411
raise NotAchievedException("Did not get success message")
412
try:
413
self.wait_text("AutoTune: Success", timeout=1, check_context=True)
414
except AutoTestTimeoutException:
415
continue
416
# got success message
417
break
418
self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))
419
self.context_clear_collection('STATUSTEXT')
420
421
self.progress("Landing to save gains")
422
self.set_rc(3, 1200)
423
self.wait_speed_vector(
424
Vector3(float('nan'), float('nan'), 1.4),
425
timeout=5,
426
)
427
self.wait_speed_vector(
428
Vector3(0.0, 0.0, 0.0),
429
timeout=20,
430
)
431
distance = self.distance_to_home()
432
if distance > 20:
433
raise NotAchievedException("wandered from home (distance=%f)" %
434
(distance,))
435
self.set_rc(3, 1000)
436
tstart = self.get_sim_time()
437
while True:
438
now = self.get_sim_time_cached()
439
if now - tstart > 500:
440
raise NotAchievedException("Did not get success message")
441
self.send_mavlink_disarm_command()
442
try:
443
self.wait_text(
444
"AutoTune: Saved gains for Roll Pitch Yaw.*",
445
timeout=0.5,
446
check_context=True,
447
regex=True,
448
)
449
except AutoTestTimeoutException:
450
continue
451
break
452
453
self.wait_disarmed()
454
self.reboot_sitl() # far from home
455
456
def takeoff(self, height, mode, timeout=30):
457
"""climb to specified height and set throttle to 1500"""
458
self.set_current_waypoint(0, check_afterwards=False)
459
self.change_mode(mode)
460
self.wait_ready_to_arm()
461
self.arm_vehicle()
462
if mode == 'GUIDED':
463
self.user_takeoff(alt_min=height, timeout=timeout)
464
return
465
self.set_rc(3, 1800)
466
self.wait_altitude(height,
467
height+5,
468
relative=True,
469
timeout=timeout)
470
self.set_rc(3, 1500)
471
472
def do_RTL(self):
473
self.change_mode("QRTL")
474
self.wait_altitude(-5, 1, relative=True, timeout=60)
475
self.wait_disarmed()
476
self.zero_throttle()
477
478
def fly_home_land_and_disarm(self, timeout=30):
479
self.context_push()
480
self.change_mode('LOITER')
481
self.set_parameter('RTL_AUTOLAND', 2)
482
filename = "QuadPlaneDalbyRTL.txt"
483
self.progress("Using %s to fly home" % filename)
484
self.load_generic_mission(filename)
485
self.send_cmd_do_set_mode("RTL")
486
self.wait_mode('AUTO')
487
self.wait_current_waypoint(4)
488
self.wait_statustext('Land descend started')
489
self.wait_statustext('Land final started', timeout=60)
490
self.wait_disarmed(timeout=timeout)
491
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
492
# the following command is accepted, but doesn't actually
493
# work! Should be able to remove check_afterwards!
494
self.set_current_waypoint(0, check_afterwards=False)
495
self.change_mode('MANUAL')
496
self.context_pop()
497
498
def wait_level_flight(self, accuracy=5, timeout=30):
499
"""Wait for level flight."""
500
tstart = self.get_sim_time()
501
self.progress("Waiting for level flight")
502
self.set_rc(1, 1500)
503
self.set_rc(2, 1500)
504
self.set_rc(4, 1500)
505
while self.get_sim_time_cached() < tstart + timeout:
506
m = self.mav.recv_match(type='ATTITUDE', blocking=True)
507
roll = math.degrees(m.roll)
508
pitch = math.degrees(m.pitch)
509
self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))
510
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
511
self.progress("Attained level flight")
512
return
513
raise NotAchievedException("Failed to attain level flight")
514
515
def fly_left_circuit(self):
516
"""Fly a left circuit, 200m on a side."""
517
self.mavproxy.send('switch 4\n')
518
self.change_mode('FBWA')
519
self.set_rc(3, 1700)
520
self.wait_level_flight()
521
522
self.progress("Flying left circuit")
523
# do 4 turns
524
for i in range(0, 4):
525
# hard left
526
self.progress("Starting turn %u" % i)
527
self.set_rc(1, 1000)
528
self.wait_heading(270 - (90*i), accuracy=10)
529
self.set_rc(1, 1500)
530
self.progress("Starting leg %u" % i)
531
self.wait_distance(100, accuracy=20)
532
self.progress("Circuit complete")
533
self.change_mode('QHOVER')
534
self.set_rc(3, 1100)
535
self.wait_altitude(10, 15,
536
relative=True,
537
timeout=60)
538
self.set_rc(3, 1500)
539
540
def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, fftLength=32, peakhz=None):
541
542
# find a motor peak
543
self.takeoff(10, mode="QHOVER")
544
545
hover_time = 15
546
tstart = self.get_sim_time()
547
self.progress("Hovering for %u seconds" % hover_time)
548
while self.get_sim_time_cached() < tstart + hover_time:
549
self.mav.recv_match(type='ATTITUDE', blocking=True)
550
vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True)
551
tend = self.get_sim_time()
552
553
self.do_RTL()
554
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
555
556
# batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin
557
scale = 1000. / 1024.
558
sminhz = int(minhz * scale)
559
smaxhz = int(maxhz * scale)
560
freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz]
561
peakdb = numpy.amax(psd["X"][sminhz:smaxhz])
562
if peakdb < dblevel or (peakhz is not None and abs(freq - peakhz) / peakhz > 0.05):
563
raise NotAchievedException("No motor peak, found %fHz at %fdB" % (freq, peakdb))
564
else:
565
self.progress("motor peak %fHz, thr %f%%, %fdB" % (freq, vfr_hud.throttle, peakdb))
566
567
# we have a peak make sure that the FFT detected something close
568
# logging is at 10Hz
569
mlog = self.dfreader_for_current_onboard_log()
570
# accuracy is determined by sample rate and fft length, given our use of quinn we could probably use half of this
571
freqDelta = 1000. / fftLength
572
pkAvg = freq
573
freqs = []
574
575
while True:
576
m = mlog.recv_match(
577
type='FTN1',
578
blocking=True,
579
condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6))
580
if m is None:
581
break
582
freqs.append(m.PkAvg)
583
584
# peak within resolution of FFT length
585
pkAvg = numpy.median(numpy.asarray(freqs))
586
if abs(pkAvg - freq) > freqDelta:
587
raise NotAchievedException("FFT did not detect a motor peak at %f, found %f, wanted %f" % (dblevel, pkAvg, freq))
588
589
return freq
590
591
def GyroFFT(self):
592
"""Use dynamic harmonic notch to control motor noise."""
593
# basic gyro sample rate test
594
self.progress("Flying with gyro FFT - Gyro sample rate")
595
self.context_push()
596
ex = None
597
try:
598
self.set_rc_default()
599
600
# magic tridge EKF type that dramatically speeds up the test
601
self.set_parameters({
602
"AHRS_EKF_TYPE": 10,
603
604
"INS_LOG_BAT_MASK": 3,
605
"INS_LOG_BAT_OPT": 0,
606
"INS_GYRO_FILTER": 100,
607
"LOG_BITMASK": 45054,
608
"LOG_DISARMED": 0,
609
"SIM_DRIFT_SPEED": 0,
610
"SIM_DRIFT_TIME": 0,
611
# enable a noisy motor peak
612
"SIM_GYR1_RND": 20,
613
# enabling FFT will also enable the arming check: self-testing the functionality
614
"FFT_ENABLE": 1,
615
"FFT_MINHZ": 80,
616
"FFT_MAXHZ": 350,
617
"FFT_SNR_REF": 10,
618
"FFT_WINDOW_SIZE": 128,
619
"FFT_WINDOW_OLAP": 0.75,
620
})
621
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
622
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
623
# a 250Hz peak should be detectable within 5%
624
self.set_parameters({
625
"SIM_VIB_FREQ_X": 250,
626
"SIM_VIB_FREQ_Y": 250,
627
"SIM_VIB_FREQ_Z": 250,
628
})
629
self.reboot_sitl()
630
631
# find a motor peak
632
self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)
633
634
# Step 2: inject actual motor noise and use the standard length FFT to track it
635
self.set_parameters({
636
"SIM_VIB_MOT_MAX": 350,
637
"FFT_WINDOW_SIZE": 32,
638
"FFT_WINDOW_OLAP": 0.5,
639
})
640
self.reboot_sitl()
641
# find a motor peak
642
freq = self.hover_and_check_matched_frequency(-15, 200, 300, 32)
643
644
# Step 3: add a FFT dynamic notch and check that the peak is squashed
645
self.set_parameters({
646
"INS_LOG_BAT_OPT": 2,
647
"INS_HNTCH_ENABLE": 1,
648
"INS_HNTCH_FREQ": freq,
649
"INS_HNTCH_REF": 1.0,
650
"INS_HNTCH_ATT": 50,
651
"INS_HNTCH_BW": freq/2,
652
"INS_HNTCH_MODE": 4,
653
})
654
self.reboot_sitl()
655
656
self.takeoff(10, mode="QHOVER")
657
hover_time = 15
658
ignore_bins = 20
659
660
self.progress("Hovering for %u seconds" % hover_time)
661
tstart = self.get_sim_time()
662
while self.get_sim_time_cached() < tstart + hover_time:
663
self.mav.recv_match(type='ATTITUDE', blocking=True)
664
tend = self.get_sim_time()
665
666
self.do_RTL()
667
psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)
668
freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins]
669
peakdB = numpy.amax(psd["X"][ignore_bins:])
670
if peakdB < -10:
671
self.progress("No motor peak, %f at %f dB" % (freq, peakdB))
672
else:
673
raise NotAchievedException("Detected peak at %f Hz of %.2f dB" % (freq, peakdB))
674
675
# Step 4: take off as a copter land as a plane, make sure we track
676
self.progress("Flying with gyro FFT - vtol to plane")
677
self.load_mission("quadplane-gyro-mission.txt")
678
if self.mavproxy is not None:
679
self.mavproxy.send('wp list\n')
680
self.change_mode('AUTO')
681
self.wait_ready_to_arm()
682
self.arm_vehicle()
683
self.wait_waypoint(1, 7, max_dist=60, timeout=1200)
684
self.wait_disarmed(timeout=120) # give quadplane a long time to land
685
686
# prevent update parameters from messing with the settings when we pop the context
687
self.set_parameter("FFT_ENABLE", 0)
688
self.reboot_sitl()
689
690
except Exception as e:
691
self.progress("Exception caught: %s" % (
692
self.get_exception_stacktrace(e)))
693
ex = e
694
695
self.context_pop()
696
697
self.reboot_sitl()
698
699
if ex is not None:
700
raise ex
701
702
def PIDTuning(self):
703
'''Test PID Tuning'''
704
self.change_mode("FBWA") # we don't update PIDs in MANUAL
705
super(AutoTestQuadPlane, self).PIDTuning()
706
707
def ParameterChecks(self):
708
'''basic parameter checks'''
709
self.test_parameter_checks_poscontrol("Q_P")
710
711
def rc_defaults(self):
712
ret = super(AutoTestQuadPlane, self).rc_defaults()
713
ret[3] = 1000
714
return ret
715
716
def default_mode(self):
717
return "MANUAL"
718
719
def disabled_tests(self):
720
return {
721
"FRSkyPassThrough": "Currently failing",
722
"CPUFailsafe": "servo channel values not scaled like ArduPlane",
723
"GyroFFT": "flapping test",
724
"ConfigErrorLoop": "failing because RC values not settable",
725
}
726
727
def BootInAUTO(self):
728
'''Test behaviour when booting in auto'''
729
self.load_mission("mission.txt")
730
self.set_parameters({
731
})
732
self.set_rc(5, 1000)
733
self.wait_mode('AUTO')
734
self.reboot_sitl()
735
self.wait_ready_to_arm()
736
self.delay_sim_time(20)
737
self.assert_current_waypoint(1)
738
self.arm_vehicle()
739
self.wait_altitude(9, 11, relative=True) # value from mission file is 10
740
distance = self.distance_to_home()
741
# this distance check is very, very loose. At time of writing
742
# the vehicle actually pitches ~6 degrees on trakeoff,
743
# wandering over 1m.
744
if distance > 2:
745
raise NotAchievedException("wandered from home (distance=%f)" %
746
(distance,))
747
self.change_mode('QLAND')
748
self.wait_disarmed(timeout=60)
749
750
def PilotYaw(self):
751
'''Test pilot yaw in various modes'''
752
self.takeoff(10, mode="QLOITER")
753
self.set_parameter("STICK_MIXING", 0)
754
self.set_rc(4, 1700)
755
for mode in "QLOITER", "QHOVER":
756
self.wait_heading(45)
757
self.wait_heading(90)
758
self.wait_heading(180)
759
self.wait_heading(275)
760
self.set_rc(4, 1500)
761
self.do_RTL()
762
763
def FwdThrInVTOL(self):
764
'''test use of fwd motor throttle into wind'''
765
self.set_parameters({"SIM_WIND_SPD": 25, # need very strong wind for this test
766
"SIM_WIND_DIR": 360,
767
"Q_WVANE_ENABLE": 1,
768
"Q_WVANE_GAIN": 1,
769
"STICK_MIXING": 0,
770
"Q_FWD_THR_USE": 2})
771
772
self.takeoff(10, mode="QLOITER")
773
self.set_rc(2, 1000)
774
self.delay_sim_time(10)
775
# Check that it is using some forward throttle
776
fwd_thr_pwm = self.get_servo_channel_value(3)
777
if fwd_thr_pwm < 1150 :
778
raise NotAchievedException("fwd motor pwm command low, want >= 1150 got %f" % (fwd_thr_pwm))
779
# check that pitch is on limit
780
m = self.mav.recv_match(type='ATTITUDE', blocking=True)
781
pitch = math.degrees(m.pitch)
782
if abs(pitch + 3.0) > 0.5 :
783
raise NotAchievedException("pitch should be -3.0 +- 0.5 deg, got %f" % (pitch))
784
self.set_rc(2, 1500)
785
self.delay_sim_time(5)
786
loc1 = self.mav.location()
787
self.set_parameter("SIM_ENGINE_FAIL", 1 << 2) # simulate a complete loss of forward motor thrust
788
self.delay_sim_time(20)
789
self.change_mode('QLAND')
790
self.wait_disarmed(timeout=60)
791
loc2 = self.mav.location()
792
position_drift = self.get_distance(loc1, loc2)
793
if position_drift > 5.0 :
794
raise NotAchievedException("position drift high, want < 5.0 m got %f m" % (position_drift))
795
796
def Weathervane(self):
797
'''test nose-into-wind functionality'''
798
# We test nose into wind code paths and yaw direction in copter autotest,
799
# so we shall test the side into wind yaw direction and plane code paths here.
800
self.set_parameters({"SIM_WIND_SPD": 10,
801
"SIM_WIND_DIR": 240,
802
"Q_WVANE_ENABLE": 3, # WVANE_ENABLE = 3 gives direction of side into wind
803
"Q_WVANE_GAIN": 3,
804
"STICK_MIXING": 0})
805
806
self.takeoff(10, mode="QLOITER")
807
808
# Turn aircraft to heading 90 deg
809
self.set_rc(4, 1700)
810
self.wait_heading(90)
811
self.set_rc(4, 1500)
812
813
# Now wait for weathervaning to activate and turn side-on to wind at 240 deg therefore heading 150 deg
814
self.wait_heading(150, accuracy=5, timeout=180)
815
816
self.do_RTL()
817
818
def CPUFailsafe(self):
819
'''In lockup Plane should copy RC inputs to RC outputs'''
820
self.plane_CPUFailsafe()
821
822
def QAssist(self):
823
'''QuadPlane Assist tests'''
824
self.takeoff(10, mode="QHOVER")
825
self.set_rc(3, 1800)
826
self.change_mode("FBWA")
827
828
# disable stall prevention so roll angle is not limited
829
self.set_parameter("STALL_PREVENTION", 0)
830
831
thr_min_pwm = self.get_parameter("Q_M_PWM_MIN")
832
lim_roll_deg = self.get_parameter("ROLL_LIMIT_DEG")
833
self.progress("Waiting for motors to stop (transition completion)")
834
self.wait_servo_channel_value(5,
835
thr_min_pwm,
836
timeout=30,
837
comparator=operator.eq)
838
self.delay_sim_time(5)
839
self.wait_servo_channel_value(5,
840
thr_min_pwm,
841
timeout=30,
842
comparator=operator.eq)
843
self.progress("Stopping forward motor to kill airspeed below limit")
844
self.set_rc(3, 1000)
845
self.progress("Waiting for qassist to kick in")
846
self.wait_servo_channel_value(5, 1400, timeout=30, comparator=operator.gt)
847
self.progress("Move forward again, check qassist stops")
848
self.set_rc(3, 1800)
849
self.progress("Checking qassist stops")
850
self.wait_servo_channel_value(5,
851
thr_min_pwm,
852
timeout=30,
853
comparator=operator.eq)
854
self.set_rc(3, 1300)
855
856
# Test angle assist
857
self.context_push()
858
self.progress("Rolling over to %.0f degrees" % -lim_roll_deg)
859
self.set_rc(1, 1000)
860
self.wait_roll(-lim_roll_deg, 5)
861
self.progress("Killing servo outputs to force qassist to help")
862
self.set_parameter("SERVO1_MIN", 1480)
863
self.set_parameter("SERVO1_MAX", 1480)
864
self.set_parameter("SERVO1_TRIM", 1480)
865
self.progress("Trying to roll over hard the other way")
866
self.set_rc(1, 2000)
867
self.progress("Waiting for qassist (angle) to kick in")
868
self.wait_servo_channel_value(5, 1100, timeout=30, comparator=operator.gt)
869
self.wait_roll(lim_roll_deg, 5)
870
self.context_pop()
871
self.set_rc(1, 1500)
872
873
# Test alt assist, climb to 60m and set assist alt to 50m
874
self.context_push()
875
guided_loc = self.home_relative_loc_ne(0, 0)
876
guided_loc.alt = 60
877
self.change_mode("GUIDED")
878
self.send_do_reposition(guided_loc)
879
self.wait_altitude(58, 62, relative=True)
880
self.set_parameter("Q_ASSIST_ALT", 50)
881
882
# Try and descent to 40m
883
guided_loc.alt = 40
884
self.send_do_reposition(guided_loc)
885
886
# Expect alt assist to kick in, eg "Alt assist 48.9m"
887
self.wait_statustext(r"Alt assist \d*.\d*m", regex=True, timeout=100)
888
889
# Test transition timeout, should switch to QRTL
890
self.set_parameter("Q_TRANS_FAIL_ACT", 1)
891
self.set_parameter("Q_TRANS_FAIL", 10)
892
self.wait_mode("QRTL")
893
894
self.context_pop()
895
896
self.wait_disarmed(timeout=200)
897
898
def LoiterAltQLand(self):
899
'''test loitering and qland with terrain involved'''
900
self.LoiterAltQLand_Terrain(
901
home="LakeGeorgeLookout",
902
ofs_n=0,
903
ofs_e=300,
904
)
905
# self.LoiterAltQLand_Terrain(
906
# home="KalaupapaCliffs",
907
# ofs_n=500,
908
# ofs_e=500,
909
# )
910
self.LoiterAltQLand_Relative()
911
912
def LoiterAltQLand_Relative(self):
913
'''test failsafe where vehicle loiters in fixed-wing mode to a
914
specific altitude then changes mode to QLAND'''
915
self.set_parameters({
916
'BATT_MONITOR': 4, # LoiterAltQLand
917
'BATT_FS_LOW_ACT': 6, # LoiterAltQLand
918
})
919
self.reboot_sitl()
920
takeoff_alt = 5
921
self.takeoff(takeoff_alt, mode='QLOITER')
922
loc = self.mav.location()
923
self.location_offset_ne(loc, 500, 500)
924
new_alt = 100
925
initial_altitude = self.get_altitude(relative=False, timeout=2)
926
self.run_cmd_int(
927
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
928
0,
929
1, # reposition flags; 1 means "change to guided"
930
0,
931
0,
932
int(loc.lat * 1e7),
933
int(loc.lng * 1e7),
934
new_alt, # alt
935
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
936
)
937
self.wait_altitude(
938
new_alt-1,
939
new_alt+1,
940
timeout=60,
941
relative=True,
942
minimum_duration=10)
943
self.wait_location(loc, timeout=120, accuracy=100)
944
self.progress("Triggering failsafe")
945
self.set_parameter('BATT_LOW_VOLT', 50)
946
self.wait_mode(25) # LoiterAltQLand
947
self.drain_mav()
948
m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)
949
q_rtl_alt = self.get_parameter('Q_RTL_ALT')
950
expected_alt = initial_altitude - takeoff_alt + q_rtl_alt
951
952
if abs(m.alt - expected_alt) > 20:
953
raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %
954
(expected_alt, m.alt))
955
self.assert_mode('LOITERALTQLAND')
956
self.wait_mode('QLAND')
957
alt = self.get_altitude(relative=True)
958
if abs(alt - q_rtl_alt) > 2:
959
raise NotAchievedException("qland too late; want=%f got=%f" %
960
(alt, q_rtl_alt))
961
962
self.wait_disarmed(timeout=300)
963
964
def LoiterAltQLand_Terrain(self,
965
home=None,
966
ofs_n=None,
967
ofs_e=None,
968
reposition_alt=100):
969
'''test failsafe where vehicle loiters in fixed-wing mode to a
970
specific altitude then changes mode to QLAND'''
971
self.context_push()
972
self.install_terrain_handlers_context()
973
self.set_parameters({
974
'BATT_MONITOR': 4, # LoiterAltQLand
975
'BATT_FS_LOW_ACT': 6, # LoiterAltQLand
976
'TERRAIN_FOLLOW': 1, # enabled in all modes
977
})
978
self.customise_SITL_commandline(
979
["--home", home]
980
)
981
takeoff_alt = 5
982
self.takeoff(takeoff_alt, mode='QLOITER')
983
loc = self.mav.location()
984
self.location_offset_ne(loc, ofs_n, ofs_e)
985
initial_altitude = self.get_altitude(relative=False, timeout=2)
986
self.run_cmd_int(
987
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
988
0,
989
1, # reposition flags; 1 means "change to guided"
990
0,
991
0,
992
int(loc.lat * 1e7),
993
int(loc.lng * 1e7),
994
reposition_alt, # alt
995
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
996
)
997
self.wait_altitude(
998
reposition_alt-1,
999
reposition_alt+1,
1000
timeout=60,
1001
relative=True,
1002
minimum_duration=10)
1003
1004
self.wait_location(loc, timeout=500, accuracy=100)
1005
1006
self.progress("Triggering failsafe")
1007
self.set_parameter('BATT_LOW_VOLT', 50)
1008
self.wait_mode(25) # LoiterAltQLand
1009
terrain_alt = self.get_terrain_height(verbose=True)
1010
self.drain_mav()
1011
m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)
1012
q_rtl_alt = self.get_parameter('Q_RTL_ALT')
1013
expected_alt = terrain_alt + q_rtl_alt
1014
1015
if abs(m.alt - expected_alt) > 20:
1016
raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %
1017
(expected_alt, m.alt))
1018
self.assert_mode('LOITERALTQLAND')
1019
self.wait_mode('QLAND')
1020
alt = initial_altitude + self.get_altitude(relative=True)
1021
if abs(alt - expected_alt) > 10:
1022
raise NotAchievedException("qland too late; want=%f got=%f" %
1023
(expected_alt, alt))
1024
1025
self.wait_disarmed(timeout=300)
1026
self.zero_throttle()
1027
self.reset_SITL_commandline()
1028
self.context_pop()
1029
1030
def GUIDEDToAUTO(self):
1031
'''Test using GUIDED mode for takeoff before shifting to auto'''
1032
self.load_mission("mission.txt")
1033
self.takeoff(30, mode='GUIDED')
1034
1035
# extra checks would go here
1036
self.assert_not_receiving_message('CAMERA_FEEDBACK')
1037
1038
self.change_mode('AUTO')
1039
self.wait_current_waypoint(3)
1040
self.change_mode('QRTL')
1041
self.wait_disarmed(timeout=240)
1042
1043
def Tailsitter(self):
1044
'''tailsitter test'''
1045
self.set_parameter('Q_FRAME_CLASS', 10)
1046
self.set_parameter('Q_ENABLE', 1)
1047
self.set_parameter('Q_TAILSIT_ENABLE', 1)
1048
1049
self.reboot_sitl()
1050
self.wait_ready_to_arm()
1051
value_before = self.get_servo_channel_value(3)
1052
self.progress("Before: %u" % value_before)
1053
self.change_mode('QHOVER')
1054
tstart = self.get_sim_time()
1055
while True:
1056
now = self.get_sim_time_cached()
1057
if now - tstart > 60:
1058
break
1059
value_after = self.get_servo_channel_value(3)
1060
self.progress("After: t=%f output=%u" % ((now - tstart), value_after))
1061
if value_before != value_after:
1062
raise NotAchievedException("Changed throttle output on mode change to QHOVER")
1063
self.disarm_vehicle()
1064
1065
def CopterTailsitter(self):
1066
'''copter tailsitter test'''
1067
self.customise_SITL_commandline(
1068
[],
1069
defaults_filepath=self.model_defaults_filepath('quadplane-copter_tailsitter'),
1070
model="quadplane-copter_tailsitter",
1071
wipe=True,
1072
)
1073
1074
self.reboot_sitl()
1075
self.wait_ready_to_arm()
1076
self.takeoff(60, mode='GUIDED')
1077
self.context_collect("STATUSTEXT")
1078
self.progress("Starting QLAND")
1079
self.change_mode("QLAND")
1080
self.wait_statustext("Rangefinder engaged")
1081
self.wait_disarmed(timeout=100)
1082
1083
def setup_ICEngine_vehicle(self):
1084
'''restarts SITL with an IC Engine setup'''
1085
model = "quadplane-ice"
1086
self.customise_SITL_commandline(
1087
[],
1088
model=model,
1089
defaults_filepath=self.model_defaults_filepath(model),
1090
wipe=False,
1091
)
1092
1093
def ICEngine(self):
1094
'''Test ICE Engine support'''
1095
rc_engine_start_chan = 11
1096
self.setup_ICEngine_vehicle()
1097
1098
self.wait_ready_to_arm()
1099
self.wait_rpm(1, 0, 0, minimum_duration=1)
1100
self.arm_vehicle()
1101
self.wait_rpm(1, 0, 0, minimum_duration=1)
1102
self.context_collect("STATUSTEXT")
1103
self.progress("Setting engine-start RC switch to HIGH")
1104
self.set_rc(rc_engine_start_chan, 2000)
1105
self.wait_statustext("Starting engine", check_context=True)
1106
self.wait_rpm(1, 300, 400, minimum_duration=1)
1107
self.progress("Setting engine-start RC switch to MID")
1108
self.set_rc(rc_engine_start_chan, 1500)
1109
self.progress("Setting full throttle")
1110
self.set_rc(3, 2000)
1111
self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40)
1112
self.progress("Setting min-throttle")
1113
self.set_rc(3, 1000)
1114
self.wait_rpm(1, 65, 75, minimum_duration=1)
1115
self.progress("Setting engine-start RC switch to LOW")
1116
self.set_rc(rc_engine_start_chan, 1000)
1117
self.wait_rpm(1, 0, 0, minimum_duration=1)
1118
# ICE provides forward thrust, which can make us think we're flying:
1119
self.disarm_vehicle(force=True)
1120
self.reboot_sitl()
1121
1122
self.start_subtest("Testing throttle out in manual mode")
1123
self.change_mode('MANUAL')
1124
self.set_rc(3, 1700)
1125
self.wait_servo_channel_value(3, 2000)
1126
self.set_parameter("ICE_OPTIONS", 4)
1127
# remember that throttle is reversed!
1128
self.wait_servo_channel_value(3, 1300)
1129
self.change_mode('FBWA')
1130
self.wait_servo_channel_value(3, 2000)
1131
1132
self.start_subtest("Testing automatic restart")
1133
# Limit start attempts to 4
1134
max_tries = 4
1135
self.set_parameter("ICE_STRT_MX_RTRY", max_tries)
1136
# Make the engine unable to run (by messing up the RPM sensor)
1137
rpm_chan = self.get_parameter("ICE_RPM_CHAN")
1138
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
1139
self.set_rc(rc_engine_start_chan, 2000)
1140
self.wait_statustext("Uncommanded engine stop")
1141
self.wait_statustext("Starting engine")
1142
# Restore the engine
1143
self.set_parameter("ICE_RPM_CHAN", rpm_chan)
1144
# Make sure the engine continues to run for the next 30 seconds
1145
try:
1146
self.wait_statustext("Uncommanded engine stop", timeout=30)
1147
# The desired result is for the wait_statustext raise AutoTestTimeoutException
1148
raise NotAchievedException("Engine stopped unexpectedly")
1149
except AutoTestTimeoutException:
1150
pass
1151
self.context_stop_collecting("STATUSTEXT")
1152
1153
self.start_subtest("Testing automatic starter attempt limit")
1154
# Try this test twice.
1155
# For the first run, since the engine has been running successfully in
1156
# the previous test for 30 seconds, the limit should reset. For the
1157
# second run, after commanding an engine stop, the limit should reset.
1158
for i in range(2):
1159
self.context_collect("STATUSTEXT")
1160
self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor
1161
self.set_rc(rc_engine_start_chan, 2000)
1162
self.wait_statustext("Engine max crank attempts reached", check_context=True, timeout=30)
1163
self.delay_sim_time(30) # wait for another 30 seconds to make sure the engine doesn't restart
1164
messages = self.context_get().collections["STATUSTEXT"]
1165
self.context_stop_collecting("STATUSTEXT")
1166
# check for the exact number of starter attempts
1167
attempts = 0
1168
for m in messages:
1169
if "Starting engine" == m.text:
1170
attempts += 1
1171
if attempts != max_tries:
1172
raise NotAchievedException(f"Run {i+1}: Expected {max_tries} attempts, got {attempts}")
1173
# Command an engine stop
1174
self.context_collect("STATUSTEXT")
1175
self.set_rc(rc_engine_start_chan, 1000)
1176
self.wait_statustext("ignition:0", check_context=True)
1177
self.context_stop_collecting("STATUSTEXT")
1178
1179
def ICEngineMission(self):
1180
'''Test ICE Engine Mission support'''
1181
rc_engine_start_chan = 11
1182
self.setup_ICEngine_vehicle()
1183
1184
self.load_mission("mission.txt")
1185
self.wait_ready_to_arm()
1186
self.set_rc(rc_engine_start_chan, 2000)
1187
self.arm_vehicle()
1188
self.change_mode('AUTO')
1189
self.wait_disarmed(timeout=300)
1190
1191
def MAV_CMD_DO_ENGINE_CONTROL(self):
1192
'''test MAV_CMD_DO_ENGINE_CONTROL mavlink command'''
1193
1194
expected_idle_rpm_min = 65
1195
expected_idle_rpm_max = 75
1196
expected_starter_rpm_min = 345
1197
expected_starter_rpm_max = 355
1198
1199
rc_engine_start_chan = 11
1200
self.setup_ICEngine_vehicle()
1201
1202
self.wait_ready_to_arm()
1203
1204
for method in self.run_cmd, self.run_cmd_int:
1205
self.change_mode('MANUAL')
1206
self.set_rc(rc_engine_start_chan, 1500) # allow motor to run
1207
self.wait_rpm(1, 0, 0, minimum_duration=1)
1208
self.arm_vehicle()
1209
self.wait_rpm(1, 0, 0, minimum_duration=1)
1210
self.start_subtest("Start motor")
1211
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1)
1212
self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max)
1213
self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=10)
1214
1215
# starting the motor while it is running is failure
1216
# (probably wrong, but that's how this works):
1217
self.start_subtest("try start motor again")
1218
self.context_collect('STATUSTEXT')
1219
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)
1220
self.wait_statustext("already running", check_context=True)
1221
self.context_stop_collecting('STATUSTEXT')
1222
# shouldn't affect run state:
1223
self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=1)
1224
1225
self.start_subtest("Stop motor")
1226
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1227
self.wait_rpm(1, 0, 0, minimum_duration=1)
1228
1229
self.start_subtest("Stop motor (again)")
1230
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1231
self.wait_rpm(1, 0, 0, minimum_duration=1)
1232
1233
self.start_subtest("Check start chan control disable")
1234
old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan)
1235
self.set_rc(rc_engine_start_chan, 1000)
1236
self.delay_sim_time(1) # Make sure the RC change has registered
1237
self.context_collect('STATUSTEXT')
1238
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)
1239
self.wait_statustext("start control disabled", check_context=True)
1240
self.context_stop_collecting('STATUSTEXT')
1241
self.set_rc(rc_engine_start_chan, old_start_channel_value)
1242
self.wait_rpm(1, 0, 0, minimum_duration=1)
1243
1244
self.start_subtest("test start-at-height")
1245
self.wait_rpm(1, 0, 0, minimum_duration=1)
1246
self.context_collect('STATUSTEXT')
1247
method(
1248
mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL,
1249
p1=1, # start
1250
p3=15.5, # ... at 15.5 metres
1251
)
1252
self.wait_statustext("height set to 15.5m", check_context=True)
1253
self.wait_rpm(1, 0, 0, minimum_duration=2)
1254
1255
self.takeoff(20, mode='GUIDED')
1256
self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max, minimum_duration=1)
1257
self.wait_statustext("Engine running", check_context=True)
1258
self.context_stop_collecting('STATUSTEXT')
1259
1260
# stop the motor again:
1261
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)
1262
self.wait_rpm(1, 0, 0, minimum_duration=1)
1263
1264
self.change_mode('QLAND')
1265
self.wait_disarmed()
1266
1267
def Ship(self):
1268
'''Ensure we can take off from simulated ship'''
1269
self.context_push()
1270
self.set_parameters({
1271
'SIM_SHIP_ENABLE': 1,
1272
'SIM_SHIP_SPEED': 1, # the default of 3 will break this test
1273
})
1274
self.change_mode('QLOITER')
1275
self.wait_ready_to_arm()
1276
self.arm_vehicle()
1277
self.set_rc(3, 1700)
1278
# self.delay_sim_time(1)
1279
# self.send_debug_trap()
1280
# output here is a bit weird as we also receive altitude from
1281
# the simulated ship....
1282
self.wait_altitude(20, 30, relative=True)
1283
self.disarm_vehicle(force=True)
1284
self.context_pop()
1285
self.reboot_sitl()
1286
1287
def MidAirDisarmDisallowed(self):
1288
'''Check disarm behaviour in Q-mode'''
1289
self.start_subtest("Basic arm in qloiter")
1290
self.set_parameter("FLIGHT_OPTIONS", 0)
1291
self.change_mode('QLOITER')
1292
self.wait_ready_to_arm()
1293
self.arm_vehicle()
1294
self.disarm_vehicle()
1295
1296
self.context_push()
1297
self.start_subtest("Ensure disarming in q-modes on ground works")
1298
self.set_parameter("FLIGHT_OPTIONS", 1 << 11)
1299
self.arm_vehicle()
1300
self.disarm_vehicle() # should be OK as we're not flying yet
1301
self.context_pop()
1302
1303
self.start_subtest("Ensure no disarming mid-air")
1304
self.arm_vehicle()
1305
self.set_rc(3, 2000)
1306
self.wait_altitude(5, 50, relative=True)
1307
self.set_rc(3, 1000)
1308
disarmed = False
1309
try:
1310
self.disarm_vehicle()
1311
disarmed = True
1312
except ValueError as e:
1313
self.progress("Got %s" % repr(e))
1314
if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e):
1315
raise e
1316
if disarmed:
1317
raise NotAchievedException("Disarmed when we shouldn't have")
1318
1319
self.change_mode('QLAND')
1320
self.wait_disarmed()
1321
1322
self.start_subtest("Check we can disarm after a short period on the ground")
1323
self.takeoff(5, 'QHOVER')
1324
self.change_mode('QLAND')
1325
try:
1326
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10)
1327
self.wait_extended_sys_state(
1328
landed_state=mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,
1329
vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC,
1330
timeout=60
1331
)
1332
except Exception:
1333
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 0)
1334
raise
1335
1336
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1)
1337
self.disarm_vehicle()
1338
1339
def MAV_CMD_NAV_LOITER_TO_ALT(self, target_system=1, target_component=1):
1340
'''ensure consecutive loiter to alts work'''
1341
self.load_mission('mission.txt')
1342
self.change_mode('AUTO')
1343
self.wait_ready_to_arm()
1344
self.arm_vehicle()
1345
self.wait_current_waypoint(4, timeout=240)
1346
self.assert_altitude(120, accuracy=5, relative=True)
1347
self.delay_sim_time(30)
1348
self.assert_altitude(120, accuracy=5, relative=True)
1349
self.set_current_waypoint(5)
1350
self.wait_altitude(altitude_min=65, altitude_max=75, relative=True)
1351
if self.current_waypoint() != 5:
1352
raise NotAchievedException("Should pass 90m before passing waypoint 5")
1353
self.wait_disarmed(timeout=300)
1354
1355
def Mission(self):
1356
'''fly the OBC 2016 mission in Dalby'''
1357
self.load_mission("Dalby-OBC2016.txt")
1358
self.load_fence("Dalby-OBC2016-fence.txt")
1359
if self.mavproxy is not None:
1360
self.mavproxy.send('wp list\n')
1361
self.install_terrain_handlers_context()
1362
self.wait_ready_to_arm()
1363
self.arm_vehicle()
1364
self.change_mode('AUTO')
1365
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
1366
1367
self.wait_disarmed(timeout=120) # give quadplane a long time to land
1368
# wait for blood sample here
1369
self.set_current_waypoint(20)
1370
self.wait_ready_to_arm()
1371
self.arm_vehicle()
1372
self.wait_waypoint(20, 34, max_dist=60, timeout=1200)
1373
1374
self.wait_disarmed(timeout=120) # give quadplane a long time to land
1375
self.progress("Mission OK")
1376
1377
def VTOLLandSpiral(self):
1378
'''check spiral-to-alt option for landing'''
1379
self.fly_mission('mission.txt')
1380
self.set_parameter('WP_LOITER_RAD', -self.get_parameter('WP_LOITER_RAD'))
1381
self.set_current_waypoint(0, check_afterwards=False)
1382
self.fly_mission('mission.txt')
1383
1384
def VTOLQuicktune(self):
1385
'''VTOL Quicktune'''
1386
self.install_applet_script_context("VTOL-quicktune.lua")
1387
1388
self.set_parameters({
1389
"SCR_ENABLE": 1,
1390
"SIM_SPEEDUP": 20, # need to give some cycles to lua
1391
"RC7_OPTION": 300,
1392
})
1393
1394
self.reboot_sitl()
1395
1396
self.context_collect('STATUSTEXT')
1397
self.set_parameters({
1398
"QUIK_ENABLE" : 1,
1399
"QUIK_DOUBLE_TIME" : 5, # run faster for autotest
1400
})
1401
1402
self.scripting_restart()
1403
self.wait_text("Quicktune for quadplane loaded", check_context=True)
1404
1405
self.wait_ready_to_arm()
1406
self.change_mode("QLOITER")
1407
self.arm_vehicle()
1408
self.takeoff(20, 'QLOITER')
1409
1410
# use rc switch to start tune
1411
self.set_rc(7, 1500)
1412
1413
self.wait_text("Tuning: starting tune", check_context=True)
1414
for axis in ['RLL', 'PIT', 'YAW']:
1415
self.wait_text("Starting %s tune" % axis, check_context=True)
1416
self.wait_text("Tuning: %s_D done" % axis, check_context=True, timeout=120)
1417
self.wait_text("Tuning: %s_P done" % axis, check_context=True, timeout=120)
1418
self.wait_text("Tuning: %s done" % axis, check_context=True, timeout=120)
1419
self.wait_text("Tuning: YAW done", check_context=True, timeout=120)
1420
1421
# to test aux function method, use aux fn for save
1422
self.run_auxfunc(300, 2)
1423
self.wait_text("Tuning: saved", check_context=True)
1424
self.change_mode("QLAND")
1425
1426
self.wait_disarmed(timeout=120)
1427
1428
def VTOLQuicktune_CPP(self):
1429
'''VTOL Quicktune in C++'''
1430
self.set_parameters({
1431
"RC7_OPTION": 181,
1432
"QWIK_ENABLE" : 1,
1433
"QWIK_DOUBLE_TIME" : 5, # run faster for autotest
1434
})
1435
1436
self.context_push()
1437
self.context_collect('STATUSTEXT')
1438
1439
# reduce roll/pitch gains by 2
1440
gain_mul = 0.5
1441
soften_params = ['Q_A_RAT_RLL_P', 'Q_A_RAT_RLL_I', 'Q_A_RAT_RLL_D',
1442
'Q_A_RAT_PIT_P', 'Q_A_RAT_PIT_I', 'Q_A_RAT_PIT_D',
1443
'Q_A_RAT_YAW_P', 'Q_A_RAT_YAW_I']
1444
1445
original_values = self.get_parameters(soften_params)
1446
1447
softened_values = {}
1448
for p in original_values.keys():
1449
softened_values[p] = original_values[p] * gain_mul
1450
self.set_parameters(softened_values)
1451
1452
self.wait_ready_to_arm()
1453
self.change_mode("QLOITER")
1454
self.set_rc(7, 1000)
1455
self.arm_vehicle()
1456
self.takeoff(20, 'QLOITER')
1457
1458
# use rc switch to start tune
1459
self.set_rc(7, 1500)
1460
1461
self.wait_text("Quicktune: starting tune", check_context=True)
1462
for axis in ['Roll', 'Pitch', 'Yaw']:
1463
self.wait_text("Starting %s tune" % axis, check_context=True)
1464
self.wait_text("Quicktune: %s D done" % axis, check_context=True, timeout=120)
1465
self.wait_text("Quicktune: %s P done" % axis, check_context=True, timeout=120)
1466
self.wait_text("Quicktune: %s done" % axis, check_context=True, timeout=120)
1467
1468
new_values = self.get_parameters(soften_params)
1469
for p in original_values.keys():
1470
threshold = 0.8 * original_values[p]
1471
self.progress("tuned param %s %.4f need %.4f" % (p, new_values[p], threshold))
1472
if new_values[p] < threshold:
1473
raise NotAchievedException(
1474
"parameter %s %.4f not increased over %.4f" %
1475
(p, new_values[p], threshold))
1476
1477
self.progress("ensure we are not overtuned")
1478
self.set_parameters({
1479
'SIM_ENGINE_MUL': 0.9,
1480
'SIM_ENGINE_FAIL': 1 << 0,
1481
})
1482
1483
self.delay_sim_time(5)
1484
1485
# and restore it
1486
self.set_parameter('SIM_ENGINE_MUL', 1)
1487
1488
for i in range(5):
1489
self.wait_heartbeat()
1490
1491
if self.statustext_in_collections("ABORTING"):
1492
raise NotAchievedException("tune has aborted, overtuned")
1493
1494
self.progress("using aux fn for save tune")
1495
1496
# to test aux function method, use aux fn for save
1497
self.run_auxfunc(181, 2)
1498
self.wait_text("Quicktune: saved", check_context=True)
1499
self.change_mode("QLAND")
1500
1501
self.wait_disarmed(timeout=120)
1502
self.set_parameter("QWIK_ENABLE", 0)
1503
self.context_pop()
1504
self.reboot_sitl()
1505
1506
def PrecisionLanding(self):
1507
'''VTOL precision landing'''
1508
1509
self.install_applet_script_context("plane_precland.lua")
1510
1511
here = self.mav.location()
1512
target = self.offset_location_ne(here, 20, 0)
1513
1514
self.set_parameters({
1515
"SCR_ENABLE": 1,
1516
"PLND_ENABLED": 1,
1517
"PLND_TYPE": 4,
1518
"SIM_PLD_ENABLE": 1,
1519
"SIM_PLD_LAT" : target.lat,
1520
"SIM_PLD_LON" : target.lng,
1521
"SIM_PLD_HEIGHT" : 0,
1522
"SIM_PLD_ALT_LMT" : 50,
1523
"SIM_PLD_DIST_LMT" : 30,
1524
"RNGFND1_TYPE": 100,
1525
"RNGFND1_PIN" : 0,
1526
"RNGFND1_SCALING" : 12.2,
1527
"RNGFND1_MAX_CM" : 5000,
1528
"RNGFND_LANDING" : 1,
1529
})
1530
1531
self.reboot_sitl()
1532
1533
self.set_parameters({
1534
"PLND_ALT_CUTOFF" : 5,
1535
"SIM_SPEEDUP" : 10,
1536
})
1537
1538
self.context_collect('STATUSTEXT')
1539
1540
self.scripting_restart()
1541
self.wait_text("PLND: Loaded", check_context=True)
1542
1543
self.wait_ready_to_arm()
1544
self.change_mode("GUIDED")
1545
self.arm_vehicle()
1546
self.takeoff(60, 'GUIDED')
1547
self.wait_altitude(58, 62, relative=True)
1548
self.drain_mav()
1549
self.change_mode("QRTL")
1550
1551
self.wait_text("PLND: Target Acquired", check_context=True, timeout=60)
1552
1553
self.wait_disarmed(timeout=180)
1554
loc2 = self.mav.location()
1555
error = self.get_distance(target, loc2)
1556
self.progress("Target error %.1fm" % error)
1557
if error > 2:
1558
raise NotAchievedException("too far from target %.1fm" % error)
1559
1560
def ShipLanding(self):
1561
'''ship landing test'''
1562
self.install_applet_script_context("plane_ship_landing.lua")
1563
1564
self.set_parameters({
1565
"SCR_ENABLE": 1,
1566
"SIM_SHIP_ENABLE": 1,
1567
"SIM_SHIP_SPEED": 5,
1568
"SIM_SHIP_DSIZE": 10,
1569
"FOLL_ENABLE": 1,
1570
"FOLL_SYSID": 17,
1571
"FOLL_OFS_TYPE": 1,
1572
"SIM_TERRAIN" : 0,
1573
"TERRAIN_ENABLE" : 0,
1574
})
1575
1576
self.load_mission("takeoff100.txt")
1577
1578
self.reboot_sitl(check_position=False)
1579
1580
self.context_collect('STATUSTEXT')
1581
self.set_parameters({
1582
"SHIP_ENABLE" : 1,
1583
"SIM_SPEEDUP" : 10,
1584
})
1585
1586
self.scripting_restart()
1587
self.wait_text("ShipLanding: loaded", check_context=True)
1588
1589
self.wait_ready_to_arm()
1590
self.change_mode("AUTO")
1591
self.arm_vehicle()
1592
self.wait_altitude(95, 105, relative=True, timeout=90)
1593
self.drain_mav()
1594
1595
self.wait_text("Mission complete, changing mode to RTL", check_context=True, timeout=60)
1596
self.wait_text("Descending for approach", check_context=True, timeout=60)
1597
self.wait_text("Reached target altitude", check_context=True, timeout=120)
1598
self.wait_text("Starting approach", check_context=True, timeout=120)
1599
self.wait_text("Land complete", check_context=True, timeout=120)
1600
1601
self.wait_disarmed(timeout=180)
1602
1603
# we confirm successful landing on the ship from our ground speed. The
1604
# deck is just 10m in size, so we must be within 10m if we are moving
1605
# with the deck
1606
self.wait_groundspeed(4.8, 5.2)
1607
1608
def RCDisableAirspeedUse(self):
1609
'''check disabling airspeed using RC switch'''
1610
self.set_parameter("RC9_OPTION", 106)
1611
self.delay_sim_time(5)
1612
self.set_rc(9, 1000)
1613
self.wait_sensor_state(
1614
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1615
True,
1616
True,
1617
True)
1618
self.set_rc(9, 2000)
1619
self.wait_sensor_state(
1620
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1621
True,
1622
False,
1623
True)
1624
self.set_rc(9, 1000)
1625
self.wait_sensor_state(
1626
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
1627
True,
1628
True,
1629
True)
1630
1631
self.progress("Disabling airspeed sensor")
1632
self.context_push()
1633
self.set_rc(9, 2000)
1634
self.set_parameters({
1635
"COMPASS_ENABLE": 0,
1636
"EK2_ENABLE": 0,
1637
"AHRS_EKF_TYPE": 3,
1638
"COMPASS_USE": 0,
1639
"COMPASS_USE2": 0,
1640
"COMPASS_USE3": 0,
1641
"ARMING_CHECK": 589818, # from a logfile, disables compass
1642
})
1643
1644
self.reboot_sitl()
1645
1646
self.context_collect('STATUSTEXT')
1647
self.wait_prearm_sys_status_healthy(timeout=120)
1648
self.change_mode('QLOITER')
1649
self.arm_vehicle()
1650
self.set_rc(3, 2000)
1651
self.wait_altitude(10, 30, relative=True)
1652
self.change_mode('FBWA')
1653
self.wait_statustext('Transition done')
1654
# the vehicle stays in DCM until there's velocity - make sure
1655
# we did go to EK3 evenutally, 'though:
1656
self.wait_statustext('EKF3 active', check_context=True)
1657
1658
self.disarm_vehicle(force=True)
1659
self.context_pop()
1660
self.reboot_sitl()
1661
1662
def mission_MAV_CMD_DO_VTOL_TRANSITION(self):
1663
'''mission item forces transition'''
1664
wps = self.create_simple_relhome_mission([
1665
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1666
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, 30),
1667
self.create_MISSION_ITEM_INT(
1668
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
1669
p1=mavutil.mavlink.MAV_VTOL_STATE_MC
1670
),
1671
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 200, 30),
1672
self.create_MISSION_ITEM_INT(
1673
mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,
1674
p1=mavutil.mavlink.MAV_VTOL_STATE_FW
1675
),
1676
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 100, 200, 30),
1677
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1678
])
1679
self.check_mission_upload_download(wps)
1680
1681
self.change_mode('AUTO')
1682
self.wait_ready_to_arm()
1683
1684
self.arm_vehicle()
1685
self.wait_current_waypoint(4)
1686
self.wait_servo_channel_value(5, 1200, comparator=operator.gt)
1687
self.wait_current_waypoint(6)
1688
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1689
1690
self.fly_home_land_and_disarm()
1691
1692
def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self):
1693
'''mavlink command forces transition during mission'''
1694
wps = self.create_simple_relhome_mission([
1695
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1696
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1697
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1698
])
1699
self.check_mission_upload_download(wps)
1700
1701
self.change_mode('AUTO')
1702
self.wait_ready_to_arm()
1703
1704
self.arm_vehicle()
1705
self.wait_current_waypoint(2)
1706
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1707
1708
for command in self.run_cmd, self.run_cmd_int:
1709
command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_MC)
1710
self.wait_servo_channel_value(5, 1200, comparator=operator.gt, timeout=300)
1711
command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_FW)
1712
self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)
1713
1714
self.fly_home_land_and_disarm()
1715
1716
def TransitionMinThrottle(self):
1717
'''Ensure that TKOFF_THR_MIN is applied during the forward transition'''
1718
wps = self.create_simple_relhome_mission([
1719
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1720
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1721
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1722
])
1723
self.check_mission_upload_download(wps)
1724
self.set_parameter('TKOFF_THR_MIN', 80)
1725
1726
self.change_mode('AUTO')
1727
self.wait_ready_to_arm()
1728
1729
self.arm_vehicle()
1730
self.wait_current_waypoint(2)
1731
# Wait for 5 seconds into the transition.
1732
self.delay_sim_time(5)
1733
# Ensure TKOFF_THR_MIN is still respected.
1734
thr_min = self.get_parameter('TKOFF_THR_MIN')
1735
self.wait_servo_channel_value(3, 1000+thr_min*10, comparator=operator.eq)
1736
1737
self.fly_home_land_and_disarm()
1738
1739
def BackTransitionMinThrottle(self):
1740
'''Ensure min throttle is applied during back transition.'''
1741
wps = self.create_simple_relhome_mission([
1742
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1743
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),
1744
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
1745
])
1746
self.check_mission_upload_download(wps)
1747
self.set_parameter('Q_RTL_MODE', 1)
1748
1749
trim_pwm = 1000 + 10*self.get_parameter("TRIM_THROTTLE")
1750
min_pwm = 1000 + 10*self.get_parameter("THR_MIN")
1751
1752
self.change_mode('AUTO')
1753
self.wait_ready_to_arm()
1754
1755
self.arm_vehicle()
1756
self.context_collect('STATUSTEXT')
1757
1758
self.wait_statustext("VTOL airbrake", check_context=True, timeout=300)
1759
self.wait_servo_channel_value(3, trim_pwm, comparator=operator.le, timeout=1)
1760
1761
self.wait_statustext("VTOL position1", check_context=True, timeout=10)
1762
self.wait_servo_channel_value(3, min_pwm+10, comparator=operator.le, timeout=1)
1763
1764
self.wait_disarmed(timeout=60)
1765
1766
def MAV_CMD_NAV_TAKEOFF(self):
1767
'''test issuing takeoff command via mavlink'''
1768
self.change_mode('GUIDED')
1769
self.wait_ready_to_arm()
1770
1771
self.arm_vehicle()
1772
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=5)
1773
self.wait_altitude(4.5, 5.5, minimum_duration=5, relative=True)
1774
self.change_mode('QLAND')
1775
self.wait_disarmed()
1776
1777
self.start_subtest("Check NAV_TAKEOFF is above current location, not home location")
1778
self.change_mode('GUIDED')
1779
self.wait_ready_to_arm()
1780
1781
# reset home 20 metres above current location
1782
current_alt_abs = self.get_altitude(relative=False)
1783
1784
loc = self.mav.location()
1785
1786
home_z_ofs = 20
1787
self.run_cmd(
1788
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
1789
p5=loc.lat,
1790
p6=loc.lng,
1791
p7=current_alt_abs + home_z_ofs,
1792
)
1793
1794
self.arm_vehicle()
1795
takeoff_alt = 5
1796
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=takeoff_alt)
1797
self.wait_altitude(
1798
current_alt_abs + takeoff_alt - 0.5,
1799
current_alt_abs + takeoff_alt + 0.5,
1800
minimum_duration=5,
1801
relative=False,
1802
)
1803
self.change_mode('QLAND')
1804
self.wait_disarmed()
1805
1806
self.reboot_sitl() # unlock home position
1807
1808
def Q_GUIDED_MODE(self):
1809
'''test moving in VTOL mode with SET_POSITION_TARGET_GLOBAL_INT'''
1810
self.set_parameter('Q_GUIDED_MODE', 1)
1811
self.change_mode('GUIDED')
1812
self.wait_ready_to_arm()
1813
self.arm_vehicle()
1814
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=15)
1815
self.wait_altitude(14, 16, relative=True)
1816
1817
loc = self.mav.location()
1818
self.location_offset_ne(loc, 50, 50)
1819
1820
# set position target
1821
self.run_cmd_int(
1822
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1823
0,
1824
1, # reposition flags; 1 means "change to guided"
1825
0,
1826
0,
1827
int(loc.lat * 1e7),
1828
int(loc.lng * 1e7),
1829
30, # alt
1830
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
1831
)
1832
self.wait_location(loc, timeout=120)
1833
1834
self.fly_home_land_and_disarm()
1835
1836
def DCMClimbRate(self):
1837
'''Test the climb rate measurement in DCM with and without GPS'''
1838
self.wait_ready_to_arm()
1839
1840
self.change_mode('QHOVER')
1841
self.arm_vehicle()
1842
self.set_rc(3, 2000)
1843
self.wait_altitude(30, 50, relative=True)
1844
1845
# Start Descending
1846
self.set_rc(3, 1000)
1847
self.wait_climbrate(-5, -0.5, timeout=10)
1848
1849
# Switch to DCM
1850
self.set_parameter('AHRS_EKF_TYPE', 0)
1851
self.delay_sim_time(5)
1852
1853
# Start Climbing
1854
self.set_rc(3, 2000)
1855
self.wait_climbrate(0.5, 5, timeout=10)
1856
1857
# Kill any GPSs
1858
self.set_parameters({
1859
'SIM_GPS1_ENABLE': 0,
1860
'SIM_GPS2_ENABLE': 0,
1861
})
1862
self.delay_sim_time(5)
1863
1864
# Start Descending
1865
self.set_rc(3, 1000)
1866
self.wait_climbrate(-5, -0.5, timeout=10)
1867
1868
# Force disarm
1869
self.disarm_vehicle(force=True)
1870
1871
def RTL_AUTOLAND_1(self):
1872
'''test behaviour when RTL_AUTOLAND==1'''
1873
1874
self.set_parameters({
1875
"RTL_AUTOLAND": 1,
1876
})
1877
1878
# when RTL is entered and RTL_AUTOLAND is 1 we should fly home
1879
# then to the landing sequence. This mission puts the landing
1880
# sequence well to the West of home so if we go directly there
1881
# we won't come within 200m of home
1882
wps = self.create_simple_relhome_mission([
1883
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
1884
# fly North
1885
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),
1886
# add a waypoint 1km North (which we will look for and trigger RTL
1887
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),
1888
1889
# *exciting* landing sequence is ~1km West and points away from Home.
1890
self.create_MISSION_ITEM_INT(
1891
mavutil.mavlink.MAV_CMD_DO_LAND_START,
1892
),
1893
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),
1894
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),
1895
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),
1896
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),
1897
])
1898
self.check_mission_upload_download(wps)
1899
1900
self.change_mode('AUTO')
1901
self.wait_ready_to_arm()
1902
1903
self.arm_vehicle()
1904
self.wait_current_waypoint(3) # will be 2km North here
1905
self.change_mode('RTL')
1906
1907
self.wait_distance_to_home(100, 200, timeout=120)
1908
self.wait_current_waypoint(7)
1909
1910
self.fly_home_land_and_disarm()
1911
1912
def send_reposition_to_loc(self, loc):
1913
self.run_cmd_int(
1914
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
1915
0,
1916
1, # reposition flags; 1 means "change to guided"
1917
0,
1918
0,
1919
int(loc.lat * 1e7),
1920
int(loc.lng * 1e7),
1921
20, # alt
1922
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
1923
)
1924
1925
def reposition_to_loc(self, loc, accuracy=100):
1926
self.send_reposition_to_loc(loc)
1927
self.wait_location(
1928
loc,
1929
accuracy=accuracy,
1930
minimum_duration=20,
1931
timeout=120,
1932
)
1933
1934
def AHRSFlyForwardFlag(self):
1935
'''ensure FlyForward flag is set appropriately'''
1936
self.set_parameters({
1937
"LOG_DISARMED": 1,
1938
"LOG_REPLAY": 1,
1939
})
1940
self.reboot_sitl()
1941
1942
self.assert_mode_is('FBWA')
1943
self.delay_sim_time(10)
1944
self.change_mode('QHOVER')
1945
self.delay_sim_time(10)
1946
1947
self.wait_ready_to_arm()
1948
self.arm_vehicle()
1949
self.set_rc(3, 2000)
1950
self.wait_altitude(20, 50, relative=True)
1951
self.context_collect('STATUSTEXT')
1952
self.change_mode('CRUISE')
1953
self.set_rc(3, 1500)
1954
self.wait_statustext('Transition started airspeed', check_context=True)
1955
self.wait_statustext('Transition airspeed reached', check_context=True)
1956
self.wait_statustext('Transition done', check_context=True)
1957
self.delay_sim_time(5)
1958
self.change_mode('QHOVER')
1959
self.wait_airspeed(0, 5)
1960
self.delay_sim_time(5)
1961
mlog_path = self.current_onboard_log_filepath()
1962
self.fly_home_land_and_disarm(timeout=600)
1963
1964
mlog = self.dfreader_for_path(mlog_path)
1965
1966
stage_require_fbwa = "require_fbwa"
1967
stage_wait_qhover = "wait_qhover"
1968
stage_verify_qhover_ff = "verify_qhover_ff"
1969
stage_wait_cruise = "wait_cruise"
1970
stage_cruise_wait_ff = "cruise_wait_ff"
1971
stage_qhover2 = "qhover2"
1972
stage_done = "done"
1973
stage = stage_require_fbwa
1974
msgs = {}
1975
seen_flag_set_in_cruise = False
1976
FF_BIT_MASK = (1 << 2)
1977
while stage != stage_done:
1978
m = mlog.recv_match()
1979
if m is None:
1980
raise NotAchievedException(f"Stuck in stage {stage}")
1981
m_type = m.get_type()
1982
msgs[m_type] = m
1983
1984
if stage == stage_require_fbwa:
1985
if m_type == 'MODE':
1986
if m.ModeNum == self.get_mode_from_mode_mapping('MANUAL'):
1987
# manual to start with
1988
continue
1989
fbwa_num = self.get_mode_from_mode_mapping('FBWA')
1990
print(f"{m.ModeNum=} {fbwa_num=}")
1991
if m.ModeNum != fbwa_num:
1992
raise ValueError(f"wanted mode={fbwa_num} got={m.ModeNum}")
1993
continue
1994
if m_type == 'RFRN':
1995
if not m.Flags & FF_BIT_MASK:
1996
raise ValueError("Expected FF to be set in FBWA")
1997
stage = stage_wait_qhover
1998
continue
1999
continue
2000
2001
if stage == stage_wait_qhover:
2002
if m_type == 'MODE':
2003
qhover_num = self.get_mode_from_mode_mapping('QHOVER')
2004
print(f"want={qhover_num} got={m.ModeNum}")
2005
if m.ModeNum == qhover_num:
2006
stage = stage_verify_qhover_ff
2007
continue
2008
continue
2009
continue
2010
2011
if stage == stage_verify_qhover_ff:
2012
if m_type == 'RFRN':
2013
if m.Flags & FF_BIT_MASK:
2014
raise ValueError("Expected FF to be unset in QHOVER")
2015
stage = stage_wait_cruise
2016
continue
2017
continue
2018
2019
if stage == stage_wait_cruise:
2020
if m_type == 'MODE':
2021
want_num = self.get_mode_from_mode_mapping('CRUISE')
2022
if m.ModeNum == want_num:
2023
stage = stage_cruise_wait_ff
2024
cruise_wait_ff_start = msgs['ATT'].TimeUS*1e-6
2025
continue
2026
continue
2027
continue
2028
2029
if stage == stage_cruise_wait_ff:
2030
if m_type == 'MODE':
2031
want_num = self.get_mode_from_mode_mapping('CRUISE')
2032
if want_num != m.ModeNum:
2033
if not seen_flag_set_in_cruise:
2034
raise ValueError("Never saw FF get set")
2035
if m.ModeNum == self.get_mode_from_mode_mapping('QHOVER'):
2036
stage = stage_qhover2
2037
continue
2038
continue
2039
if m_type == 'RFRN':
2040
flag_set = m.Flags & FF_BIT_MASK
2041
now = msgs['ATT'].TimeUS*1e-6
2042
delta_t = now - cruise_wait_ff_start
2043
if delta_t < 8:
2044
if flag_set:
2045
raise ValueError("Should not see bit set")
2046
if delta_t > 10:
2047
if not flag_set and not seen_flag_set_in_cruise:
2048
raise ValueError("Should see bit set")
2049
seen_flag_set_in_cruise = True
2050
continue
2051
continue
2052
2053
if stage == stage_qhover2:
2054
'''bit should stay low for qhover 2'''
2055
if m_type == 'RFRN':
2056
flag_set = m.Flags & FF_BIT_MASK
2057
if flag_set:
2058
raise ValueError("ff should be low in qhover")
2059
continue
2060
if m_type == 'MODE':
2061
if m.ModeNum != self.get_mode_from_mode_mapping('QHOVER'):
2062
stage = stage_done
2063
continue
2064
continue
2065
continue
2066
2067
raise NotAchievedException("Bad stage")
2068
2069
def RTL_AUTOLAND_1_FROM_GUIDED(self):
2070
'''test behaviour when RTL_AUTOLAND==1 and entering from guided'''
2071
2072
self.set_parameters({
2073
"RTL_AUTOLAND": 1,
2074
})
2075
2076
# when RTL is entered and RTL_AUTOLAND is 1 we should fly home
2077
# then to the landing sequence. This mission puts the landing
2078
# sequence well to the West of home so if we go directly there
2079
# we won't come within 200m of home
2080
wps = self.create_simple_relhome_mission([
2081
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
2082
# fly North
2083
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),
2084
# add a waypoint 1km North (which we will look for and trigger RTL
2085
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),
2086
2087
# *exciting* landing sequence is ~1km West and points away from Home.
2088
self.create_MISSION_ITEM_INT(
2089
mavutil.mavlink.MAV_CMD_DO_LAND_START,
2090
),
2091
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),
2092
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),
2093
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),
2094
(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),
2095
])
2096
self.check_mission_upload_download(wps)
2097
self.set_current_waypoint(0, check_afterwards=False)
2098
2099
self.change_mode('AUTO')
2100
self.wait_ready_to_arm()
2101
2102
here = self.mav.location()
2103
guided_loc = self.offset_location_ne(here, 500, -500)
2104
2105
self.arm_vehicle()
2106
self.wait_current_waypoint(3) # will be 2km North here
2107
self.reposition_to_loc(guided_loc)
2108
self.send_cmd_do_set_mode('RTL')
2109
2110
self.wait_distance_to_home(100, 200, timeout=120)
2111
self.wait_current_waypoint(7)
2112
2113
self.fly_home_land_and_disarm()
2114
2115
def WindEstimateConsistency(self):
2116
'''test that DCM and EKF3 roughly agree on wind speed and direction'''
2117
self.set_parameters({
2118
'SIM_WIND_SPD': 10, # metres/second
2119
'SIM_WIND_DIR': 315, # from the North-West
2120
})
2121
self.change_mode('TAKEOFF')
2122
self.wait_ready_to_arm()
2123
self.arm_vehicle()
2124
self.delay_sim_time(180)
2125
mlog = self.dfreader_for_current_onboard_log()
2126
self.fly_home_land_and_disarm()
2127
2128
self.progress("Inspecting dataflash log")
2129
match_start_time = None
2130
dcm = None
2131
xkf2 = None
2132
while True:
2133
m = mlog.recv_match(
2134
type=['DCM', 'XKF2'],
2135
blocking=True,
2136
)
2137
if m is None:
2138
raise NotAchievedException("Did not see wind estimates match")
2139
2140
m_type = m.get_type()
2141
if m_type == 'DCM':
2142
dcm = m
2143
else:
2144
xkf2 = m
2145
if dcm is None or xkf2 is None:
2146
continue
2147
2148
now = m.TimeUS * 1e-6
2149
2150
matches_east = abs(dcm.VWE-xkf2.VWE) < 1.5
2151
matches_north = abs(dcm.VWN-xkf2.VWN) < 1.5
2152
2153
matches = matches_east and matches_north
2154
2155
if not matches:
2156
match_start_time = None
2157
continue
2158
2159
if match_start_time is None:
2160
match_start_time = now
2161
continue
2162
2163
if now - match_start_time > 60:
2164
self.progress("Wind estimates correlated")
2165
break
2166
2167
def tests(self):
2168
'''return list of all tests'''
2169
2170
ret = super(AutoTestQuadPlane, self).tests()
2171
ret.extend([
2172
self.FwdThrInVTOL,
2173
self.AirMode,
2174
self.TestMotorMask,
2175
self.PilotYaw,
2176
self.ParameterChecks,
2177
self.QAUTOTUNE,
2178
self.TestLogDownload,
2179
self.TestLogDownloadWrap,
2180
self.EXTENDED_SYS_STATE,
2181
self.Mission,
2182
self.Weathervane,
2183
self.QAssist,
2184
self.GyroFFT,
2185
self.Tailsitter,
2186
self.CopterTailsitter,
2187
self.ICEngine,
2188
self.ICEngineMission,
2189
self.MAV_CMD_DO_ENGINE_CONTROL,
2190
self.MidAirDisarmDisallowed,
2191
self.GUIDEDToAUTO,
2192
self.BootInAUTO,
2193
self.Ship,
2194
self.WindEstimateConsistency,
2195
self.MAV_CMD_NAV_LOITER_TO_ALT,
2196
self.LoiterAltQLand,
2197
self.VTOLLandSpiral,
2198
self.VTOLQuicktune,
2199
self.VTOLQuicktune_CPP,
2200
self.PrecisionLanding,
2201
self.ShipLanding,
2202
Test(self.MotorTest, kwargs={ # tests motors 4 and 2
2203
"mot1_servo_chan": 8, # quad-x second motor cw from f-r
2204
"mot4_servo_chan": 6, # quad-x third motor cw from f-r
2205
"wait_finish_text": False,
2206
"quadplane": True,
2207
}),
2208
self.RCDisableAirspeedUse,
2209
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
2210
self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,
2211
self.TransitionMinThrottle,
2212
self.BackTransitionMinThrottle,
2213
self.MAV_CMD_NAV_TAKEOFF,
2214
self.Q_GUIDED_MODE,
2215
self.DCMClimbRate,
2216
self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence
2217
self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence
2218
self.AHRSFlyForwardFlag,
2219
])
2220
return ret
2221
2222