1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 09:16:07 +03:00
betaflight/src/failsafe.h
Dominic Clifton e969d184e6 decouple failsafe from the rest of the system.
Note: the pwm_common driver has a dependency on the main failsafe code,
the solution is probably to move some of the code into rx_pwm.
2014-04-21 00:46:16 +01:00

29 lines
1.2 KiB
C

#pragma once
typedef struct failsafeConfig_s {
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
uint16_t failsafe_detect_threshold; // Update controls channel only if pulse is above failsafe_detect_threshold. below this trigger failsafe.
} failsafeConfig_t;
typedef struct failsafeVTable_s {
void (*reset)(void);
void (*validDataReceived)(void);
bool (*shouldForceLanding)(bool armed);
bool (*hasTimerElapsed)(void);
bool (*shouldHaveCausedLandingByNow)(void);
void (*updateState)(void);
bool (*isIdle)(void);
} failsafeVTable_t;
typedef struct failsafe_s {
const failsafeVTable_t *vTable;
int16_t counter;
int16_t events;
} failsafe_t;
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);