Skip to content

Commit

Permalink
autotest: fix altitude tolerance on throttle loss test
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed May 14, 2024
1 parent 320896c commit 3d89861
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -5471,6 +5471,11 @@ def K1000ThrottleLossScript(self):
self.progress("Takeoff")
self.takeoff(alt=target_alt, mode="TAKEOFF", timeout=120)
self.change_mode("GUIDED")
self.run_cmd_int(
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
p7=target_alt, # alt
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
)

self.progress("Killing the motor, waiting for warn-only retry logic")
self.set_parameters({
Expand All @@ -5491,7 +5496,7 @@ def K1000ThrottleLossScript(self):
except NotAchievedException:
raise NotAchievedException('Throttle held off when should be warn only behavior')

self.wait_altitude(target_alt, target_alt+1, relative=True, timeout=60)
self.wait_altitude(target_alt-2, target_alt+2, relative=True, timeout=60)

self.progress("Kill the motor and check the esc restart procedure")
self.set_parameters({
Expand Down

0 comments on commit 3d89861

Please sign in to comment.