mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
autotest: add test for fence surviving a bind-values receiver failure
This commit is contained in:
parent
4636a4c458
commit
fc98b7d9e8
@ -930,6 +930,45 @@ class AutoTestPlane(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def test_throttle_failsafe_fence(self):
|
||||
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
||||
|
||||
self.progress("Checking fence is not present before being configured")
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
print("%s" % str(m))
|
||||
if (m.onboard_control_sensors_enabled & fence_bit):
|
||||
raise NotAchievedException("Fence enabled before being configured")
|
||||
|
||||
self.change_mode('MANUAL')
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.load_fence("CMAC-fence.txt")
|
||||
|
||||
self.set_parameter("FENCE_CHANNEL", 7)
|
||||
self.set_parameter("FENCE_ACTION", 4)
|
||||
self.set_rc(3, 1000)
|
||||
self.set_rc(7, 2000)
|
||||
|
||||
self.progress("Checking fence is initially OK")
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
print("%s" % str(m))
|
||||
if (not (m.onboard_control_sensors_enabled & fence_bit)):
|
||||
raise NotAchievedException("Fence not initially enabled")
|
||||
|
||||
self.set_parameter("THR_FS_VALUE", 960)
|
||||
self.progress("Failing receiver (throttle-to-950)")
|
||||
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
|
||||
self.wait_mode("CIRCLE")
|
||||
self.delay_sim_time(1) # give
|
||||
self.drain_mav_unparsed()
|
||||
|
||||
self.progress("Checking fence is OK after receiver failure (bind-values)")
|
||||
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
print("%s" % str(m))
|
||||
if (not (m.onboard_control_sensors_enabled & fence_bit)):
|
||||
raise NotAchievedException("Fence not enabled after RC fail")
|
||||
|
||||
def test_gripper_mission(self):
|
||||
self.context_push()
|
||||
ex = None
|
||||
@ -1549,6 +1588,10 @@ class AutoTestPlane(AutoTest):
|
||||
"Fly throttle failsafe",
|
||||
self.test_throttle_failsafe),
|
||||
|
||||
("ThrottleFailsafeFence",
|
||||
"Fly fence survives throttle failsafe",
|
||||
self.test_throttle_failsafe_fence),
|
||||
|
||||
("TestFlaps", "Flaps", self.fly_flaps),
|
||||
|
||||
("DO_CHANGE_SPEED", "Test mavlink DO_CHANGE_SPEED command", self.fly_do_change_speed),
|
||||
|
Loading…
Reference in New Issue
Block a user