mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: add test for MAV_CMD_GUIDED_CHANGE_ALTITUDE
This commit is contained in:
parent
fe56a6aedd
commit
10f93b9e50
@ -4636,6 +4636,31 @@ class AutoTestPlane(AutoTest):
|
||||
])
|
||||
self.start_SITL()
|
||||
|
||||
def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self):
|
||||
'''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE'''
|
||||
self.takeoff(30, relative=True)
|
||||
self.change_mode('GUIDED')
|
||||
for alt in 50, 70:
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
|
||||
p7=alt,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
||||
)
|
||||
self.wait_altitude(alt-1, alt+1, timeout=30, relative=True)
|
||||
|
||||
# test for #24535
|
||||
self.change_mode('LOITER')
|
||||
self.delay_sim_time(5)
|
||||
self.change_mode('GUIDED')
|
||||
self.wait_altitude(
|
||||
alt-3, # NOTE: reuse of alt from above loop!
|
||||
alt+3,
|
||||
minimum_duration=10,
|
||||
timeout=30,
|
||||
relative=True,
|
||||
)
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
@ -4725,6 +4750,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.NoArmWithoutMissionItems,
|
||||
self.MODE_SWITCH_RESET,
|
||||
self.ExternalPositionEstimate,
|
||||
self.MAV_CMD_GUIDED_CHANGE_ALTITUDE,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user