mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
First-cut of a refactored failsafe system.
* fixes issue where indicators would flash when SBus RX entered failsafe mode. * fixes bug where turning off a TX for an SBus RX would instantly disarm when using a switch to arm when the channel went outside the arming range. * introduces failsafe phases to make the system more understandable. * allows the system to ask if rxSignalIsBeing received for all RX systems: PPM/PWM/SerialRX/MSP. Also works when a serial data signal is still being received but the data stream indicates a failsafe condition - e.g. SBus failsafe flags. * failsafe settings are no-longer per-profile. Untested: Sumd/Sumh/XBus/MSP (!) Tested: SBus X8R, Lemon RX Sat, X8R in PWM, Spektrum PPM.
This commit is contained in:
parent
37e551db11
commit
c8c0c85656
14 changed files with 260 additions and 145 deletions
|
@ -138,7 +138,7 @@ profile_t *currentProfile;
|
||||||
static uint8_t currentControlRateProfileIndex = 0;
|
static uint8_t currentControlRateProfileIndex = 0;
|
||||||
controlRateConfig_t *currentControlRateProfile;
|
controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 95;
|
static const uint8_t EEPROM_CONF_VERSION = 96;
|
||||||
|
|
||||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
{
|
{
|
||||||
|
@ -407,6 +407,9 @@ static void resetConf(void)
|
||||||
masterConfig.rxConfig.midrc = 1500;
|
masterConfig.rxConfig.midrc = 1500;
|
||||||
masterConfig.rxConfig.mincheck = 1100;
|
masterConfig.rxConfig.mincheck = 1100;
|
||||||
masterConfig.rxConfig.maxcheck = 1900;
|
masterConfig.rxConfig.maxcheck = 1900;
|
||||||
|
masterConfig.rxConfig.rx_min_usec = 985; // any of first 4 channels below this value will trigger failsafe
|
||||||
|
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe
|
||||||
|
|
||||||
masterConfig.rxConfig.rssi_channel = 0;
|
masterConfig.rxConfig.rssi_channel = 0;
|
||||||
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||||
|
|
||||||
|
@ -474,11 +477,9 @@ static void resetConf(void)
|
||||||
currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||||
|
|
||||||
// Failsafe Variables
|
// Failsafe Variables
|
||||||
currentProfile->failsafeConfig.failsafe_delay = 10; // 1sec
|
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
|
||||||
currentProfile->failsafeConfig.failsafe_off_delay = 200; // 20sec
|
masterConfig.failsafeConfig.failsafe_off_delay = 200; // 20sec
|
||||||
currentProfile->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||||
currentProfile->failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe
|
|
||||||
currentProfile->failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe
|
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
// servos
|
// servos
|
||||||
|
@ -671,7 +672,7 @@ void activateConfig(void)
|
||||||
gpsUsePIDs(¤tProfile->pidProfile);
|
gpsUsePIDs(¤tProfile->pidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
useFailsafeConfig(¤tProfile->failsafeConfig);
|
useFailsafeConfig(&masterConfig.failsafeConfig);
|
||||||
setAccelerationTrims(&masterConfig.accZero);
|
setAccelerationTrims(&masterConfig.accZero);
|
||||||
|
|
||||||
mixerUseConfigs(
|
mixerUseConfigs(
|
||||||
|
|
|
@ -61,6 +61,8 @@ typedef struct master_t {
|
||||||
rxConfig_t rxConfig;
|
rxConfig_t rxConfig;
|
||||||
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
||||||
|
|
||||||
|
failsafeConfig_t failsafeConfig;
|
||||||
|
|
||||||
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
||||||
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
||||||
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
||||||
|
|
|
@ -54,9 +54,6 @@ typedef struct profile_s {
|
||||||
gimbalConfig_t gimbalConfig;
|
gimbalConfig_t gimbalConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Failsafe related configuration
|
|
||||||
failsafeConfig_t failsafeConfig;
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsProfile_t gpsProfile;
|
gpsProfile_t gpsProfile;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -44,9 +44,10 @@ static failsafeConfig_t *failsafeConfig;
|
||||||
|
|
||||||
static rxConfig_t *rxConfig;
|
static rxConfig_t *rxConfig;
|
||||||
|
|
||||||
void failsafeReset(void)
|
static void failsafeReset(void)
|
||||||
{
|
{
|
||||||
failsafeState.counter = 0;
|
failsafeState.counter = 0;
|
||||||
|
failsafeState.phase = FAILSAFE_IDLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -63,27 +64,39 @@ failsafeState_t* failsafeInit(rxConfig_t *intialRxConfig)
|
||||||
rxConfig = intialRxConfig;
|
rxConfig = intialRxConfig;
|
||||||
|
|
||||||
failsafeState.events = 0;
|
failsafeState.events = 0;
|
||||||
failsafeState.enabled = false;
|
failsafeState.monitoring = false;
|
||||||
|
|
||||||
return &failsafeState;
|
return &failsafeState;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool failsafeIsIdle(void)
|
failsafePhase_e failsafePhase()
|
||||||
{
|
{
|
||||||
return failsafeState.counter == 0;
|
return failsafeState.phase;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool failsafeIsEnabled(void)
|
#define MAX_COUNTER_VALUE_WHEN_RX_IS_RECEIVED_AFTER_RX_CYCLE 1
|
||||||
|
|
||||||
|
bool failsafeIsReceivingRxData(void)
|
||||||
{
|
{
|
||||||
return failsafeState.enabled;
|
return failsafeState.counter <= MAX_COUNTER_VALUE_WHEN_RX_IS_RECEIVED_AFTER_RX_CYCLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
void failsafeEnable(void)
|
bool failsafeIsMonitoring(void)
|
||||||
{
|
{
|
||||||
failsafeState.enabled = true;
|
return failsafeState.monitoring;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool failsafeHasTimerElapsed(void)
|
bool failsafeIsActive(void)
|
||||||
|
{
|
||||||
|
return failsafeState.active;
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeStartMonitoring(void)
|
||||||
|
{
|
||||||
|
failsafeState.monitoring = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool failsafeHasTimerElapsed(void)
|
||||||
{
|
{
|
||||||
return failsafeState.counter > (5 * failsafeConfig->failsafe_delay);
|
return failsafeState.counter > (5 * failsafeConfig->failsafe_delay);
|
||||||
}
|
}
|
||||||
|
@ -93,19 +106,28 @@ bool failsafeShouldForceLanding(bool armed)
|
||||||
return failsafeHasTimerElapsed() && armed;
|
return failsafeHasTimerElapsed() && armed;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool failsafeShouldHaveCausedLandingByNow(void)
|
static bool failsafeShouldHaveCausedLandingByNow(void)
|
||||||
{
|
{
|
||||||
return failsafeState.counter > 5 * (failsafeConfig->failsafe_delay + failsafeConfig->failsafe_off_delay);
|
return failsafeState.counter > 5 * (failsafeConfig->failsafe_delay + failsafeConfig->failsafe_off_delay);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void failsafeAvoidRearm(void)
|
static void failsafeActivate(void)
|
||||||
{
|
{
|
||||||
// This will prevent the automatic rearm if failsafe shuts it down and prevents
|
failsafeState.active = true;
|
||||||
// to restart accidently by just reconnect to the tx - you will have to switch off first to rearm
|
failsafeState.phase = FAILSAFE_LANDING;
|
||||||
ENABLE_ARMING_FLAG(PREVENT_ARMING);
|
|
||||||
|
failsafeState.events++;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void failsafeOnValidDataReceived(void)
|
static void failsafeApplyControlInput(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
rcData[i] = rxConfig->midrc;
|
||||||
|
}
|
||||||
|
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeOnValidDataReceived(void)
|
||||||
{
|
{
|
||||||
if (failsafeState.counter > 20)
|
if (failsafeState.counter > 20)
|
||||||
failsafeState.counter -= 20;
|
failsafeState.counter -= 20;
|
||||||
|
@ -115,58 +137,57 @@ static void failsafeOnValidDataReceived(void)
|
||||||
|
|
||||||
void failsafeUpdateState(void)
|
void failsafeUpdateState(void)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
bool receivingRxData = failsafeIsReceivingRxData();
|
||||||
|
bool armed = ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
if (!failsafeHasTimerElapsed()) {
|
if (receivingRxData) {
|
||||||
return;
|
failsafeState.phase = FAILSAFE_IDLE;
|
||||||
|
failsafeState.active = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!failsafeIsEnabled()) {
|
switch (failsafeState.phase) {
|
||||||
failsafeReset();
|
case FAILSAFE_IDLE:
|
||||||
return;
|
if (!receivingRxData && armed) {
|
||||||
|
failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FAILSAFE_RX_LOSS_DETECTED:
|
||||||
|
if (failsafeShouldForceLanding(armed)) {
|
||||||
|
// Stabilize, and set Throttle to specified level
|
||||||
|
failsafeActivate();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FAILSAFE_LANDING:
|
||||||
|
if (armed) {
|
||||||
|
failsafeApplyControlInput();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (failsafeShouldHaveCausedLandingByNow() || !armed) {
|
||||||
|
|
||||||
|
failsafeState.phase = FAILSAFE_LANDED;
|
||||||
|
failsafeState.active = false;
|
||||||
|
mwDisarm();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FAILSAFE_LANDED:
|
||||||
|
// This will prevent the automatic rearm if failsafe shuts it down and prevents
|
||||||
|
// to restart accidently by just reconnect to the tx - you will have to switch off first to rearm
|
||||||
|
ENABLE_ARMING_FLAG(PREVENT_ARMING);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (failsafeShouldForceLanding(ARMING_FLAG(ARMED))) { // Stabilize, and set Throttle to specified level
|
|
||||||
failsafeAvoidRearm();
|
|
||||||
|
|
||||||
for (i = 0; i < 3; i++) {
|
|
||||||
rcData[i] = rxConfig->midrc; // after specified guard time after RC signal is lost (in 0.1sec)
|
|
||||||
}
|
|
||||||
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
|
||||||
failsafeState.events++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (failsafeShouldHaveCausedLandingByNow() || !ARMING_FLAG(ARMED)) {
|
|
||||||
mwDisarm();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Should be called once each time RX data is processed by the system.
|
* Should be called once when RX data is processed by the system.
|
||||||
*/
|
*/
|
||||||
void failsafeOnRxCycle(void)
|
void failsafeOnRxCycleStarted(void)
|
||||||
{
|
{
|
||||||
failsafeState.counter++;
|
failsafeState.counter++;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define REQUIRED_CHANNEL_MASK 0x0F // first 4 channels
|
|
||||||
|
|
||||||
// pulse duration is in micro seconds (usec)
|
|
||||||
void failsafeCheckPulse(uint8_t channel, uint16_t pulseDuration)
|
|
||||||
{
|
|
||||||
static uint8_t goodChannelMask = 0;
|
|
||||||
|
|
||||||
if (channel < 4 &&
|
|
||||||
pulseDuration > failsafeConfig->failsafe_min_usec &&
|
|
||||||
pulseDuration < failsafeConfig->failsafe_max_usec
|
|
||||||
) {
|
|
||||||
// if signal is valid - mark channel as OK
|
|
||||||
goodChannelMask |= (1 << channel);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (goodChannelMask == REQUIRED_CHANNEL_MASK) {
|
|
||||||
goodChannelMask = 0;
|
|
||||||
failsafeOnValidDataReceived();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
|
@ -23,30 +23,37 @@ 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_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)
|
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_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
|
||||||
uint16_t failsafe_min_usec;
|
|
||||||
uint16_t failsafe_max_usec;
|
|
||||||
} failsafeConfig_t;
|
} failsafeConfig_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
FAILSAFE_IDLE = 0,
|
||||||
|
FAILSAFE_RX_LOSS_DETECTED,
|
||||||
|
FAILSAFE_LANDING,
|
||||||
|
FAILSAFE_LANDED
|
||||||
|
} failsafePhase_e;
|
||||||
|
|
||||||
typedef struct failsafeState_s {
|
typedef struct failsafeState_s {
|
||||||
int16_t counter;
|
int16_t counter;
|
||||||
int16_t events;
|
int16_t events;
|
||||||
bool enabled;
|
bool monitoring;
|
||||||
|
bool active;
|
||||||
|
failsafePhase_e phase;
|
||||||
} failsafeState_t;
|
} failsafeState_t;
|
||||||
|
|
||||||
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);
|
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);
|
||||||
|
|
||||||
void failsafeEnable(void);
|
void failsafeStartMonitoring(void);
|
||||||
void failsafeOnRxCycle(void);
|
|
||||||
void failsafeCheckPulse(uint8_t channel, uint16_t pulseDuration);
|
|
||||||
void failsafeUpdateState(void);
|
void failsafeUpdateState(void);
|
||||||
|
|
||||||
void failsafeReset(void);
|
failsafePhase_e failsafePhase();
|
||||||
|
bool failsafeIsMonitoring(void);
|
||||||
|
bool failsafeIsActive(void);
|
||||||
|
bool failsafeIsReceivingRxData(void);
|
||||||
|
|
||||||
|
void failsafeOnValidDataReceived(void);
|
||||||
|
void failsafeOnRxCycleStarted(void);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
bool failsafeIsEnabled(void);
|
|
||||||
bool failsafeIsIdle(void);
|
|
||||||
bool failsafeHasTimerElapsed(void);
|
|
||||||
bool failsafeShouldForceLanding(bool armed);
|
|
||||||
bool failsafeShouldHaveCausedLandingByNow(void);
|
|
||||||
|
|
||||||
|
|
|
@ -49,9 +49,9 @@ static void beep_code(char first, char second, char third, char pause);
|
||||||
static uint8_t toggleBeep = 0;
|
static uint8_t toggleBeep = 0;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FAILSAFE_IDLE = 0,
|
FAILSAFE_WARNING_NONE = 0,
|
||||||
FAILSAFE_LANDING,
|
FAILSAFE_WARNING_LANDING,
|
||||||
FAILSAFE_FIND_ME
|
FAILSAFE_WARNING_FIND_ME
|
||||||
} failsafeBeeperWarnings_e;
|
} failsafeBeeperWarnings_e;
|
||||||
|
|
||||||
void beepcodeInit(void)
|
void beepcodeInit(void)
|
||||||
|
@ -64,7 +64,7 @@ void beepcodeUpdateState(batteryState_e batteryState)
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
static uint8_t warn_noGPSfix = 0;
|
static uint8_t warn_noGPSfix = 0;
|
||||||
#endif
|
#endif
|
||||||
static failsafeBeeperWarnings_e warn_failsafe = FAILSAFE_IDLE;
|
static failsafeBeeperWarnings_e warn_failsafe = FAILSAFE_WARNING_NONE;
|
||||||
|
|
||||||
//===================== BeeperOn via rcOptions =====================
|
//===================== BeeperOn via rcOptions =====================
|
||||||
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { // unconditional beeper on via AUXn switch
|
if (IS_RC_MODE_ACTIVE(BOXBEEPERON)) { // unconditional beeper on via AUXn switch
|
||||||
|
@ -74,20 +74,19 @@ void beepcodeUpdateState(batteryState_e batteryState)
|
||||||
}
|
}
|
||||||
//===================== Beeps for failsafe =====================
|
//===================== Beeps for failsafe =====================
|
||||||
if (feature(FEATURE_FAILSAFE)) {
|
if (feature(FEATURE_FAILSAFE)) {
|
||||||
if (failsafeShouldForceLanding(ARMING_FLAG(ARMED))) {
|
switch (failsafePhase()) {
|
||||||
warn_failsafe = FAILSAFE_LANDING;
|
case FAILSAFE_LANDING:
|
||||||
|
warn_failsafe = FAILSAFE_WARNING_LANDING;
|
||||||
if (failsafeShouldHaveCausedLandingByNow()) {
|
break;
|
||||||
warn_failsafe = FAILSAFE_FIND_ME;
|
case FAILSAFE_LANDED:
|
||||||
}
|
warn_failsafe = FAILSAFE_WARNING_FIND_ME;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
warn_failsafe = FAILSAFE_WARNING_NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (failsafeHasTimerElapsed() && !ARMING_FLAG(ARMED)) {
|
if (rxIsReceivingSignal()) {
|
||||||
warn_failsafe = FAILSAFE_FIND_ME;
|
warn_failsafe = FAILSAFE_WARNING_NONE;
|
||||||
}
|
|
||||||
|
|
||||||
if (failsafeIsIdle()) {
|
|
||||||
warn_failsafe = FAILSAFE_IDLE; // turn off alarm if TX is okay
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
|
@ -203,6 +204,33 @@ void updateTicker(void)
|
||||||
tickerIndex = tickerIndex % TICKER_CHARACTER_COUNT;
|
tickerIndex = tickerIndex % TICKER_CHARACTER_COUNT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void updateRxStatus(void)
|
||||||
|
{
|
||||||
|
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 2, 0);
|
||||||
|
i2c_OLED_send_char(rxIsReceivingSignal() ? 'R' : '!');
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateFailsafeStatus(void)
|
||||||
|
{
|
||||||
|
char failsafeIndicator;
|
||||||
|
switch (failsafePhase()) {
|
||||||
|
case FAILSAFE_IDLE:
|
||||||
|
failsafeIndicator = '-';
|
||||||
|
break;
|
||||||
|
case FAILSAFE_RX_LOSS_DETECTED:
|
||||||
|
failsafeIndicator = 'R';
|
||||||
|
break;
|
||||||
|
case FAILSAFE_LANDING:
|
||||||
|
failsafeIndicator = 'l';
|
||||||
|
break;
|
||||||
|
case FAILSAFE_LANDED:
|
||||||
|
failsafeIndicator = 'L';
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 3, 0);
|
||||||
|
i2c_OLED_send_char(failsafeIndicator);
|
||||||
|
}
|
||||||
|
|
||||||
void showTitle()
|
void showTitle()
|
||||||
{
|
{
|
||||||
i2c_OLED_set_line(0);
|
i2c_OLED_set_line(0);
|
||||||
|
@ -573,8 +601,11 @@ void updateDisplay(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
if (!armedState) {
|
if (!armedState) {
|
||||||
|
updateFailsafeStatus();
|
||||||
|
updateRxStatus();
|
||||||
updateTicker();
|
updateTicker();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void displaySetPage(pageId_e pageId)
|
void displaySetPage(pageId_e pageId)
|
||||||
|
|
|
@ -661,7 +661,7 @@ void applyLedWarningLayer(uint8_t updateNow)
|
||||||
if (feature(FEATURE_VBAT) && calculateBatteryState() != BATTERY_OK) {
|
if (feature(FEATURE_VBAT) && calculateBatteryState() != BATTERY_OK) {
|
||||||
warningFlags |= WARNING_FLAG_LOW_BATTERY;
|
warningFlags |= WARNING_FLAG_LOW_BATTERY;
|
||||||
}
|
}
|
||||||
if (feature(FEATURE_FAILSAFE) && failsafeHasTimerElapsed()) {
|
if (feature(FEATURE_FAILSAFE) && failsafeIsActive()) {
|
||||||
warningFlags |= WARNING_FLAG_FAILSAFE;
|
warningFlags |= WARNING_FLAG_FAILSAFE;
|
||||||
}
|
}
|
||||||
if (!ARMING_FLAG(ARMED) && !ARMING_FLAG(OK_TO_ARM)) {
|
if (!ARMING_FLAG(ARMED) && !ARMING_FLAG(OK_TO_ARM)) {
|
||||||
|
@ -714,6 +714,9 @@ void applyLedIndicatorLayer(uint8_t indicatorFlashState)
|
||||||
const ledConfig_t *ledConfig;
|
const ledConfig_t *ledConfig;
|
||||||
static const hsvColor_t *flashColor;
|
static const hsvColor_t *flashColor;
|
||||||
|
|
||||||
|
if (!rxIsReceivingSignal()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (indicatorFlashState == 0) {
|
if (indicatorFlashState == 0) {
|
||||||
flashColor = &hsv_orange;
|
flashColor = &hsv_orange;
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/navigation.h"
|
#include "flight/navigation.h"
|
||||||
|
#include "flight/failsafe.h"
|
||||||
|
|
||||||
#include "mw.h"
|
#include "mw.h"
|
||||||
|
|
||||||
|
@ -124,7 +125,8 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// Disarming via ARM BOX
|
// Disarming via ARM BOX
|
||||||
if (ARMING_FLAG(ARMED)) {
|
|
||||||
|
if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) {
|
||||||
if (disarm_kill_switch) {
|
if (disarm_kill_switch) {
|
||||||
mwDisarm();
|
mwDisarm();
|
||||||
} else if (throttleStatus == THROTTLE_LOW) {
|
} else if (throttleStatus == THROTTLE_LOW) {
|
||||||
|
|
|
@ -404,11 +404,12 @@ const clivalue_t valueTable[] = {
|
||||||
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, CONTROL_RATE_CONFIG_TPA_MAX},
|
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, CONTROL_RATE_CONFIG_TPA_MAX},
|
||||||
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||||
|
|
||||||
{ "failsafe_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_delay, 0, 200 },
|
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, 0, 200 },
|
||||||
{ "failsafe_off_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_off_delay, 0, 200 },
|
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, 0, 200 },
|
||||||
{ "failsafe_throttle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
{ "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
|
||||||
{ "failsafe_min_usec", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_min_usec, 100, PWM_RANGE_MAX },
|
|
||||||
{ "failsafe_max_usec", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_max_usec, 100, PWM_RANGE_MAX + (PWM_RANGE_MAX - PWM_RANGE_MIN) },
|
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, 100, PWM_RANGE_MAX },
|
||||||
|
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, 100, PWM_RANGE_MAX + (PWM_RANGE_MAX - PWM_RANGE_MIN) },
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
{ "gimbal_flags", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.gimbal_flags, 0, 255},
|
{ "gimbal_flags", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.gimbal_flags, 0, 255},
|
||||||
|
|
|
@ -1003,7 +1003,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize16(masterConfig.escAndServoConfig.maxthrottle);
|
serialize16(masterConfig.escAndServoConfig.maxthrottle);
|
||||||
serialize16(masterConfig.escAndServoConfig.mincommand);
|
serialize16(masterConfig.escAndServoConfig.mincommand);
|
||||||
|
|
||||||
serialize16(currentProfile->failsafeConfig.failsafe_throttle);
|
serialize16(masterConfig.failsafeConfig.failsafe_throttle);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
serialize8(masterConfig.gpsConfig.provider); // gps_type
|
serialize8(masterConfig.gpsConfig.provider); // gps_type
|
||||||
|
@ -1378,7 +1378,7 @@ static bool processInCommand(void)
|
||||||
masterConfig.escAndServoConfig.maxthrottle = read16();
|
masterConfig.escAndServoConfig.maxthrottle = read16();
|
||||||
masterConfig.escAndServoConfig.mincommand = read16();
|
masterConfig.escAndServoConfig.mincommand = read16();
|
||||||
|
|
||||||
currentProfile->failsafeConfig.failsafe_throttle = read16();
|
masterConfig.failsafeConfig.failsafe_throttle = read16();
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
masterConfig.gpsConfig.provider = read8(); // gps_type
|
masterConfig.gpsConfig.provider = read8(); // gps_type
|
||||||
|
|
|
@ -509,8 +509,8 @@ void processRx(void)
|
||||||
|
|
||||||
if (feature(FEATURE_FAILSAFE)) {
|
if (feature(FEATURE_FAILSAFE)) {
|
||||||
|
|
||||||
if (currentTime > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsEnabled()) {
|
if (currentTime > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) {
|
||||||
failsafeEnable();
|
failsafeStartMonitoring();
|
||||||
}
|
}
|
||||||
|
|
||||||
failsafeUpdateState();
|
failsafeUpdateState();
|
||||||
|
@ -527,7 +527,8 @@ void processRx(void)
|
||||||
if (ARMING_FLAG(ARMED)
|
if (ARMING_FLAG(ARMED)
|
||||||
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
|
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
|
||||||
&& masterConfig.auto_disarm_delay != 0
|
&& masterConfig.auto_disarm_delay != 0
|
||||||
&& isUsingSticksForArming()) {
|
&& isUsingSticksForArming())
|
||||||
|
{
|
||||||
if (throttleStatus == THROTTLE_LOW) {
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
|
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
|
||||||
mwDisarm();
|
mwDisarm();
|
||||||
|
@ -551,7 +552,7 @@ void processRx(void)
|
||||||
|
|
||||||
bool canUseHorizonMode = true;
|
bool canUseHorizonMode = true;
|
||||||
|
|
||||||
if ((IS_RC_MODE_ACTIVE(BOXANGLE) || (feature(FEATURE_FAILSAFE) && failsafeHasTimerElapsed())) && (sensors(SENSOR_ACC))) {
|
if ((IS_RC_MODE_ACTIVE(BOXANGLE) || (feature(FEATURE_FAILSAFE) && failsafeIsActive())) && (sensors(SENSOR_ACC))) {
|
||||||
// bumpless transfer to Level mode
|
// bumpless transfer to Level mode
|
||||||
canUseHorizonMode = false;
|
canUseHorizonMode = false;
|
||||||
|
|
||||||
|
@ -628,7 +629,7 @@ void loop(void)
|
||||||
static bool haveProcessedAnnexCodeOnce = false;
|
static bool haveProcessedAnnexCodeOnce = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
updateRx();
|
updateRx(currentTime);
|
||||||
|
|
||||||
if (shouldProcessRx(currentTime)) {
|
if (shouldProcessRx(currentTime)) {
|
||||||
processRx();
|
processRx();
|
||||||
|
|
113
src/main/rx/rx.c
113
src/main/rx/rx.c
|
@ -62,6 +62,13 @@ const char rcChannelLetters[] = "AERT12345678abcdefgh";
|
||||||
|
|
||||||
uint16_t rssi = 0; // range: [0;1023]
|
uint16_t rssi = 0; // range: [0;1023]
|
||||||
|
|
||||||
|
static bool rxDataReceived = false;
|
||||||
|
static bool rxSignalReceived = false;
|
||||||
|
static bool shouldCheckPulse = true;
|
||||||
|
|
||||||
|
static uint32_t rxUpdateAt = 0;
|
||||||
|
static uint32_t needRxSignalBefore = 0;
|
||||||
|
|
||||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
|
|
||||||
#define PPM_AND_PWM_SAMPLE_COUNT 4
|
#define PPM_AND_PWM_SAMPLE_COUNT 4
|
||||||
|
@ -70,6 +77,7 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
#define PULSE_MAX 2250 // maximum PWM pulse width which is considered valid
|
#define PULSE_MAX 2250 // maximum PWM pulse width which is considered valid
|
||||||
|
|
||||||
#define DELAY_50_HZ (1000000 / 50)
|
#define DELAY_50_HZ (1000000 / 50)
|
||||||
|
#define DELAY_10_HZ (1000000 / 10)
|
||||||
|
|
||||||
static rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
static rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
||||||
|
|
||||||
|
@ -84,6 +92,28 @@ void useRxConfig(rxConfig_t *rxConfigToUse)
|
||||||
}
|
}
|
||||||
|
|
||||||
#define STICK_CHANNEL_COUNT 4
|
#define STICK_CHANNEL_COUNT 4
|
||||||
|
#define REQUIRED_CHANNEL_MASK 0x0F // first 4 channels
|
||||||
|
|
||||||
|
// pulse duration is in micro seconds (usec)
|
||||||
|
void rxCheckPulse(uint8_t channel, uint16_t pulseDuration)
|
||||||
|
{
|
||||||
|
static uint8_t goodChannelMask = 0;
|
||||||
|
|
||||||
|
if (channel < 4 &&
|
||||||
|
pulseDuration > rxConfig->rx_min_usec &&
|
||||||
|
pulseDuration < rxConfig->rx_max_usec
|
||||||
|
) {
|
||||||
|
// if signal is valid - mark channel as OK
|
||||||
|
goodChannelMask |= (1 << channel);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (goodChannelMask == REQUIRED_CHANNEL_MASK) {
|
||||||
|
goodChannelMask = 0;
|
||||||
|
failsafeOnValidDataReceived();
|
||||||
|
rxSignalReceived = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void rxInit(rxConfig_t *rxConfig)
|
void rxInit(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
|
@ -179,43 +209,71 @@ uint8_t calculateChannelRemapping(uint8_t *channelMap, uint8_t channelMapEntryCo
|
||||||
return channelToRemap;
|
return channelToRemap;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool rcDataReceived = false;
|
bool rxIsReceivingSignal(void)
|
||||||
|
|
||||||
static uint32_t rxUpdateAt = 0;
|
|
||||||
|
|
||||||
|
|
||||||
void updateRx(void)
|
|
||||||
{
|
{
|
||||||
rcDataReceived = false;
|
return rxSignalReceived;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool isRxDataDriven(void) {
|
||||||
|
return !(feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM));
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateRx(uint32_t currentTime)
|
||||||
|
{
|
||||||
|
rxDataReceived = false;
|
||||||
|
shouldCheckPulse = true;
|
||||||
|
|
||||||
|
if (rxSignalReceived) {
|
||||||
|
if (((int32_t)(currentTime - needRxSignalBefore) >= 0)) {
|
||||||
|
rxSignalReceived = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef SERIAL_RX
|
#ifdef SERIAL_RX
|
||||||
if (feature(FEATURE_RX_SERIAL)) {
|
if (feature(FEATURE_RX_SERIAL)) {
|
||||||
uint8_t frameStatus = serialRxFrameStatus(rxConfig);
|
uint8_t frameStatus = serialRxFrameStatus(rxConfig);
|
||||||
|
|
||||||
if (frameStatus & SERIAL_RX_FRAME_COMPLETE) {
|
if (frameStatus & SERIAL_RX_FRAME_COMPLETE) {
|
||||||
rcDataReceived = true;
|
rxDataReceived = true;
|
||||||
if ((frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0 && feature(FEATURE_FAILSAFE)) {
|
rxSignalReceived = (frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0;
|
||||||
failsafeReset();
|
if (rxSignalReceived && feature(FEATURE_FAILSAFE)) {
|
||||||
|
shouldCheckPulse = false;
|
||||||
|
|
||||||
|
failsafeOnValidDataReceived();
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
shouldCheckPulse = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (feature(FEATURE_RX_MSP)) {
|
if (feature(FEATURE_RX_MSP)) {
|
||||||
rcDataReceived = rxMspFrameComplete();
|
rxDataReceived = rxMspFrameComplete();
|
||||||
if (rcDataReceived && feature(FEATURE_FAILSAFE)) {
|
if (rxDataReceived) {
|
||||||
failsafeReset();
|
|
||||||
|
if (feature(FEATURE_FAILSAFE)) {
|
||||||
|
failsafeOnValidDataReceived();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (feature(FEATURE_RX_SERIAL | FEATURE_RX_MSP) && rxDataReceived) {
|
||||||
|
needRxSignalBefore = currentTime + DELAY_10_HZ;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (feature(FEATURE_RX_PPM)) {
|
||||||
|
if (isPPMDataBeingReceived()) {
|
||||||
|
rxSignalReceived = true;
|
||||||
|
needRxSignalBefore = currentTime + DELAY_10_HZ;
|
||||||
|
resetPPMDataReceivedState();
|
||||||
|
}
|
||||||
|
shouldCheckPulse = rxSignalReceived;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool shouldProcessRx(uint32_t currentTime)
|
bool shouldProcessRx(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
return rcDataReceived || ((int32_t)(currentTime - rxUpdateAt) >= 0); // data driven or 50Hz
|
return rxDataReceived || ((int32_t)(currentTime - rxUpdateAt) >= 0); // data driven or 50Hz
|
||||||
}
|
|
||||||
|
|
||||||
static bool isRxDataDriven(void) {
|
|
||||||
return !(feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint8_t rcSampleIndex = 0;
|
static uint8_t rcSampleIndex = 0;
|
||||||
|
@ -256,17 +314,6 @@ static void processRxChannels(void)
|
||||||
return; // rcData will have already been updated by MSP_SET_RAW_RC
|
return; // rcData will have already been updated by MSP_SET_RAW_RC
|
||||||
}
|
}
|
||||||
|
|
||||||
bool shouldCheckPulse = true;
|
|
||||||
|
|
||||||
if (feature(FEATURE_FAILSAFE)) {
|
|
||||||
if (feature(FEATURE_RX_PPM)) {
|
|
||||||
shouldCheckPulse = isPPMDataBeingReceived();
|
|
||||||
resetPPMDataReceivedState();
|
|
||||||
} else {
|
|
||||||
shouldCheckPulse = !isRxDataDriven();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (chan = 0; chan < rxRuntimeConfig.channelCount; chan++) {
|
for (chan = 0; chan < rxRuntimeConfig.channelCount; chan++) {
|
||||||
|
|
||||||
if (!rcReadRawFunc) {
|
if (!rcReadRawFunc) {
|
||||||
|
@ -279,8 +326,8 @@ static void processRxChannels(void)
|
||||||
// sample the channel
|
// sample the channel
|
||||||
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
|
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
|
||||||
|
|
||||||
if (feature(FEATURE_FAILSAFE) && shouldCheckPulse) {
|
if (shouldCheckPulse) {
|
||||||
failsafeCheckPulse(chan, sample);
|
rxCheckPulse(chan, sample);
|
||||||
}
|
}
|
||||||
|
|
||||||
// validate the range
|
// validate the range
|
||||||
|
@ -311,9 +358,7 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
|
||||||
{
|
{
|
||||||
rxUpdateAt = currentTime + DELAY_50_HZ;
|
rxUpdateAt = currentTime + DELAY_50_HZ;
|
||||||
|
|
||||||
if (feature(FEATURE_FAILSAFE)) {
|
failsafeOnRxCycleStarted();
|
||||||
failsafeOnRxCycle();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (isRxDataDriven()) {
|
if (isRxDataDriven()) {
|
||||||
processDataDrivenRx();
|
processDataDrivenRx();
|
||||||
|
|
|
@ -79,6 +79,10 @@ typedef struct rxConfig_s {
|
||||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||||
uint16_t mincheck; // minimum rc end
|
uint16_t mincheck; // minimum rc end
|
||||||
uint16_t maxcheck; // maximum rc end
|
uint16_t maxcheck; // maximum rc end
|
||||||
|
|
||||||
|
uint16_t rx_min_usec;
|
||||||
|
uint16_t rx_max_usec;
|
||||||
|
|
||||||
} rxConfig_t;
|
} rxConfig_t;
|
||||||
|
|
||||||
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
|
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
|
||||||
|
@ -94,7 +98,8 @@ void useRxConfig(rxConfig_t *rxConfigToUse);
|
||||||
|
|
||||||
typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||||
|
|
||||||
void updateRx(void);
|
void updateRx(uint32_t currentTime);
|
||||||
|
bool rxIsReceivingSignal(void);
|
||||||
bool shouldProcessRx(uint32_t currentTime);
|
bool shouldProcessRx(uint32_t currentTime);
|
||||||
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
|
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue