diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 0c92a1310b..3f90ccfb27 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -129,8 +129,8 @@ const AP_Param::Info var_info[] PROGMEM = { #if GEOFENCE_ENABLED == ENABLED // @Param: FENCE_ACTION // @DisplayName: Action on geofence breach - // @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter - // @Values: 0:None,1:GuidedMode + // @Description: What to do on fence breach + // @Values: 0:None,1:GuidedMode,2:ReportOnly // @User: Standard GSCALAR(fence_action, "FENCE_ACTION", 0), diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index e79867adf4..defdc6170f 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -235,7 +235,8 @@ static void geofence_check(bool altitude_check_only) } // we are outside the fence - if (geofence_state->fence_triggered && control_mode == GUIDED) { + if (geofence_state->fence_triggered && + (control_mode == GUIDED || g.fence_action == FENCE_ACTION_REPORT)) { // we have already triggered, don't trigger again until the // user disables/re-enables using the fence channel switch return; @@ -256,6 +257,9 @@ static void geofence_check(bool altitude_check_only) // see what action the user wants switch (g.fence_action) { + case FENCE_ACTION_REPORT: + break; + case FENCE_ACTION_GUIDED: // fly to the return point, with an altitude half way between // min and max