autotest: assert ArduPilot announces compass cal capability

This commit is contained in:
Peter Barker 2019-10-29 11:50:24 +11:00 committed by Andrew Tridgell
parent b9dbfff0d0
commit 7dda87fd44
3 changed files with 4 additions and 3 deletions

View File

@ -4792,7 +4792,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
("GetCapabilities",
"Get Capabilities",
self.do_get_autopilot_capabilities),
self.test_get_autopilot_capabilities),
("DO_SET_MODE",
"Set mode via MAV_COMMAND_DO_SET_MODE",

View File

@ -117,7 +117,7 @@ inherit Rover's tests!'''
("GetCapabilities",
"Get Capabilities",
self.do_get_autopilot_capabilities),
self.test_get_autopilot_capabilities),
("DO_SET_MODE",
"Set mode via MAV_COMMAND_DO_SET_MODE",

View File

@ -1548,8 +1548,9 @@ class AutoTest(ABC):
raise NotAchievedException("Did not get AUTOPILOT_VERSION")
return m.capabilities
def do_get_autopilot_capabilities(self):
def test_get_autopilot_capabilities(self):
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT)
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION)
def get_mode_from_mode_mapping(self, mode):
"""Validate and return the mode number from a string or int."""