Skip to content

Commit

Permalink
autotest: helicopter: have land_and_disarm also lower the rotor speed
Browse files Browse the repository at this point in the history
similarly for do_RTL
  • Loading branch information
peterbarker committed Apr 20, 2024
1 parent 623f0b8 commit 484ce40
Showing 1 changed file with 9 additions and 9 deletions.
18 changes: 9 additions & 9 deletions Tools/autotest/helicopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down Expand Up @@ -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'''
Expand All @@ -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")
Expand Down Expand Up @@ -280,7 +277,6 @@ def PosHoldTakeOff(self):
ex = e

self.land_and_disarm()
self.set_rc(8, 1000)

self.context_pop()

Expand Down Expand Up @@ -318,7 +314,6 @@ def StabilizeTakeOff(self):
ex = e

self.land_and_disarm()
self.set_rc(8, 1000)

self.context_pop()

Expand Down Expand Up @@ -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({
Expand All @@ -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({
Expand All @@ -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({
Expand All @@ -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({
Expand All @@ -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):
Expand Down

0 comments on commit 484ce40

Please sign in to comment.