From 484ce402eba60f52e513692e57346f4a399be592 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 20 Apr 2024 09:40:30 +1000 Subject: [PATCH] autotest: helicopter: have land_and_disarm also lower the rotor speed similarly for do_RTL --- Tools/autotest/helicopter.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 3b85bc70e0189..b7339368967b5 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -91,7 +91,6 @@ def RotorRunup(self): raise NotAchievedException("Takeoff initiated before runup time complete %u" % runup_time) self.progress("Runup time %u" % runup_time) self.zero_throttle() - self.set_rc(8, 1000) self.land_and_disarm() self.mav.wait_heartbeat() @@ -206,7 +205,6 @@ def FlyEachFrame(self): ) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def governortest(self): '''Test Heli Internal Throttle Curve and Governor''' @@ -219,7 +217,6 @@ def governortest(self): self.set_parameter("H_RSC_MODE", 4) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def hover(self): self.progress("Setting hover collective") @@ -280,7 +277,6 @@ def PosHoldTakeOff(self): ex = e self.land_and_disarm() - self.set_rc(8, 1000) self.context_pop() @@ -318,7 +314,6 @@ def StabilizeTakeOff(self): ex = e self.land_and_disarm() - self.set_rc(8, 1000) self.context_pop() @@ -878,7 +873,6 @@ def AutoTune(self): now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() - self.set_rc(8, 1000) # test pitch rate P and Rate D tuning self.set_parameters({ @@ -898,7 +892,6 @@ def AutoTune(self): now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() - self.set_rc(8, 1000) # test Roll rate P and Rate D tuning self.set_parameters({ @@ -918,7 +911,6 @@ def AutoTune(self): now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() - self.set_rc(8, 1000) # test Roll and pitch angle P tuning self.set_parameters({ @@ -938,7 +930,6 @@ def AutoTune(self): now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() - self.set_rc(8, 1000) # test yaw FF, rate P and Rate D, and angle P tuning self.set_parameters({ @@ -958,6 +949,15 @@ def AutoTune(self): now = self.get_sim_time() self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) self.land_and_disarm() + + def land_and_disarm(self, **kwargs): + super(AutoTestHelicopter, self).land_and_disarm(**kwargs) + self.progress("Killing rotor speed") + self.set_rc(8, 1000) + + def do_RTL(self, **kwargs): + super(AutoTestHelicopter, self).do_RTL(**kwargs) + self.progress("Killing rotor speed") self.set_rc(8, 1000) def tests(self):