Skip to content

Commit

Permalink
Tools: test use Location::AltFrame for guided_state.target_alt_frame
Browse files Browse the repository at this point in the history
  • Loading branch information
timtuxworth committed Aug 31, 2024
1 parent f8134a6 commit 1b9b396
Showing 1 changed file with 22 additions and 0 deletions.
22 changes: 22 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -5508,6 +5508,7 @@ def RunMissionScript(self):

def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
'''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE'''
self.start_subtest("set home relative altitude")
self.takeoff(30, relative=True)
self.change_mode('GUIDED')
for alt in 50, 70:
Expand All @@ -5519,6 +5520,7 @@ def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
self.wait_altitude(alt-1, alt+1, timeout=30, relative=True)

# test for #24535
self.start_subtest("switch to loiter and resume maintains altitude")
self.change_mode('LOITER')
self.delay_sim_time(5)
self.change_mode('GUIDED')
Expand All @@ -5529,6 +5531,26 @@ def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
timeout=30,
relative=True,
)
# test that this works if switching between RELATIVE (HOME) and GLOBAL(AMSL)
self.start_subtest("set global/AMSL altitude switch to loiter and resume")
alt = 600
self.run_cmd_int(
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
p7=alt,
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
)
self.wait_altitude(alt-3, alt+3, timeout=30, relative=False)
self.change_mode('LOITER')
self.delay_sim_time(5)
self.change_mode('GUIDED')
self.wait_altitude(
alt-5, # NOTE: reuse of alt from above CHANGE_ALTITUDE
alt+5,
minimum_duration=10,
timeout=30,
relative=False,
)
self.delay_sim_time(5)
self.fly_home_land_and_disarm()

def _MAV_CMD_PREFLIGHT_CALIBRATION(self, command):
Expand Down

0 comments on commit 1b9b396

Please sign in to comment.