mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
autotest: add test for Copter taking off above-home via command int
This commit is contained in:
parent
0b04f765d4
commit
f9165c786d
@ -10410,6 +10410,44 @@ class AutoTestCopter(AutoTest):
|
||||
|
||||
self.reboot_sitl() # unlock home position
|
||||
|
||||
def MAV_CMD_NAV_TAKEOFF_command_int(self):
|
||||
'''test issuing takeoff command via mavlink and command_int'''
|
||||
self.change_mode('GUIDED')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.start_subtest("Check NAV_TAKEOFF is above home location, not current location")
|
||||
# reset home 20 metres above current location
|
||||
current_alt_abs = self.get_altitude(relative=False)
|
||||
|
||||
loc = self.mav.location()
|
||||
|
||||
home_z_ofs = 20
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
|
||||
p5=loc.lat,
|
||||
p6=loc.lng,
|
||||
p7=current_alt_abs + home_z_ofs,
|
||||
)
|
||||
|
||||
self.change_mode('GUIDED')
|
||||
self.arm_vehicle()
|
||||
takeoff_alt = 5
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
||||
p7=takeoff_alt,
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
||||
)
|
||||
self.wait_altitude(
|
||||
current_alt_abs + home_z_ofs + takeoff_alt - 0.5,
|
||||
current_alt_abs + home_z_ofs + takeoff_alt + 0.5,
|
||||
minimum_duration=5,
|
||||
relative=False,
|
||||
)
|
||||
self.change_mode('LAND')
|
||||
self.wait_disarmed()
|
||||
|
||||
self.reboot_sitl() # unlock home position
|
||||
|
||||
def tests2b(self): # this block currently around 9.5mins here
|
||||
'''return list of all tests'''
|
||||
ret = ([
|
||||
@ -10478,6 +10516,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.MAV_CMD_DO_LAND_START,
|
||||
self.MAV_CMD_SET_EKF_SOURCE_SET,
|
||||
self.MAV_CMD_NAV_TAKEOFF,
|
||||
self.MAV_CMD_NAV_TAKEOFF_command_int,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user