|
|
|
@ -660,6 +660,27 @@ class AutoTestQuadPlane(AutoTest):
@@ -660,6 +660,27 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
self.change_mode("RTL") |
|
|
|
|
self.wait_disarmed(timeout=300) |
|
|
|
|
|
|
|
|
|
def tailsitter(self): |
|
|
|
|
'''tailsitter test''' |
|
|
|
|
self.set_parameter('Q_FRAME_CLASS', 10) |
|
|
|
|
self.set_parameter('Q_ENABLE', 1) |
|
|
|
|
|
|
|
|
|
self.reboot_sitl() |
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
value_before = self.get_servo_channel_value(3) |
|
|
|
|
self.progress("Before: %u" % value_before) |
|
|
|
|
self.change_mode('QHOVER') |
|
|
|
|
tstart = self.get_sim_time() |
|
|
|
|
while True: |
|
|
|
|
now = self.get_sim_time_cached() |
|
|
|
|
if now - tstart > 60: |
|
|
|
|
break |
|
|
|
|
value_after = self.get_servo_channel_value(3) |
|
|
|
|
self.progress("After: t=%f output=%u" % ((now - tstart), value_after)) |
|
|
|
|
if value_before != value_after: |
|
|
|
|
raise NotAchievedException("Changed throttle output on mode change to QHOVER") |
|
|
|
|
self.disarm_vehicle() |
|
|
|
|
|
|
|
|
|
def tests(self): |
|
|
|
|
'''return list of all tests''' |
|
|
|
|
|
|
|
|
@ -691,6 +712,11 @@ class AutoTestQuadPlane(AutoTest):
@@ -691,6 +712,11 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
("GyroFFT", "Fly Gyro FFT", |
|
|
|
|
self.fly_gyro_fft), |
|
|
|
|
|
|
|
|
|
("Tailsitter", |
|
|
|
|
"Test tailsitter support", |
|
|
|
|
self.tailsitter), |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
("LogUpload", |
|
|
|
|
"Log upload", |
|
|
|
|
self.log_upload), |
|
|
|
|