From 4adc3fb25f6b89d60f2eee17dca7dad76e568f6f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 3 Oct 2023 18:04:47 +1100 Subject: [PATCH] autotest: test MAV_CMD_DO_AUX_FUNCTION as both COMMAND_LONG and COMMAND_INT --- Tools/autotest/arduplane.py | 21 ++++++++++++++------- Tools/autotest/common.py | 5 ++++- 2 files changed, 18 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index c8d6023560..cc91fba550 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -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=7) - def MAV_DO_AUX_FUNCTION(self): + def _MAV_CMD_DO_AUX_FUNCTION(self, run_cmd): '''Test triggering Auxiliary Functions via mavlink''' 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.run_auxfunc(64, 0) + self.run_auxfunc(64, 0, run_cmd=run_cmd) 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.run_auxfunc( 65231, 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.run_auxfunc( 62, 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): '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() @@ -5005,7 +5012,7 @@ class AutoTestPlane(AutoTest): self.RTL_CLIMB_MIN, self.ClimbBeforeTurn, self.IMUTempCal, - self.MAV_DO_AUX_FUNCTION, + self.MAV_CMD_DO_AUX_FUNCTION, self.SmartBattery, self.FlyEachFrame, self.RCDisableAirspeedUse, diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 94bfa2f8bc..ef0c86ce55 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -3788,8 +3788,11 @@ class AutoTest(ABC): def run_auxfunc(self, function, level, + run_cmd=None, 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, p1=function, p2=level,