1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Fixed rxfail and rxrange CLI commands

This commit is contained in:
DieHertz 2017-03-16 18:14:22 +03:00
parent dcecf9dc67
commit 0b100bf167
7 changed files with 43 additions and 43 deletions

View file

@ -2002,7 +2002,7 @@ static void cliRxFailsafe(char *cmdline)
channel = atoi(ptr++);
if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfigMutable()->failsafe_channel_configurations[channel];
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;
@ -2565,9 +2565,9 @@ static void cliRxRange(char *cmdline)
const char *ptr;
if (isEmpty(cmdline)) {
printRxRange(DUMP_MASTER, rxConfig()->channelRanges, NULL);
printRxRange(DUMP_MASTER, rxChannelRangeConfigs(0), NULL);
} else if (strcasecmp(cmdline, "reset") == 0) {
resetAllRxChannelRangeConfigurations(rxConfigMutable()->channelRanges);
resetAllRxChannelRangeConfigurations(rxChannelRangeConfigsMutable(0));
} else {
ptr = cmdline;
i = atoi(ptr);
@ -2591,7 +2591,7 @@ static void cliRxRange(char *cmdline)
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
cliShowParseError();
} else {
rxChannelRangeConfig_t *channelRangeConfig = &rxConfigMutable()->channelRanges[i];
rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigsMutable(i);
channelRangeConfig->min = rangeMin;
channelRangeConfig->max = rangeMax;
}
@ -3858,8 +3858,6 @@ static void cliProfile(char *cmdline)
const int i = atoi(cmdline);
if (i >= 0 && i < MAX_PROFILE_COUNT) {
systemConfigMutable()->pidProfileIndex = i;
writeEEPROM();
readEEPROM();
cliProfile("");
}
}

View file

@ -1057,8 +1057,6 @@ void changePidProfile(uint8_t pidProfileIndex)
}
systemConfigMutable()->pidProfileIndex = pidProfileIndex;
currentPidProfile = pidProfilesMutable(pidProfileIndex);
writeEEPROM();
readEEPROM();
beeperConfirmationBeeps(pidProfileIndex + 1);
}

View file

@ -1816,8 +1816,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_RXFAIL_CONFIG:
i = sbufReadU8(src);
if (i < MAX_SUPPORTED_RC_CHANNEL_COUNT) {
rxConfigMutable()->failsafe_channel_configurations[i].mode = sbufReadU8(src);
rxConfigMutable()->failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
rxFailsafeChannelConfigsMutable(i)->mode = sbufReadU8(src);
rxFailsafeChannelConfigsMutable(i)->step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
} else {
return MSP_RESULT_ERROR;
}

View file

@ -29,6 +29,7 @@
#include "common/maths.h"
#include "common/utils.h"
#include "config/config_reset.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
@ -101,29 +102,35 @@ static uint8_t rcSampleIndex = 0;
#define SERIALRX_PROVIDER 0
#endif
#define RX_MIN_USEC 885
#define RX_MAX_USEC 2115
#define RX_MID_USEC 1500
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
{
rxConfig->halfDuplex = 0;
rxConfig->serialrx_provider = SERIALRX_PROVIDER;
rxConfig->rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
rxConfig->sbus_inversion = 1;
rxConfig->spektrum_sat_bind = 0;
rxConfig->spektrum_sat_bind_autoreset = 1;
rxConfig->midrc = 1500;
rxConfig->mincheck = 1100;
rxConfig->maxcheck = 1900;
rxConfig->rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
rxConfig->rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
rxConfig->rssi_channel = 0;
rxConfig->rssi_scale = RSSI_SCALE_DEFAULT;
rxConfig->rssi_invert = 0;
rxConfig->rcInterpolation = RC_SMOOTHING_AUTO;
rxConfig->rcInterpolationChannels = 0;
rxConfig->rcInterpolationInterval = 19;
rxConfig->fpvCamAngleDegrees = 0;
rxConfig->max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT;
rxConfig->airModeActivateThreshold = 1350;
RESET_CONFIG(const rxConfig_t, rxConfig,
.halfDuplex = 0,
.serialrx_provider = SERIALRX_PROVIDER,
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
.sbus_inversion = 1,
.spektrum_sat_bind = 0,
.spektrum_sat_bind_autoreset = 1,
.midrc = RX_MID_USEC,
.mincheck = 1100,
.maxcheck = 1900,
.rx_min_usec = RX_MIN_USEC, // any of first 4 channels below this value will trigger rx loss detection
.rx_max_usec = RX_MAX_USEC, // any of first 4 channels above this value will trigger rx loss detection
.rssi_channel = 0,
.rssi_scale = RSSI_SCALE_DEFAULT,
.rssi_invert = 0,
.rcInterpolation = RC_SMOOTHING_AUTO,
.rcInterpolationChannels = 0,
.rcInterpolationInterval = 19,
.fpvCamAngleDegrees = 0,
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT,
.airModeActivateThreshold = 1350
);
#ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", rxConfig);
@ -148,8 +155,8 @@ void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeCha
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfigs[i].mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
rxFailsafeChannelConfigs[i].step = (i == THROTTLE)
? CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->rx_min_usec)
: CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->midrc);
? CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEC)
: CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MID_USEC);
}
}
@ -430,7 +437,7 @@ static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
static uint16_t getRxfailValue(uint8_t channel)
{
const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxConfig()->failsafe_channel_configurations[channel];
const rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigs(channel);
switch(channelFailsafeConfig->mode) {
case RX_FAILSAFE_MODE_AUTO:
@ -498,7 +505,7 @@ static void readRxChannelsApplyRanges(void)
// apply the rx calibration
if (channel < NON_AUX_CHANNEL_COUNT) {
sample = applyRxChannelRangeConfiguraton(sample, &rxConfig()->channelRanges[channel]);
sample = applyRxChannelRangeConfiguraton(sample, rxChannelRangeConfigs(channel));
}
rcRaw[channel] = sample;

View file

@ -140,9 +140,6 @@ typedef struct rxConfig_s {
uint16_t rx_min_usec;
uint16_t rx_max_usec;
rxFailsafeChannelConfig_t failsafe_channel_configurations[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxChannelRangeConfig_t channelRanges[NON_AUX_CHANNEL_COUNT];
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);

View file

@ -891,8 +891,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
case BST_RXFAIL_CONFIG:
for (i = NON_AUX_CHANNEL_COUNT; i < rxRuntimeConfig.channelCount; i++) {
bstWrite8(rxConfig()->failsafe_channel_configurations[i].mode);
bstWrite16(RXFAIL_STEP_TO_CHANNEL_VALUE(rxConfig()->failsafe_channel_configurations[i].step));
bstWrite8(rxFailsafeChannelConfigs(i)->mode);
bstWrite16(RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(i)->step));
}
break;
@ -1307,8 +1307,8 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
ret = BST_FAILED;
} else {
for (i = NON_AUX_CHANNEL_COUNT; i < channelCount; i++) {
rxConfigMutable()->failsafe_channel_configurations[i].mode = bstRead8();
rxConfigMutable()->failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(bstRead16());
rxFailsafeChannelConfigsMutable(i)->mode = bstRead8();
rxFailsafeChannelConfigsMutable(i)->step = CHANNEL_VALUE_TO_RXFAIL_STEP(bstRead16());
}
}
}

View file

@ -57,8 +57,8 @@ void targetConfiguration(void)
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
/*for (int channel = 0; channel < NON_AUX_CHANNEL_COUNT; channel++) {
rxConfigMutable()->channelRanges[channel].min = 1180;
rxConfigMutable()->channelRanges[channel].max = 1860;
rxChannelRangeConfigsMutable(channel)->min = 1180;
rxChannelRangeConfigsMutable(channel)->max = 1860;
}*/
for (int profileId = 0; profileId < 2; profileId++) {