mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Merge branch 'softserial-track-errors' into hott-telemetry
Conflicts: src/drv_softserial.c
This commit is contained in:
commit
8138bc8cf3
4 changed files with 64 additions and 26 deletions
|
@ -146,6 +146,9 @@ void initialiseSoftSerial(softSerial_t *softSerial, uint8_t portIndex, uint32_t
|
||||||
softSerial->rxBitIndex = 0;
|
softSerial->rxBitIndex = 0;
|
||||||
softSerial->isInverted = inverted;
|
softSerial->isInverted = inverted;
|
||||||
|
|
||||||
|
softSerial->transmissionErrors = 0;
|
||||||
|
softSerial->receiveErrors = 0;
|
||||||
|
|
||||||
serialOutputPortConfig(softSerial->txTimerHardware);
|
serialOutputPortConfig(softSerial->txTimerHardware);
|
||||||
serialInputPortConfig(softSerial->rxTimerHardware);
|
serialInputPortConfig(softSerial->rxTimerHardware);
|
||||||
|
|
||||||
|
@ -267,12 +270,23 @@ void prepareForNextRxByte(softSerial_t *softSerial)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#define STOP_BIT_MASK (1 << 0)
|
||||||
|
#define START_BIT_MASK (1 << (RX_TOTAL_BITS - 1))
|
||||||
|
|
||||||
void extractAndStoreRxByte(softSerial_t *softSerial)
|
void extractAndStoreRxByte(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
if ((softSerial->port.mode & MODE_RX) == 0) {
|
if ((softSerial->port.mode & MODE_RX) == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint8_t haveStartBit = (softSerial->internalRxBuffer & START_BIT_MASK) == 0;
|
||||||
|
uint8_t haveStopBit = (softSerial->internalRxBuffer & STOP_BIT_MASK) == 1;
|
||||||
|
|
||||||
|
if (!haveStartBit || !haveStopBit) {
|
||||||
|
softSerial->receiveErrors++;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF;
|
uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF;
|
||||||
softSerial->port.rxBuffer[softSerial->port.rxBufferTail] = rxByte;
|
softSerial->port.rxBuffer[softSerial->port.rxBufferTail] = rxByte;
|
||||||
updateBufferIndex(softSerial);
|
updateBufferIndex(softSerial);
|
||||||
|
@ -292,6 +306,11 @@ void processRxState(softSerial_t *softSerial)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (softSerial->rxBitIndex == RX_TOTAL_BITS) {
|
if (softSerial->rxBitIndex == RX_TOTAL_BITS) {
|
||||||
|
|
||||||
|
if (softSerial->rxEdge == TRAILING) {
|
||||||
|
softSerial->internalRxBuffer |= STOP_BIT_MASK;
|
||||||
|
}
|
||||||
|
|
||||||
extractAndStoreRxByte(softSerial);
|
extractAndStoreRxByte(softSerial);
|
||||||
prepareForNextRxByte(softSerial);
|
prepareForNextRxByte(softSerial);
|
||||||
}
|
}
|
||||||
|
@ -314,7 +333,14 @@ void onSerialRxPinChange(uint8_t portIndex, uint16_t capture)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (softSerial->isSearchingForStartBit) {
|
if (softSerial->isSearchingForStartBit) {
|
||||||
TIM_SetCounter(softSerial->rxTimerHardware->tim, 0); // synchronise bit counter
|
// synchronise bit counter
|
||||||
|
// FIXME this reduces functionality somewhat as receiving breaks concurrent transmission on all ports because
|
||||||
|
// the next callback to the onSerialTimer will happen too early causing transmission errors.
|
||||||
|
TIM_SetCounter(softSerial->rxTimerHardware->tim, 0);
|
||||||
|
if (softSerial->isTransmittingData) {
|
||||||
|
softSerial->transmissionErrors++;
|
||||||
|
}
|
||||||
|
|
||||||
serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->isInverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
serialICConfig(softSerial->rxTimerHardware->tim, softSerial->rxTimerHardware->channel, softSerial->isInverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
||||||
softSerial->rxEdge = LEADING;
|
softSerial->rxEdge = LEADING;
|
||||||
|
|
||||||
|
|
|
@ -30,6 +30,9 @@ typedef struct softSerial_s {
|
||||||
uint16_t internalRxBuffer; // includes start and stop bits
|
uint16_t internalRxBuffer; // includes start and stop bits
|
||||||
|
|
||||||
uint8_t isInverted;
|
uint8_t isInverted;
|
||||||
|
|
||||||
|
uint16_t transmissionErrors;
|
||||||
|
uint16_t receiveErrors;
|
||||||
} softSerial_t;
|
} softSerial_t;
|
||||||
|
|
||||||
extern timerHardware_t* serialTimerHardware;
|
extern timerHardware_t* serialTimerHardware;
|
||||||
|
|
|
@ -181,36 +181,40 @@ static void timCCxHandler(TIM_TypeDef *tim)
|
||||||
uint16_t capture;
|
uint16_t capture;
|
||||||
timerConfig_t *timerConfig;
|
timerConfig_t *timerConfig;
|
||||||
|
|
||||||
if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
|
uint8_t channelIndex = 0;
|
||||||
TIM_ClearITPendingBit(tim, TIM_IT_CC1);
|
for (channelIndex = 0; channelIndex < CC_CHANNELS_PER_TIMER; channelIndex++) {
|
||||||
|
uint8_t channel = channels[channelIndex];
|
||||||
|
|
||||||
timerConfig = findTimerConfig(tim, TIM_Channel_1);
|
if (channel == TIM_Channel_1 && TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
|
||||||
capture = TIM_GetCapture1(tim);
|
TIM_ClearITPendingBit(tim, TIM_IT_CC1);
|
||||||
} else if (TIM_GetITStatus(tim, TIM_IT_CC2) == SET) {
|
|
||||||
TIM_ClearITPendingBit(tim, TIM_IT_CC2);
|
|
||||||
|
|
||||||
timerConfig = findTimerConfig(tim, TIM_Channel_2);
|
timerConfig = findTimerConfig(tim, TIM_Channel_1);
|
||||||
capture = TIM_GetCapture2(tim);
|
capture = TIM_GetCapture1(tim);
|
||||||
} else if (TIM_GetITStatus(tim, TIM_IT_CC3) == SET) {
|
} else if (channel == TIM_Channel_2 && TIM_GetITStatus(tim, TIM_IT_CC2) == SET) {
|
||||||
TIM_ClearITPendingBit(tim, TIM_IT_CC3);
|
TIM_ClearITPendingBit(tim, TIM_IT_CC2);
|
||||||
|
|
||||||
timerConfig = findTimerConfig(tim, TIM_Channel_3);
|
timerConfig = findTimerConfig(tim, TIM_Channel_2);
|
||||||
capture = TIM_GetCapture3(tim);
|
capture = TIM_GetCapture2(tim);
|
||||||
} else if (TIM_GetITStatus(tim, TIM_IT_CC4) == SET) {
|
} else if (channel == TIM_Channel_3 && TIM_GetITStatus(tim, TIM_IT_CC3) == SET) {
|
||||||
TIM_ClearITPendingBit(tim, TIM_IT_CC4);
|
TIM_ClearITPendingBit(tim, TIM_IT_CC3);
|
||||||
|
|
||||||
timerConfig = findTimerConfig(tim, TIM_Channel_4);
|
timerConfig = findTimerConfig(tim, TIM_Channel_3);
|
||||||
capture = TIM_GetCapture4(tim);
|
capture = TIM_GetCapture3(tim);
|
||||||
} else {
|
} else if (channel == TIM_Channel_4 && TIM_GetITStatus(tim, TIM_IT_CC4) == SET) {
|
||||||
return; // avoid uninitialised variable dereference
|
TIM_ClearITPendingBit(tim, TIM_IT_CC4);
|
||||||
|
|
||||||
|
timerConfig = findTimerConfig(tim, TIM_Channel_4);
|
||||||
|
capture = TIM_GetCapture4(tim);
|
||||||
|
} else {
|
||||||
|
continue; // avoid uninitialised variable dereference
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!timerConfig->callback) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
timerConfig->callback(timerConfig->reference, capture);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!timerConfig->callback) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
timerConfig->callback(timerConfig->reference, capture);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TIM1_CC_IRQHandler(void)
|
void TIM1_CC_IRQHandler(void)
|
||||||
{
|
{
|
||||||
timCCxHandler(TIM1);
|
timCCxHandler(TIM1);
|
||||||
|
|
|
@ -186,14 +186,19 @@ int main(void)
|
||||||
//serialWrite(core.mainport, b);
|
//serialWrite(core.mainport, b);
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
if (loopbackPort2) {
|
if (loopbackPort2) {
|
||||||
while (serialTotalBytesWaiting(loopbackPort2)) {
|
while (serialTotalBytesWaiting(loopbackPort2)) {
|
||||||
|
#ifndef OLIMEXINO // PB0/D27 and PB1/D28 internally connected so this would result in a continuous stream of data
|
||||||
|
serialRead(loopbackPort2);
|
||||||
|
#else
|
||||||
uint8_t b = serialRead(loopbackPort2);
|
uint8_t b = serialRead(loopbackPort2);
|
||||||
serialWrite(loopbackPort2, b);
|
serialWrite(loopbackPort2, b);
|
||||||
//serialWrite(core.mainport, 0x02);
|
//serialWrite(core.mainport, 0x02);
|
||||||
//serialWrite(core.mainport, b);
|
//serialWrite(core.mainport, b);
|
||||||
|
#endif // OLIMEXINO
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue