mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: add tests for MAV_CMD_DO_LAND_START for both int and long
This commit is contained in:
parent
e965b987f6
commit
3dfd06cff2
@ -4952,6 +4952,37 @@ class AutoTestPlane(AutoTest):
|
||||
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd)
|
||||
self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int)
|
||||
|
||||
def MAV_CMD_DO_LAND_START(self):
|
||||
'''test MAV_CMD_DO_LAND_START as mavlink command'''
|
||||
self.set_parameters({
|
||||
"RTL_AUTOLAND": 3,
|
||||
})
|
||||
self.upload_simple_relhome_mission([
|
||||
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30),
|
||||
self.create_MISSION_ITEM_INT(
|
||||
mavutil.mavlink.MAV_CMD_DO_LAND_START,
|
||||
),
|
||||
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0),
|
||||
])
|
||||
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.arm_vehicle()
|
||||
|
||||
self.start_subtest("DO_LAND_START as COMMAND_LONG")
|
||||
self.wait_current_waypoint(2)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START)
|
||||
self.wait_current_waypoint(4)
|
||||
|
||||
self.start_subtest("DO_LAND_START as COMMAND_INT")
|
||||
self.set_current_waypoint(2)
|
||||
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_LAND_START)
|
||||
self.wait_current_waypoint(4)
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
@ -5049,6 +5080,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.MAV_CMD_DO_AUTOTUNE_ENABLE,
|
||||
self.MAV_CMD_DO_GO_AROUND,
|
||||
self.MAV_CMD_DO_FLIGHTTERMINATION,
|
||||
self.MAV_CMD_DO_LAND_START,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user