1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

only TX in kiss mode

This commit is contained in:
Sami Korhonen 2016-10-23 10:18:19 +03:00
parent 7929e1b8f1
commit 14d1e25280

View file

@ -79,6 +79,7 @@ typedef struct escSerial_s {
uint16_t receiveErrors; uint16_t receiveErrors;
uint8_t escSerialPortIndex; uint8_t escSerialPortIndex;
uint8_t mode;
timerCCHandlerRec_t timerCb; timerCCHandlerRec_t timerCb;
timerCCHandlerRec_t edgeCb; timerCCHandlerRec_t edgeCb;
@ -120,12 +121,10 @@ static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg)
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr) void serialInputPortConfig(const timerHardware_t *timerHardwarePtr)
{ {
#ifdef STM32F10X #ifdef STM32F10X
escSerialGPIOConfig(timerHardwarePtr->tag, Mode_IPU); escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU);
#else #else
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_AF_PP_UP); escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_AF_PP_UP);
#endif #endif
//escSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
timerChClearCCFlag(timerHardwarePtr); timerChClearCCFlag(timerHardwarePtr);
timerChITConfig(timerHardwarePtr,ENABLE); timerChITConfig(timerHardwarePtr,ENABLE);
} }
@ -258,11 +257,15 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac
serialTimerTxConfig(escSerial->txTimerHardware, portIndex); serialTimerTxConfig(escSerial->txTimerHardware, portIndex);
serialTimerRxConfig(escSerial->rxTimerHardware, portIndex); serialTimerRxConfig(escSerial->rxTimerHardware, portIndex);
} }
if(mode==1 || mode==2){ else if(mode==1){
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud); serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
serialTimerRxConfigBL(escSerial->rxTimerHardware, portIndex, options); serialTimerRxConfigBL(escSerial->rxTimerHardware, portIndex, options);
} }
else if(mode==2) {
serialOutputPortConfig(escSerial->rxTimerHardware); // rx is the pin used
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
}
escSerial->mode = mode;
return &escSerial->port; return &escSerial->port;
} }
@ -429,8 +432,11 @@ void processTxStateBL(escSerial_t *escSerial)
escSerial->isTransmittingData = false; escSerial->isTransmittingData = false;
if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) { if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) {
if(escSerial->mode==1)
{
serialInputPortConfig(escSerial->rxTimerHardware); serialInputPortConfig(escSerial->rxTimerHardware);
} }
}
} }
@ -863,6 +869,8 @@ void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uin
escPort = openEscSerial(ESCSERIAL1, NULL, motor_output, escBaudrate, 0, mode); escPort = openEscSerial(ESCSERIAL1, NULL, motor_output, escBaudrate, 0, mode);
uint8_t ch; uint8_t ch;
while(1) { while(1) {
if(mode!=2)
{
if (serialRxBytesWaiting(escPort)) { if (serialRxBytesWaiting(escPort)) {
LED0_ON; LED0_ON;
while(serialRxBytesWaiting(escPort)) while(serialRxBytesWaiting(escPort))
@ -872,6 +880,7 @@ void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uin
} }
LED0_OFF; LED0_OFF;
} }
}
if (serialRxBytesWaiting(escPassthroughPort)) { if (serialRxBytesWaiting(escPassthroughPort)) {
LED1_ON; LED1_ON;
while(serialRxBytesWaiting(escPassthroughPort)) while(serialRxBytesWaiting(escPassthroughPort))