mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: update for APM_OBC API change
This commit is contained in:
parent
4e97c98fa1
commit
9fff67ec89
@ -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
|
||||
}
|
||||
|
||||
|
@ -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…
Reference in New Issue
Block a user