diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index df86b8f425..e0c9b85ff7 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -2012,7 +2012,7 @@ static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str) only one fits in the queue, so if you send more than one before the last one gets into the serial buffer then the old one will be lost */ -static void gcs_send_text_fmt(const prog_char_t *fmt, ...) +void gcs_send_text_fmt(const prog_char_t *fmt, ...) { char fmtstr[40]; va_list ap; diff --git a/ArduPlane/commands_process.pde b/ArduPlane/commands_process.pde index 974474d503..4eb633c95f 100644 --- a/ArduPlane/commands_process.pde +++ b/ArduPlane/commands_process.pde @@ -2,7 +2,7 @@ // For changing active command mid-mission //---------------------------------------- -static void change_command(uint8_t cmd_index) +void change_command(uint8_t cmd_index) { struct Location temp = get_cmd_with_index(cmd_index); diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index 4bf9f77eed..e79867adf4 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -316,6 +316,13 @@ static void geofence_send_status(mavlink_channel_t chan) } } +// public function for use in failsafe modules +bool geofence_breached(void) +{ + return geofence_state?geofence_state->fence_triggered:false; +} + + #else // GEOFENCE_ENABLED static void geofence_check(bool altitude_check_only) { }