mirror of https://github.com/ArduPilot/ardupilot
autotest: more changes for plane disarm disallow
This commit is contained in:
parent
a98e913a2a
commit
6fcf85edb8
|
@ -1038,7 +1038,7 @@ class AutoTestPlane(AutoTest):
|
|||
"SIM_RC_FAIL": 0, # fix receiver
|
||||
})
|
||||
self.zero_throttle()
|
||||
self.disarm_vehicle()
|
||||
self.disarm_vehicle(force=True)
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
|
@ -2268,7 +2268,7 @@ function'''
|
|||
self.wait_waypoint(4, 4, timeout=1200, max_dist=120)
|
||||
|
||||
# Disarm
|
||||
self.disarm_vehicle()
|
||||
self.disarm_vehicle_expect_fail()
|
||||
|
||||
self.progress("Mission OK")
|
||||
|
||||
|
@ -2365,7 +2365,7 @@ function'''
|
|||
raise NotAchievedException("Airspeed did not reduce with lower SOAR_VSPEED")
|
||||
|
||||
# Disarm
|
||||
self.disarm_vehicle()
|
||||
self.disarm_vehicle_expect_fail()
|
||||
|
||||
self.progress("Mission OK")
|
||||
|
||||
|
@ -2872,7 +2872,7 @@ function'''
|
|||
self.context_clear_collection("STATUSTEXT")
|
||||
###################################################################
|
||||
|
||||
self.disarm_vehicle()
|
||||
self.disarm_vehicle(force=True)
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
|
|
|
@ -4361,6 +4361,22 @@ class AutoTest(ABC):
|
|||
timeout=timeout)
|
||||
return self.wait_disarmed()
|
||||
|
||||
def disarm_vehicle_expect_fail(self):
|
||||
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
|
||||
self.progress("Disarm - expect to fail")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
0, # DISARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
self.progress("Disarm - forced")
|
||||
self.disarm_vehicle(force=True)
|
||||
|
||||
def wait_disarmed_default_wait_time(self):
|
||||
return 30
|
||||
|
||||
|
@ -11191,7 +11207,7 @@ switch value'''
|
|||
# ok done, stop the engine
|
||||
if self.is_plane():
|
||||
self.zero_throttle()
|
||||
if not self.disarm_vehicle():
|
||||
if not self.disarm_vehicle(force=True):
|
||||
raise NotAchievedException("Failed to DISARM")
|
||||
|
||||
def test_frsky_d(self):
|
||||
|
|
|
@ -248,20 +248,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||
self.progress("Waiting for Motor1 to speed up")
|
||||
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
|
||||
|
||||
self.progress("Disarm/rearm with GCS - expect to fail")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
|
||||
0, # DISARM
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
timeout=10,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||
|
||||
self.progress("Disarm/rearm with GCS - forced")
|
||||
self.disarm_vehicle(force=True)
|
||||
self.disarm_vehicle_expect_fail()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.progress("Verify that airmode is still on")
|
||||
|
|
Loading…
Reference in New Issue