|
|
|
@ -406,6 +406,18 @@ class AutoTestQuadPlane(AutoTest):
@@ -406,6 +406,18 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
"CPUFailsafe": "servo channel values not scaled like ArduPlane", |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
def test_pilot_yaw(self): |
|
|
|
|
self.takeoff(10, mode="QLOITER") |
|
|
|
|
self.set_parameter("STICK_MIXING", 0) |
|
|
|
|
self.set_rc(4, 1700) |
|
|
|
|
for mode in "QLOITER", "QHOVER": |
|
|
|
|
self.wait_heading(45) |
|
|
|
|
self.wait_heading(90) |
|
|
|
|
self.wait_heading(180) |
|
|
|
|
self.wait_heading(275) |
|
|
|
|
self.set_rc(4, 1500) |
|
|
|
|
self.do_RTL() |
|
|
|
|
|
|
|
|
|
def CPUFailsafe(self): |
|
|
|
|
'''In lockup Plane should copy RC inputs to RC outputs''' |
|
|
|
|
self.plane_CPUFailsafe() |
|
|
|
@ -450,6 +462,10 @@ class AutoTestQuadPlane(AutoTest):
@@ -450,6 +462,10 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
ret.extend([ |
|
|
|
|
("TestMotorMask", "Test output_motor_mask", self.test_motor_mask), |
|
|
|
|
|
|
|
|
|
("PilotYaw", |
|
|
|
|
"Test pilot yaw in various modes", |
|
|
|
|
self.test_pilot_yaw), |
|
|
|
|
|
|
|
|
|
("ParameterChecks", |
|
|
|
|
"Test Arming Parameter Checks", |
|
|
|
|
self.test_parameter_checks), |
|
|
|
|