autotest: test MAV_CMD_DO_AUX_FUNCTION as both COMMAND_LONG and COMMAND_INT

This commit is contained in:
Peter Barker 2023-10-03 18:04:47 +11:00 committed by Andrew Tridgell
parent 57c2f7b2de
commit 4adc3fb25f
2 changed files with 18 additions and 8 deletions

View File

@ -3793,29 +3793,36 @@ class AutoTestPlane(AutoTest):
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6) attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6)
attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7) attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7)
def MAV_DO_AUX_FUNCTION(self): def _MAV_CMD_DO_AUX_FUNCTION(self, run_cmd):
'''Test triggering Auxiliary Functions via mavlink''' '''Test triggering Auxiliary Functions via mavlink'''
self.context_collect('STATUSTEXT') self.context_collect('STATUSTEXT')
self.run_auxfunc(64, 2) # 64 == reverse throttle self.run_auxfunc(64, 2, run_cmd=run_cmd) # 64 == reverse throttle
self.wait_statustext("RevThrottle: ENABLE", check_context=True) self.wait_statustext("RevThrottle: ENABLE", check_context=True)
self.run_auxfunc(64, 0) self.run_auxfunc(64, 0, run_cmd=run_cmd)
self.wait_statustext("RevThrottle: DISABLE", check_context=True) self.wait_statustext("RevThrottle: DISABLE", check_context=True)
self.run_auxfunc(65, 2) # 65 == GPS_DISABLE self.run_auxfunc(65, 2, run_cmd=run_cmd) # 65 == GPS_DISABLE
self.start_subtest("Bad auxfunc") self.start_subtest("Bad auxfunc")
self.run_auxfunc( self.run_auxfunc(
65231, 65231,
2, 2,
want_result=mavutil.mavlink.MAV_RESULT_FAILED want_result=mavutil.mavlink.MAV_RESULT_FAILED,
run_cmd=run_cmd,
) )
self.start_subtest("Bad switchpos") self.start_subtest("Bad switchpos")
self.run_auxfunc( self.run_auxfunc(
62, 62,
17, 17,
want_result=mavutil.mavlink.MAV_RESULT_DENIED want_result=mavutil.mavlink.MAV_RESULT_DENIED,
run_cmd=run_cmd,
) )
def MAV_CMD_DO_AUX_FUNCTION(self):
'''Test triggering Auxiliary Functions via mavlink'''
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd)
self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd_int)
def FlyEachFrame(self): def FlyEachFrame(self):
'''Fly each supported internal frame''' '''Fly each supported internal frame'''
vinfo = vehicleinfo.VehicleInfo() vinfo = vehicleinfo.VehicleInfo()
@ -5005,7 +5012,7 @@ class AutoTestPlane(AutoTest):
self.RTL_CLIMB_MIN, self.RTL_CLIMB_MIN,
self.ClimbBeforeTurn, self.ClimbBeforeTurn,
self.IMUTempCal, self.IMUTempCal,
self.MAV_DO_AUX_FUNCTION, self.MAV_CMD_DO_AUX_FUNCTION,
self.SmartBattery, self.SmartBattery,
self.FlyEachFrame, self.FlyEachFrame,
self.RCDisableAirspeedUse, self.RCDisableAirspeedUse,

View File

@ -3788,8 +3788,11 @@ class AutoTest(ABC):
def run_auxfunc(self, def run_auxfunc(self,
function, function,
level, level,
run_cmd=None,
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
self.run_cmd( if run_cmd is None:
run_cmd = self.run_cmd
run_cmd(
mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION, mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,
p1=function, p1=function,
p2=level, p2=level,