Plane: Geofence, speed up the no fence checks if disabled

This just checks if we are going to early out on the fence because it's
disabled. This also saves us 60 bytes of flash space. This technically
is a behaviour change as it was possible to load the fence before while
disabled if there was an RC channel mapped to it. This defers that until
the fence will have an action. The advantage of this though is that it
speeds up the check that's done per loop in a quadplane for stick mixing
This commit is contained in:
Michael du Breuil 2019-09-16 13:24:41 -07:00 committed by WickedShell
parent 562b155f63
commit 8bfab6d2f2

View File

@ -207,14 +207,20 @@ bool Plane::geofence_set_enabled(bool enable)
*/
bool Plane::geofence_enabled(void)
{
if (g.fence_action == FENCE_ACTION_NONE) {
if (geofence_state != nullptr) {
geofence_state->fence_triggered = false;
}
return false;
}
geofence_update_pwm_enabled_state();
if (geofence_state == nullptr) {
return false;
}
if (g.fence_action == FENCE_ACTION_NONE ||
!geofence_present() ||
if (!geofence_present() ||
(g.fence_action != FENCE_ACTION_REPORT && !geofence_state->is_enabled)) {
// geo-fencing is disabled
// re-arm for when the channel trigger is switched on