Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

autotest: rewrite PosHoldTakeoff using newly-available methods #26850

Merged
merged 2 commits into from
Apr 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
66 changes: 24 additions & 42 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -7047,57 +7047,39 @@ def PosHoldTakeOff(self):
"""ensure vehicle stays put until it is ready to fly"""
self.context_push()

ex = None
try:
self.set_parameter("PILOT_TKOFF_ALT", 700)
self.change_mode('POSHOLD')
self.set_rc(3, 1000)
self.wait_ready_to_arm()
self.arm_vehicle()
self.delay_sim_time(2)
# check we are still on the ground...
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
if abs(m.relative_alt) > 100:
raise NotAchievedException("Took off prematurely")

self.progress("Pushing throttle up")
self.set_rc(3, 1710)
self.delay_sim_time(0.5)
self.progress("Bringing back to hover throttle")
self.set_rc(3, 1500)
self.set_parameter("PILOT_TKOFF_ALT", 700)
self.change_mode('POSHOLD')
self.set_rc(3, 1000)
self.wait_ready_to_arm()
self.arm_vehicle()
self.delay_sim_time(2)
# check we are still on the ground...
relative_alt = self.get_altitude(relative=True)
if relative_alt > 0.1:
raise NotAchievedException("Took off prematurely")

# make sure we haven't already reached alt:
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
max_initial_alt = 2000
if abs(m.relative_alt) > max_initial_alt:
raise NotAchievedException("Took off too fast (%f > %f" %
(abs(m.relative_alt), max_initial_alt))
self.progress("Pushing throttle up")
self.set_rc(3, 1710)
self.delay_sim_time(0.5)
self.progress("Bringing back to hover throttle")
self.set_rc(3, 1500)

self.progress("Monitoring takeoff-to-alt")
self.wait_altitude(6.9, 8, relative=True)
# make sure we haven't already reached alt:
relative_alt = self.get_altitude(relative=True)
max_initial_alt = 2.0
if abs(relative_alt) > max_initial_alt:
raise NotAchievedException("Took off too fast (%f > %f" %
(relative_alt, max_initial_alt))

self.progress("Making sure we stop at our takeoff altitude")
tstart = self.get_sim_time()
while self.get_sim_time() - tstart < 5:
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
delta = abs(7000 - m.relative_alt)
self.progress("alt=%f delta=%f" % (m.relative_alt/1000,
delta/1000))
if delta > 1000:
raise NotAchievedException("Failed to maintain takeoff alt")
self.progress("takeoff OK")
except Exception as e:
self.print_exception_caught(e)
ex = e
self.progress("Monitoring takeoff-to-alt")
self.wait_altitude(6.9, 8, relative=True, minimum_duration=10)
self.progress("takeoff OK")

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

self.context_pop()

if ex is not None:
raise ex

def initial_mode(self):
return "STABILIZE"

Expand Down
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
Loading