mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add test for MAV_CMD_NAV_TAKEOFF for quadplane using command_long
This commit is contained in:
parent
e71227fe3a
commit
7e1492d2b7
@ -1442,6 +1442,48 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
|
|
||||||
self.fly_home_land_and_disarm()
|
self.fly_home_land_and_disarm()
|
||||||
|
|
||||||
|
def MAV_CMD_NAV_TAKEOFF(self):
|
||||||
|
'''test issuing takeoff command via mavlink'''
|
||||||
|
self.change_mode('GUIDED')
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
|
||||||
|
self.arm_vehicle()
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=5)
|
||||||
|
self.wait_altitude(4.5, 5.5, minimum_duration=5, relative=True)
|
||||||
|
self.change_mode('QLAND')
|
||||||
|
self.wait_disarmed()
|
||||||
|
|
||||||
|
self.start_subtest("Check NAV_TAKEOFF is above current location, not home location")
|
||||||
|
self.change_mode('GUIDED')
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
|
||||||
|
# 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.arm_vehicle()
|
||||||
|
takeoff_alt = 5
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=takeoff_alt)
|
||||||
|
self.wait_altitude(
|
||||||
|
current_alt_abs + takeoff_alt - 0.5,
|
||||||
|
current_alt_abs + takeoff_alt + 0.5,
|
||||||
|
minimum_duration=5,
|
||||||
|
relative=False,
|
||||||
|
)
|
||||||
|
self.change_mode('QLAND')
|
||||||
|
self.wait_disarmed()
|
||||||
|
|
||||||
|
self.reboot_sitl() # unlock home position
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
|
|
||||||
@ -1480,5 +1522,6 @@ class AutoTestQuadPlane(AutoTest):
|
|||||||
self.RCDisableAirspeedUse,
|
self.RCDisableAirspeedUse,
|
||||||
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
|
self.mission_MAV_CMD_DO_VTOL_TRANSITION,
|
||||||
self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,
|
self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,
|
||||||
|
self.MAV_CMD_NAV_TAKEOFF,
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
Loading…
Reference in New Issue
Block a user