mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
autotest: make and declare quadplane.py flake8-clean
This commit is contained in:
parent
c13d229877
commit
05c9b79a5e
@ -1,6 +1,10 @@
|
|||||||
#!/usr/bin/env python
|
'''
|
||||||
|
Fly ArduPlane QuadPlane in SITL
|
||||||
|
|
||||||
|
AP_FLAKE8_CLEAN
|
||||||
|
|
||||||
|
'''
|
||||||
|
|
||||||
# Fly ArduPlane QuadPlane in SITL
|
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
import os
|
import os
|
||||||
import numpy
|
import numpy
|
||||||
@ -11,7 +15,6 @@ from pymavlink import mavutil
|
|||||||
from common import AutoTest
|
from common import AutoTest
|
||||||
from common import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException
|
from common import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException
|
||||||
|
|
||||||
from pysim import vehicleinfo
|
|
||||||
import operator
|
import operator
|
||||||
|
|
||||||
|
|
||||||
@ -164,7 +167,24 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.set_parameter("AHRS_TRIM_X", math.radians(-60))
|
self.set_parameter("AHRS_TRIM_X", math.radians(-60))
|
||||||
self.wait_roll(60, 1)
|
self.wait_roll(60, 1)
|
||||||
# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE
|
# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE
|
||||||
for mode in ('QLOITER', 'QHOVER', 'CIRCLE', 'STABILIZE', 'TRAINING', 'ACRO', 'FBWA', 'FBWB', 'CRUISE', 'AUTOTUNE', 'RTL', 'LOITER', 'AVOID_ADSB', 'GUIDED', 'QLAND', 'QRTL'):
|
for mode in (
|
||||||
|
'ACRO',
|
||||||
|
'AUTOTUNE',
|
||||||
|
'AVOID_ADSB',
|
||||||
|
'CIRCLE',
|
||||||
|
'CRUISE',
|
||||||
|
'FBWA',
|
||||||
|
'FBWB',
|
||||||
|
'GUIDED',
|
||||||
|
'LOITER',
|
||||||
|
'QHOVER',
|
||||||
|
'QLAND',
|
||||||
|
'QLOITER',
|
||||||
|
'QRTL',
|
||||||
|
'RTL',
|
||||||
|
'STABILIZE',
|
||||||
|
'TRAINING',
|
||||||
|
):
|
||||||
self.progress("Testing %s mode" % mode)
|
self.progress("Testing %s mode" % mode)
|
||||||
self.change_mode(mode)
|
self.change_mode(mode)
|
||||||
self.zero_throttle()
|
self.zero_throttle()
|
||||||
@ -231,7 +251,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
|
|
||||||
|
|
||||||
def test_motor_mask(self):
|
def test_motor_mask(self):
|
||||||
"""Check operation of output_motor_mask"""
|
"""Check operation of output_motor_mask"""
|
||||||
"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""
|
"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""
|
||||||
@ -314,7 +333,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.mavproxy.send('disarm\n')
|
self.mavproxy.send('disarm\n')
|
||||||
try:
|
try:
|
||||||
self.wait_text("AutoTune: Saved gains for Roll Pitch Yaw", timeout=0.5)
|
self.wait_text("AutoTune: Saved gains for Roll Pitch Yaw", timeout=0.5)
|
||||||
except AutoTestTimeoutException as e:
|
except AutoTestTimeoutException:
|
||||||
continue
|
continue
|
||||||
break
|
break
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
@ -468,7 +487,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
"FFT_SNR_REF": 10,
|
"FFT_SNR_REF": 10,
|
||||||
"FFT_WINDOW_SIZE": 128,
|
"FFT_WINDOW_SIZE": 128,
|
||||||
"FFT_WINDOW_OLAP": 0.75,
|
"FFT_WINDOW_OLAP": 0.75,
|
||||||
});
|
})
|
||||||
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
|
# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft
|
||||||
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
|
# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so
|
||||||
# a 250Hz peak should be detectable within 5%
|
# a 250Hz peak should be detectable within 5%
|
||||||
|
Loading…
Reference in New Issue
Block a user