Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix fence being disabled during RC failure event #12751

Merged
merged 2 commits into from Nov 18, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
5 changes: 5 additions & 0 deletions ArduPlane/geofence.cpp
Expand Up @@ -160,6 +160,11 @@ bool Plane::geofence_present(void)
*/
void Plane::geofence_update_pwm_enabled_state()
{
if (rc_failsafe_active()) {
// do nothing based on the radio channel value as it may be at bind value
return;
}

bool is_pwm_enabled;
if (g.fence_channel == 0) {
is_pwm_enabled = false;
Expand Down
43 changes: 43 additions & 0 deletions Tools/autotest/arduplane.py
Expand Up @@ -930,6 +930,45 @@ def test_throttle_failsafe(self):
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
Expand Down Expand Up @@ -1422,6 +1461,10 @@ def tests(self):
"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),
Expand Down