Browse Source

Plane: update for APM_OBC API change

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
9fff67ec89
  1. 2
      ArduPlane/ArduPlane.pde
  2. 6
      ArduPlane/geofence.pde

2
ArduPlane/ArduPlane.pde

@ -975,7 +975,7 @@ static void obc_fs_check(void) @@ -975,7 +975,7 @@ static void obc_fs_check(void)
{
#if OBC_FAILSAFE == ENABLED
// perform OBC failsafe checks
obc.check(OBC_MODE(control_mode), failsafe.last_heartbeat_ms);
obc.check(OBC_MODE(control_mode), failsafe.last_heartbeat_ms, geofence_breached());
#endif
}

6
ArduPlane/geofence.pde

@ -424,8 +424,10 @@ static void geofence_send_status(mavlink_channel_t chan) @@ -424,8 +424,10 @@ static void geofence_send_status(mavlink_channel_t chan)
}
}
// public function for use in failsafe modules
bool geofence_breached(void)
/*
return true if geofence has been breached
*/
static bool geofence_breached(void)
{
return geofence_state ? geofence_state->fence_triggered : false;
}

Loading…
Cancel
Save