mirror of https://github.com/ArduPilot/ardupilot
autotest: augment WaitAndMaintain class, add WaitAndMaintainArmed
This commit is contained in:
parent
6dccdde660
commit
0f67535350
|
@ -400,6 +400,18 @@ class WaitAndMaintain(object):
|
|||
text += f" (maintain={delta:.1f}/{self.minimum_duration})"
|
||||
self.progress(text)
|
||||
|
||||
def progress_text(self, value):
|
||||
return f"want={self.get_target_value()} got={value}"
|
||||
|
||||
def validate_value(self, value):
|
||||
return value == self.get_target_value()
|
||||
|
||||
def timeoutexception(self):
|
||||
return AutoTestTimeoutException("Failed to attain or maintain value")
|
||||
|
||||
def success_text(self):
|
||||
return f"{type(self)} Success"
|
||||
|
||||
|
||||
class WaitAndMaintainLocation(WaitAndMaintain):
|
||||
def __init__(self, test_suite, target, accuracy=5, height_accuracy=1, **kwargs):
|
||||
|
@ -453,6 +465,17 @@ class WaitAndMaintainLocation(WaitAndMaintain):
|
|||
return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}")
|
||||
|
||||
|
||||
class WaitAndMaintainArmed(WaitAndMaintain):
|
||||
def get_current_value(self):
|
||||
return self.test_suite.armed()
|
||||
|
||||
def get_target_value(self):
|
||||
return True
|
||||
|
||||
def announce_start_text(self):
|
||||
return "Ensuring vehicle remains armed"
|
||||
|
||||
|
||||
class MSP_Generic(Telem):
|
||||
def __init__(self, destination_address):
|
||||
super(MSP_Generic, self).__init__(destination_address)
|
||||
|
|
Loading…
Reference in New Issue