mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: add test for tailsitter throttle
This commit is contained in:
parent
d15e01d390
commit
4b3adb806c
@ -4995,6 +4995,24 @@ class AutoTest(ABC):
|
||||
**kwargs
|
||||
)
|
||||
|
||||
def get_servo_channel_value(self, channel, timeout=2):
|
||||
channel_field = "servo%u_raw" % channel
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
remaining = timeout - (self.get_sim_time_cached() - tstart)
|
||||
if remaining <= 0:
|
||||
raise NotAchievedException("Channel value condition not met")
|
||||
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
|
||||
blocking=True,
|
||||
timeout=remaining)
|
||||
if m is None:
|
||||
continue
|
||||
m_value = getattr(m, channel_field, None)
|
||||
if m_value is None:
|
||||
raise ValueError("message (%s) has no field %s" %
|
||||
(str(m), channel_field))
|
||||
return m_value
|
||||
|
||||
def wait_servo_channel_value(self, channel, value, timeout=2, comparator=operator.eq):
|
||||
"""wait for channel value comparison (default condition is equality)"""
|
||||
channel_field = "servo%u_raw" % channel
|
||||
|
@ -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):
|
||||
("GyroFFT", "Fly Gyro FFT",
|
||||
self.fly_gyro_fft),
|
||||
|
||||
("Tailsitter",
|
||||
"Test tailsitter support",
|
||||
self.tailsitter),
|
||||
|
||||
|
||||
("LogUpload",
|
||||
"Log upload",
|
||||
self.log_upload),
|
||||
|
Loading…
Reference in New Issue
Block a user