autotest: more changes for plane disarm disallow

This commit is contained in:
Andrew Tridgell 2022-03-18 20:13:50 +11:00 committed by Randy Mackay
parent 16af5800db
commit 6e91b87fb0
3 changed files with 42 additions and 18 deletions

View File

@ -1028,6 +1028,27 @@ class AutoTestPlane(AutoTest):
if ex is not None:
raise ex
self.start_subtest("Not use RC throttle input when THR_FAILSAFE==2")
self.takeoff(100)
self.set_rc(3, 1800)
self.set_rc(1, 2000)
self.wait_attitude(desroll=45, timeout=1)
self.context_push()
self.set_parameters({
"THR_FAILSAFE": 2,
"SIM_RC_FAIL": 1, # no pulses
})
self.delay_sim_time(1)
self.wait_attitude(desroll=0, timeout=5)
self.assert_servo_channel_value(3, self.get_parameter("RC3_MIN"))
self.set_parameters({
"SIM_RC_FAIL": 0, # fix receiver
})
self.zero_throttle()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
def test_throttle_failsafe_fence(self):
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
@ -2260,7 +2281,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")
@ -2357,7 +2378,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")
@ -2864,7 +2885,7 @@ function'''
self.context_clear_collection("STATUSTEXT")
###################################################################
self.disarm_vehicle()
self.disarm_vehicle(force=True)
except Exception as e:
self.print_exception_caught(e)

View File

@ -4243,6 +4243,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
@ -11012,7 +11028,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):

View File

@ -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")