Browse Source

APM: expose change_command() and geofence_breached() to libraries

this makes a failsafe library easier
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
0584017aff
  1. 2
      ArduPlane/GCS_Mavlink.pde
  2. 2
      ArduPlane/commands_process.pde
  3. 7
      ArduPlane/geofence.pde

2
ArduPlane/GCS_Mavlink.pde

@ -2012,7 +2012,7 @@ static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str) @@ -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;

2
ArduPlane/commands_process.pde

@ -2,7 +2,7 @@ @@ -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);

7
ArduPlane/geofence.pde

@ -316,6 +316,13 @@ static void geofence_send_status(mavlink_channel_t chan) @@ -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) { }

Loading…
Cancel
Save