1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-22 07:45:29 +03:00

Review comment fixes

This commit is contained in:
phobos- 2022-08-28 15:14:23 +02:00
parent 185a94384c
commit fb2afd4c5b
6 changed files with 10 additions and 10 deletions

View file

@ -316,7 +316,7 @@ void meanAccumulatorAdd(meanAccumulator_t *filter, const int8_t newVal)
filter->count++;
}
int8_t meanAccumulatorMean(meanAccumulator_t *filter, const int8_t defaultValue)
int8_t meanAccumulatorCalc(meanAccumulator_t *filter, const int8_t defaultValue)
{
if (filter->count) {
int8_t retVal = filter->accumulator / filter->count;

View file

@ -126,5 +126,5 @@ typedef struct meanAccumulator_s {
} meanAccumulator_t;
void meanAccumulatorAdd(meanAccumulator_t *filter, const int8_t newVal);
int8_t meanAccumulatorMean(meanAccumulator_t *filter, const int8_t defaultValue);
int8_t meanAccumulatorCalc(meanAccumulator_t *filter, const int8_t defaultValue);
void meanAccumulatorInit(meanAccumulator_t *filter);

View file

@ -399,7 +399,7 @@ static void expressLrsSendTelemResp(void)
otaPkt.tlm_dl.ul_link_stats.antenna = 0;
otaPkt.tlm_dl.ul_link_stats.modelMatch = connectionHasModelMatch;
otaPkt.tlm_dl.ul_link_stats.lq = receiver.uplinkLQ;
otaPkt.tlm_dl.ul_link_stats.SNR = meanAccumulatorMean(&snrFilter, -16);
otaPkt.tlm_dl.ul_link_stats.SNR = meanAccumulatorCalc(&snrFilter, -16);
#ifdef USE_MSP_OVER_TELEMETRY
otaPkt.tlm_dl.ul_link_stats.mspConfirm = getCurrentMspConfirm() ? 1 : 0;
#else
@ -703,7 +703,7 @@ static bool validatePacketCrcStd(volatile elrsOtaPacket_t * const otaPktPtr)
uint16_t const inCRC = ((uint16_t) otaPktPtr->crcHigh << 8) + otaPktPtr->crcLow;
// For smHybrid the CRC only has the packet type in byte 0
// For smWide the FHSS slot is added to the CRC in byte 0 on PACKET_TYPE_RCDATAs
if (otaPktPtr->type == ELRS_RC_DATA_PACKET && rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE) {
if (otaPktPtr->type == ELRS_RC_DATA_PACKET && rxExpressLrsSpiConfig()->switchMode == SM_WIDE) {
otaPktPtr->crcHigh = (receiver.nonceRX % receiver.modParams->fhssHopInterval) + 1;
} else {
otaPktPtr->crcHigh = 0;
@ -732,7 +732,7 @@ rx_spi_received_e processRFPacket(volatile uint8_t *payload, uint32_t timeStampU
// Must be fully connected to process RC packets, prevents processing RC
// during sync, where packets can be received before connection
if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
if (rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE) {
if (rxExpressLrsSpiConfig()->switchMode == SM_WIDE) {
wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
if ((currTlmDenom < 8) || wideSwitchIndex == 7) {
confirmCurrentTelemetryPayload((otaPktPtr->rc.switches & 0x40) >> 6);
@ -1055,7 +1055,7 @@ void expressLrsSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
{
if (rcData && payload) {
volatile elrsOtaPacket_t * const otaPktPtr = (elrsOtaPacket_t * const) payload;
rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE ? unpackChannelDataHybridWide(rcData, otaPktPtr) : unpackChannelDataHybridSwitch8(rcData, otaPktPtr);
rxExpressLrsSpiConfig()->switchMode == SM_WIDE ? unpackChannelDataHybridWide(rcData, otaPktPtr) : unpackChannelDataHybridSwitch8(rcData, otaPktPtr);
}
}

View file

@ -87,7 +87,7 @@ typedef enum {
} elrsFreqDomain_e;
typedef enum {
SM_HYBRID_WIDE = 0,
SM_WIDE = 0,
SM_HYBRID = 1
} elrsSwitchMode_e;

View file

@ -252,7 +252,7 @@ void receiveMspData(const uint8_t packageIndex, const volatile uint8_t* const re
mspCurrentPackage++;
}
if (acceptData) {
if (acceptData && (receiveData != NULL)) {
uint8_t len = MIN((uint8_t)(mspLength - mspCurrentOffset), ELRS_MSP_BYTES_PER_CALL);
memcpy(&mspData[mspCurrentOffset], (const uint8_t*) receiveData, len);
mspCurrentOffset += len;

View file

@ -258,7 +258,7 @@ TEST(RxSpiExpressLrsUnitTest, TestInitUnbound)
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(16, config.channelCount);
receiver = empty;
rxExpressLrsSpiConfigMutable()->switchMode = SM_HYBRID_WIDE;
rxExpressLrsSpiConfigMutable()->switchMode = SM_WIDE;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(16, config.channelCount);
}
@ -478,6 +478,6 @@ extern "C" {
void updateTelemetryRate(const uint16_t , const uint8_t , const uint8_t ) {}
void meanAccumulatorAdd(meanAccumulator_t * , const int8_t ) {};
int8_t meanAccumulatorMean(meanAccumulator_t * , const int8_t defaultValue) { return defaultValue; };
int8_t meanAccumulatorCalc(meanAccumulator_t * , const int8_t defaultValue) { return defaultValue; };
void meanAccumulatorInit(meanAccumulator_t * ) {};
}