1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Merge pull request #1351 from ProDrone/1345_IS_pid_change_during_boot

RX init issue, optimization.
This commit is contained in:
Dominic Clifton 2015-09-28 00:39:47 +01:00
commit d1616b2795
2 changed files with 19 additions and 28 deletions

View file

@ -414,7 +414,7 @@ static void resetConf(void)
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i]; rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? masterConfig.rxConfig.rx_min_usec : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc); channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
} }
masterConfig.rxConfig.rssi_channel = 0; masterConfig.rxConfig.rssi_channel = 0;

View file

@ -89,6 +89,7 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
rxRuntimeConfig_t rxRuntimeConfig; rxRuntimeConfig_t rxRuntimeConfig;
static rxConfig_t *rxConfig; static rxConfig_t *rxConfig;
static uint8_t rcSampleIndex = 0;
static uint16_t nullReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) { static uint16_t nullReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) {
UNUSED(rxRuntimeConfig); UNUSED(rxRuntimeConfig);
@ -148,14 +149,13 @@ void rxInit(rxConfig_t *rxConfig)
uint8_t i; uint8_t i;
useRxConfig(rxConfig); useRxConfig(rxConfig);
rcSampleIndex = 0;
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rcData[i] = rxConfig->midrc; rcData[i] = rxConfig->midrc;
} }
if (!feature(FEATURE_3D)) { rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig->midrc : rxConfig->rx_min_usec;
rcData[0] = rxConfig->rx_min_usec;
}
#ifdef SERIAL_RX #ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) { if (feature(FEATURE_RX_SERIAL)) {
@ -334,8 +334,6 @@ bool shouldProcessRx(uint32_t currentTime)
return rxDataReceived || ((int32_t)(currentTime - rxUpdateAt) >= 0); // data driven or 50Hz return rxDataReceived || ((int32_t)(currentTime - rxUpdateAt) >= 0); // data driven or 50Hz
} }
static uint8_t rcSampleIndex = 0;
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample) static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
{ {
static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT]; static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT];
@ -427,27 +425,26 @@ static void readRxChannelsApplyRanges(void)
} }
} }
static void processNonDataDrivenRx(void)
{
rcSampleIndex++;
}
static void detectAndApplySignalLossBehaviour(void) static void detectAndApplySignalLossBehaviour(void)
{ {
int channel; int channel;
uint16_t sample;
bool useValueFromRx = true;
bool rxIsDataDriven = isRxDataDriven();
if (!rxSignalReceived) {
if (rxIsDataDriven && rxDataReceived) {
// use the values from the RX
} else {
useValueFromRx = false;
}
}
rxResetFlightChannelStatus(); rxResetFlightChannelStatus();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) { for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
uint16_t sample = rcRaw[channel];
if (!rxSignalReceived) { sample = (useValueFromRx) ? rcRaw[channel] : PPM_RCVR_TIMEOUT;
if (isRxDataDriven() && rxDataReceived) {
// use the values from the RX
} else {
sample = PPM_RCVR_TIMEOUT;
}
}
bool validPulse = isPulseValid(sample); bool validPulse = isPulseValid(sample);
@ -457,7 +454,7 @@ static void detectAndApplySignalLossBehaviour(void)
rxUpdateFlightChannelStatus(channel, validPulse); rxUpdateFlightChannelStatus(channel, validPulse);
if (isRxDataDriven()) { if (rxIsDataDriven) {
rcData[channel] = sample; rcData[channel] = sample;
} else { } else {
rcData[channel] = calculateNonDataDrivenChannel(channel, sample); rcData[channel] = calculateNonDataDrivenChannel(channel, sample);
@ -483,14 +480,6 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
{ {
rxUpdateAt = currentTime + DELAY_50_HZ; rxUpdateAt = currentTime + DELAY_50_HZ;
if (!feature(FEATURE_RX_MSP)) {
// rcData will have already been updated by MSP_SET_RAW_RC
if (!isRxDataDriven()) {
processNonDataDrivenRx();
}
}
// only proceed when no more samples to skip and suspend period is over // only proceed when no more samples to skip and suspend period is over
if (skipRxSamples) { if (skipRxSamples) {
if (currentTime > suspendRxSignalUntil) { if (currentTime > suspendRxSignalUntil) {
@ -501,6 +490,8 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
readRxChannelsApplyRanges(); readRxChannelsApplyRanges();
detectAndApplySignalLossBehaviour(); detectAndApplySignalLossBehaviour();
rcSampleIndex++;
} }
void parseRcChannels(const char *input, rxConfig_t *rxConfig) void parseRcChannels(const char *input, rxConfig_t *rxConfig)