mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 17:25:18 +03:00
Remove Stage1 failsafe; Deprecate FEATURE_FAILSAFE
This commit is contained in:
parent
2725e6a9fc
commit
4f1ba1e431
12 changed files with 26 additions and 235 deletions
|
@ -61,7 +61,7 @@
|
|||
#define PG_MODE_ACTIVATION_PROFILE 41
|
||||
//#define PG_SERVO_PROFILE 42
|
||||
#define PG_SERVO_PARAMS 42
|
||||
#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
|
||||
//#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
|
||||
#define PG_RX_CHANNEL_RANGE_CONFIG 44
|
||||
//#define PG_MODE_COLOR_CONFIG 45
|
||||
//#define PG_SPECIAL_COLOR_CONFIG 46
|
||||
|
|
|
@ -89,7 +89,7 @@
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_FAILSAFE
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
|
||||
|
|
|
@ -49,7 +49,7 @@ typedef enum {
|
|||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_SOFTSERIAL = 1 << 6,
|
||||
FEATURE_GPS = 1 << 7,
|
||||
FEATURE_FAILSAFE = 1 << 8,
|
||||
FEATURE_UNUSED_3 = 1 << 8, // was FAILSAFE
|
||||
FEATURE_SONAR = 1 << 9,
|
||||
FEATURE_TELEMETRY = 1 << 10,
|
||||
FEATURE_CURRENT_METER = 1 << 11,
|
||||
|
|
|
@ -325,10 +325,8 @@ static void initActiveBoxIds(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (feature(FEATURE_FAILSAFE)){
|
||||
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
||||
}
|
||||
}
|
||||
|
||||
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
|
||||
|
||||
|
@ -904,13 +902,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, failsafeConfig()->failsafe_recovery_delay);
|
||||
break;
|
||||
|
||||
case MSP_RXFAIL_CONFIG:
|
||||
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
|
||||
sbufWriteU8(dst, rxFailsafeChannelConfigs(i)->mode);
|
||||
sbufWriteU16(dst, RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(i)->step));
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_RSSI_CONFIG:
|
||||
sbufWriteU8(dst, rxConfig()->rssi_channel);
|
||||
break;
|
||||
|
@ -1886,16 +1877,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_RXFAIL_CONFIG:
|
||||
i = sbufReadU8(src);
|
||||
if (i < MAX_SUPPORTED_RC_CHANNEL_COUNT) {
|
||||
rxFailsafeChannelConfigsMutable(i)->mode = sbufReadU8(src);
|
||||
rxFailsafeChannelConfigsMutable(i)->step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_RSSI_CONFIG:
|
||||
rxConfigMutable()->rssi_channel = sbufReadU8(src);
|
||||
break;
|
||||
|
|
|
@ -302,14 +302,12 @@ void processRx(timeUs_t currentTimeUs)
|
|||
|
||||
updateRSSI(currentTimeUs);
|
||||
|
||||
if (feature(FEATURE_FAILSAFE)) {
|
||||
|
||||
// Update failsafe monitoring system
|
||||
if (currentTimeUs > FAILSAFE_POWER_ON_DELAY_US && !failsafeIsMonitoring()) {
|
||||
failsafeStartMonitoring();
|
||||
}
|
||||
|
||||
failsafeUpdateState();
|
||||
}
|
||||
|
||||
const throttleStatus_e throttleStatus = calculateThrottleStatus(flight3DConfig()->deadband3d_throttle);
|
||||
|
||||
|
@ -368,7 +366,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
|
||||
bool canUseHorizonMode = true;
|
||||
|
||||
if ((IS_RC_MODE_ACTIVE(BOXANGLE) || (feature(FEATURE_FAILSAFE) && failsafeIsActive()) || naivationRequiresAngleMode()) && sensors(SENSOR_ACC)) {
|
||||
if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeIsActive() || naivationRequiresAngleMode()) && sensors(SENSOR_ACC)) {
|
||||
// bumpless transfer to Level mode
|
||||
canUseHorizonMode = false;
|
||||
|
||||
|
|
|
@ -164,7 +164,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_s
|
|||
// Disarming via ARM BOX
|
||||
// Don't disarm via switch if failsafe is active or receiver doesn't receive data - we can't trust receiver
|
||||
// and can't afford to risk disarming in the air
|
||||
if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXFAILSAFE) && feature(FEATURE_FAILSAFE)) && rxIsReceivingSignal() && !failsafeIsActive()) {
|
||||
if (ARMING_FLAG(ARMED) && !IS_RC_MODE_ACTIVE(BOXFAILSAFE) && rxIsReceivingSignal() && !failsafeIsActive()) {
|
||||
rcDisarmTicks++;
|
||||
if (rcDisarmTicks > 3) { // Wait for at least 3 RX ticks (60ms @ 50Hz RX)
|
||||
if (disarm_kill_switch) {
|
||||
|
|
|
@ -147,21 +147,13 @@ static const char * const mixerNames[] = {
|
|||
// sync this with features_e
|
||||
static const char * const featureNames[] = {
|
||||
"RX_PPM", "VBAT", "UNUSED_1", "RX_SERIAL", "MOTOR_STOP",
|
||||
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
||||
"SERVO_TILT", "SOFTSERIAL", "GPS", "UNUSED_3",
|
||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "UNUSED_2",
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
|
||||
"SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE", "OSD", NULL
|
||||
};
|
||||
|
||||
// sync this with rxFailsafeChannelMode_e
|
||||
static const char rxFailsafeModeCharacters[] = "ahs";
|
||||
|
||||
static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
|
||||
{ RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
|
||||
{ RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
|
||||
};
|
||||
|
||||
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
||||
// sync with gyroSensor_e
|
||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE"};
|
||||
|
@ -897,7 +889,6 @@ static rxConfig_t rxConfigCopy;
|
|||
#ifdef BLACKBOX
|
||||
static blackboxConfig_t blackboxConfigCopy;
|
||||
#endif
|
||||
static rxFailsafeChannelConfig_t rxFailsafeChannelConfigsCopy[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
static rxChannelRangeConfig_t rxChannelRangeConfigsCopy[NON_AUX_CHANNEL_COUNT];
|
||||
static motorConfig_t motorConfigCopy;
|
||||
static failsafeConfig_t failsafeConfigCopy;
|
||||
|
@ -1261,10 +1252,6 @@ static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn
|
|||
ret.currentConfig = &pidProfileCopy[getConfigProfile()];
|
||||
ret.defaultConfig = pidProfile();
|
||||
break;
|
||||
case PG_RX_FAILSAFE_CHANNEL_CONFIG:
|
||||
ret.currentConfig = &rxFailsafeChannelConfigsCopy[0];
|
||||
ret.defaultConfig = rxFailsafeChannelConfigs(0);
|
||||
break;
|
||||
case PG_RX_CHANNEL_RANGE_CONFIG:
|
||||
ret.currentConfig = &rxChannelRangeConfigsCopy[0];
|
||||
ret.defaultConfig = rxChannelRangeConfigs(0);
|
||||
|
@ -1478,133 +1465,6 @@ static bool isEmpty(const char *string)
|
|||
return (string == NULL || *string == '\0') ? true : false;
|
||||
}
|
||||
|
||||
static void printRxFailsafe(uint8_t dumpMask, const rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs, const rxFailsafeChannelConfig_t *defaultRxFailsafeChannelConfigs)
|
||||
{
|
||||
// print out rxConfig failsafe settings
|
||||
for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
|
||||
const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxFailsafeChannelConfigs[channel];
|
||||
const rxFailsafeChannelConfig_t *channelFailsafeConfigDefault;
|
||||
bool equalsDefault = true;
|
||||
if (defaultRxFailsafeChannelConfigs) {
|
||||
channelFailsafeConfigDefault = &defaultRxFailsafeChannelConfigs[channel];
|
||||
equalsDefault = (channelFailsafeConfig->mode == channelFailsafeConfigDefault->mode)
|
||||
&& (channelFailsafeConfig->step == channelFailsafeConfigDefault->step);
|
||||
}
|
||||
const bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
|
||||
if (requireValue) {
|
||||
const char *format = "rxfail %u %c %d\r\n";
|
||||
if (defaultRxFailsafeChannelConfigs) {
|
||||
cliDefaultPrintf(dumpMask, equalsDefault, format,
|
||||
channel,
|
||||
rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode],
|
||||
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigDefault->step)
|
||||
);
|
||||
}
|
||||
cliDumpPrintf(dumpMask, equalsDefault, format,
|
||||
channel,
|
||||
rxFailsafeModeCharacters[channelFailsafeConfig->mode],
|
||||
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
|
||||
);
|
||||
} else {
|
||||
const char *format = "rxfail %u %c\r\n";
|
||||
if (defaultRxFailsafeChannelConfigs) {
|
||||
cliDefaultPrintf(dumpMask, equalsDefault, format,
|
||||
channel,
|
||||
rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode]
|
||||
);
|
||||
}
|
||||
cliDumpPrintf(dumpMask, equalsDefault, format,
|
||||
channel,
|
||||
rxFailsafeModeCharacters[channelFailsafeConfig->mode]
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliRxFailsafe(char *cmdline)
|
||||
{
|
||||
uint8_t channel;
|
||||
char buf[3];
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
// print out rxConfig failsafe settings
|
||||
for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
|
||||
cliRxFailsafe(itoa(channel, buf, 10));
|
||||
}
|
||||
} else {
|
||||
const char *ptr = cmdline;
|
||||
channel = atoi(ptr++);
|
||||
if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
|
||||
|
||||
// const cast
|
||||
rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigsMutable(channel);
|
||||
|
||||
const rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
|
||||
rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
|
||||
bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
|
||||
|
||||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
const char *p = strchr(rxFailsafeModeCharacters, *(ptr));
|
||||
if (p) {
|
||||
const uint8_t requestedMode = p - rxFailsafeModeCharacters;
|
||||
mode = rxFailsafeModesTable[type][requestedMode];
|
||||
} else {
|
||||
mode = RX_FAILSAFE_MODE_INVALID;
|
||||
}
|
||||
if (mode == RX_FAILSAFE_MODE_INVALID) {
|
||||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
|
||||
requireValue = mode == RX_FAILSAFE_MODE_SET;
|
||||
|
||||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
if (!requireValue) {
|
||||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
uint16_t value = atoi(ptr);
|
||||
value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
|
||||
if (value > MAX_RXFAIL_RANGE_STEP) {
|
||||
cliPrint("Value out of range\r\n");
|
||||
return;
|
||||
}
|
||||
|
||||
channelFailsafeConfig->step = value;
|
||||
} else if (requireValue) {
|
||||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
channelFailsafeConfig->mode = mode;
|
||||
}
|
||||
|
||||
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfig->mode];
|
||||
|
||||
// triple use of cliPrintf below
|
||||
// 1. acknowledge interpretation on command,
|
||||
// 2. query current setting on single item,
|
||||
// 3. recursive use for full list.
|
||||
|
||||
if (requireValue) {
|
||||
cliPrintf("rxfail %u %c %d\r\n",
|
||||
channel,
|
||||
modeCharacter,
|
||||
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
|
||||
);
|
||||
} else {
|
||||
cliPrintf("rxfail %u %c\r\n",
|
||||
channel,
|
||||
modeCharacter
|
||||
);
|
||||
}
|
||||
} else {
|
||||
cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(USE_ASSERT)
|
||||
static void cliAssert(char *cmdline)
|
||||
{
|
||||
|
@ -3548,9 +3408,6 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
cliPrintHashLine("rxrange");
|
||||
printRxRange(dumpMask, rxChannelRangeConfigsCopy, rxChannelRangeConfigs(0));
|
||||
|
||||
cliPrintHashLine("rxfail");
|
||||
printRxFailsafe(dumpMask, rxFailsafeChannelConfigsCopy, rxFailsafeChannelConfigs(0));
|
||||
|
||||
cliPrintHashLine("master");
|
||||
dumpAllValues(MASTER_VALUE, dumpMask);
|
||||
|
||||
|
@ -3680,7 +3537,6 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
|
||||
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFailsafe),
|
||||
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
|
||||
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
|
||||
#ifdef USE_SERVOS
|
||||
|
|
|
@ -538,7 +538,7 @@ static void applyLedWarningLayer(bool updateNow, timeUs_t *timer)
|
|||
warningFlags = 0;
|
||||
if (feature(FEATURE_VBAT) && getBatteryState() != BATTERY_OK)
|
||||
warningFlags |= 1 << WARNING_LOW_BATTERY;
|
||||
if (feature(FEATURE_FAILSAFE) && failsafeIsActive())
|
||||
if (failsafeIsActive())
|
||||
warningFlags |= 1 << WARNING_FAILSAFE;
|
||||
if (!ARMING_FLAG(ARMED) && !ARMING_FLAG(OK_TO_ARM))
|
||||
warningFlags |= 1 << WARNING_ARMING_DISABLED;
|
||||
|
|
|
@ -189,8 +189,9 @@
|
|||
#define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings
|
||||
#define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings
|
||||
|
||||
#define MSP_RXFAIL_CONFIG 77 //out message Returns RXFAIL settings
|
||||
#define MSP_SET_RXFAIL_CONFIG 78 //in message Sets RXFAIL settings
|
||||
// DEPRECATED
|
||||
//#define MSP_RXFAIL_CONFIG 77 //out message Returns RXFAIL settings
|
||||
//#define MSP_SET_RXFAIL_CONFIG 78 //in message Sets RXFAIL settings
|
||||
|
||||
#define MSP_SDCARD_SUMMARY 79 //out message Get the state of the SD card
|
||||
|
||||
|
|
|
@ -143,21 +143,6 @@ void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t *rxChannelRangeConfi
|
|||
}
|
||||
}
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs, PG_RX_FAILSAFE_CHANNEL_CONFIG, 0);
|
||||
|
||||
void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs)
|
||||
{
|
||||
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
|
||||
if (i== THROTTLE) {
|
||||
rxFailsafeChannelConfigs[i].mode = RX_FAILSAFE_MODE_HOLD;
|
||||
rxFailsafeChannelConfigs[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEX);
|
||||
} else {
|
||||
rxFailsafeChannelConfigs[i].mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
|
||||
rxFailsafeChannelConfigs[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIDRC);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
|
||||
{
|
||||
UNUSED(rxRuntimeConfig);
|
||||
|
@ -423,30 +408,23 @@ static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
|
|||
return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT;
|
||||
}
|
||||
|
||||
static uint16_t getRxfailValue(uint8_t channel)
|
||||
static uint16_t getRxNosignalValue(uint8_t channel)
|
||||
{
|
||||
switch(rxFailsafeChannelConfigs(channel)->mode) {
|
||||
case RX_FAILSAFE_MODE_AUTO:
|
||||
switch (channel) {
|
||||
case ROLL:
|
||||
case PITCH:
|
||||
case YAW:
|
||||
return rxConfig()->midrc;
|
||||
|
||||
case THROTTLE:
|
||||
if (feature(FEATURE_3D))
|
||||
return rxConfig()->midrc;
|
||||
else
|
||||
return rxConfig()->rx_min_usec;
|
||||
}
|
||||
/* no break */
|
||||
|
||||
default:
|
||||
case RX_FAILSAFE_MODE_INVALID:
|
||||
case RX_FAILSAFE_MODE_HOLD:
|
||||
//return rxConfig()->rx_min_usec;
|
||||
return rcData[channel];
|
||||
|
||||
case RX_FAILSAFE_MODE_SET:
|
||||
return RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(channel)->step);
|
||||
default:
|
||||
return rcData[channel];
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -514,7 +492,7 @@ static void detectAndApplySignalLossBehaviour(void)
|
|||
if (currentMilliTime < rcInvalidPulsPeriod[channel]) {
|
||||
sample = rcData[channel]; // hold channel for MAX_INVALID_PULS_TIME
|
||||
} else {
|
||||
sample = getRxfailValue(channel); // after that apply rxfail value
|
||||
sample = getRxNosignalValue(channel); // after that apply rxfail value
|
||||
rxUpdateFlightChannelStatus(channel, validPulse);
|
||||
}
|
||||
} else {
|
||||
|
@ -530,14 +508,14 @@ static void detectAndApplySignalLossBehaviour(void)
|
|||
|
||||
rxFlightChannelsValid = rxHaveValidFlightChannels();
|
||||
|
||||
if ((rxFlightChannelsValid) && !(IS_RC_MODE_ACTIVE(BOXFAILSAFE) && feature(FEATURE_FAILSAFE))) {
|
||||
if (rxFlightChannelsValid && !IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
|
||||
failsafeOnValidDataReceived();
|
||||
} else {
|
||||
rxIsInFailsafeMode = rxIsInFailsafeModeNotDataDriven = true;
|
||||
failsafeOnValidDataFailed();
|
||||
|
||||
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
|
||||
rcData[channel] = getRxfailValue(channel);
|
||||
rcData[channel] = getRxNosignalValue(channel);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -85,28 +85,6 @@ extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2
|
|||
#define RSSI_SCALE_MAX 255
|
||||
#define RSSI_SCALE_DEFAULT 30
|
||||
|
||||
typedef enum {
|
||||
RX_FAILSAFE_MODE_AUTO = 0,
|
||||
RX_FAILSAFE_MODE_HOLD,
|
||||
RX_FAILSAFE_MODE_SET,
|
||||
RX_FAILSAFE_MODE_INVALID
|
||||
} rxFailsafeChannelMode_e;
|
||||
|
||||
#define RX_FAILSAFE_MODE_COUNT 3
|
||||
|
||||
typedef enum {
|
||||
RX_FAILSAFE_TYPE_FLIGHT = 0,
|
||||
RX_FAILSAFE_TYPE_AUX
|
||||
} rxFailsafeChannelType_e;
|
||||
|
||||
#define RX_FAILSAFE_TYPE_COUNT 2
|
||||
|
||||
typedef struct rxFailsafeChannelConfig_s {
|
||||
uint8_t mode; // See rxFailsafeChannelMode_e
|
||||
uint8_t step;
|
||||
} rxFailsafeChannelConfig_t;
|
||||
PG_DECLARE_ARRAY(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs);
|
||||
|
||||
typedef struct rxChannelRangeConfig_s {
|
||||
uint16_t min;
|
||||
uint16_t max;
|
||||
|
|
|
@ -45,7 +45,6 @@ void targetConfiguration(void)
|
|||
|
||||
featureSet(FEATURE_VBAT);
|
||||
featureSet(FEATURE_LED_STRIP);
|
||||
featureSet(FEATURE_FAILSAFE);
|
||||
|
||||
serialConfigMutable()->portConfigs[0].functionMask = FUNCTION_MSP;
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue