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

Fix escserial for HAL targets. (#12992)

* Fix escserial for HAL targets.

* Remove the code disabling ESCSERIAL for F7.

* Timer/StdPeriph - Add an implementation of 'timerReconfigureTimebase'.

Simply calls the `configTimeBase`, seemed cleaner than adding #ifdef USE_HAL_DRIVER everywhere instead.
This commit is contained in:
Dominic Clifton 2023-08-08 00:49:48 +02:00 committed by GitHub
parent 0eac4df5a4
commit 199c0ec99d
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
8 changed files with 56 additions and 93 deletions

View file

@ -111,7 +111,7 @@ typedef struct {
escOutputs_t escOutputs[MAX_SUPPORTED_MOTORS];
extern timerHardware_t* serialTimerHardware;
//extern timerHardware_t* serialTimerHardware;
const struct serialPortVTable escSerialVTable[];
@ -135,11 +135,10 @@ enum {
#define STOP_BIT_MASK (1 << 0)
#define START_BIT_MASK (1 << (RX_TOTAL_BITS - 1))
// XXX No TIM_DeInit equivalent in HAL driver???
#ifdef USE_HAL_DRIVER
static void TIM_DeInit(TIM_TypeDef *tim)
{
UNUSED(tim);
LL_TIM_DeInit(tim);
}
#endif
@ -183,7 +182,7 @@ static void escSerialGPIOConfig(const timerHardware_t *timhw, ioConfig_t cfg)
}
IOInit(IOGetByTag(tag), OWNER_MOTOR, 0);
#ifdef STM32F7
#if defined(STM32F7) || defined(STM32H7)
IOConfigGPIOAF(IOGetByTag(tag), cfg, timhw->alternateFunction);
#else
IOConfigGPIO(IOGetByTag(tag), cfg);
@ -194,7 +193,7 @@ static void escSerialInputPortConfig(const timerHardware_t *timerHardwarePtr)
{
escSerialGPIOConfig(timerHardwarePtr, IOCFG_AF_PP_UP);
timerChClearCCFlag(timerHardwarePtr);
timerChITConfig(timerHardwarePtr,ENABLE);
timerChITConfig(timerHardwarePtr, ENABLE);
}
static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
@ -211,7 +210,7 @@ static bool isEscSerialTransmitBufferEmpty(const serialPort_t *instance)
static void escSerialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
{
escSerialGPIOConfig(timerHardwarePtr, IOCFG_OUT_PP);
timerChITConfig(timerHardwarePtr,DISABLE);
timerChITConfig(timerHardwarePtr, DISABLE);
}
static void processTxStateBL(escSerial_t *escSerial)
@ -346,7 +345,7 @@ static void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture
processRxStateBL(escSerial);
}
static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, uint32_t baud)
static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t portIndex, uint32_t baud)
{
uint32_t clock = SystemCoreClock/2;
uint32_t timerPeriod;
@ -363,9 +362,10 @@ static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
}
} while (isTimerPeriodTooLarge(timerPeriod));
timerConfigure(timerHardwarePtr, timerPeriod, clock);
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerBL);
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
timerReconfigureTimeBase(timerHardwarePtr->tim, timerPeriod, clock);
timerChCCHandlerInit(&escSerialPorts[portIndex].timerCb, onSerialTimerBL);
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[portIndex].timerCb, NULL);
timerStart(timerHardwarePtr->tim);
}
static void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
@ -421,10 +421,11 @@ static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
{
// start bit is usually a FALLING signal
TIM_DeInit(timerHardwarePtr->tim);
timerConfigure(timerHardwarePtr, 0xFFFF, SystemCoreClock / 2);
timerReconfigureTimeBase(timerHardwarePtr->tim, 0xFFFF, SystemCoreClock / 2);
timerChConfigIC(timerHardwarePtr, (options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
timerStart(timerHardwarePtr->tim);
}
#ifdef USE_ESCSERIAL_SIMONK
@ -545,9 +546,10 @@ static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint
{
uint32_t timerPeriod = 34;
TIM_DeInit(timerHardwarePtr->tim);
timerConfigure(timerHardwarePtr, timerPeriod, MHZ_TO_HZ(1));
timerReconfigureTimeBase(timerHardwarePtr->tim, timerPeriod, MHZ_TO_HZ(1));
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerEsc);
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
timerStart(timerHardwarePtr->tim);
}
static void extractAndStoreRxByteEsc(escSerial_t *escSerial)
@ -634,10 +636,11 @@ static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint
{
// start bit is usually a FALLING signal
TIM_DeInit(timerHardwarePtr->tim);
timerConfigure(timerHardwarePtr, 0xFFFF, MHZ_TO_HZ(1));
timerReconfigureTimeBase(timerHardwarePtr->tim, 0xFFFF, MHZ_TO_HZ(1));
timerChConfigIC(timerHardwarePtr, ICPOLARITY_FALLING, 0);
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
timerStart(timerHardwarePtr->tim);
}
#endif
@ -678,6 +681,9 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
#ifdef USE_HAL_DRIVER
escSerial->rxTimerHandle = timerFindTimerHandle(escSerial->rxTimerHardware->tim);
#endif
// Workaround to ensure that the timerHandle is configured before use, timer will be reconfigured to a different frequency below
// this prevents a null-pointer dereference in __HAL_TIM_CLEAR_FLAG called by timerChClearCCFlag and similar accesses of timerHandle without the Instance being configured first.
timerConfigure(escSerial->rxTimerHardware, 0xffff, 1);
}
escSerial->mode = mode;
@ -690,6 +696,10 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
escSerial->txTimerHandle = timerFindTimerHandle(escSerial->txTimerHardware->tim);
#endif
// Workaround to ensure that the timerHandle is configured before use, timer will be reconfigured to a different frequency below
// this prevents a null-pointer dereference in __HAL_TIM_CLEAR_FLAG called by timerChClearCCFlag and similar accesses of timerHandle without the Instance being configured first.
timerConfigure(escSerial->txTimerHardware, 0xffff, 1);
escSerial->port.vTable = escSerialVTable;
escSerial->port.baudRate = baud;
escSerial->port.mode = MODE_RXTX;
@ -941,9 +951,7 @@ bool escEnablePassthrough(serialPort_t *escPassthroughPort, const motorDevConfig
uint8_t motor_output = escIndex;
LED0_OFF;
LED1_OFF;
//StopPwmAllMotors();
// XXX Review effect of motor refactor
//pwmDisableMotors();
motorDisable();
passPort = escPassthroughPort;