Merge pull request #3003 from sambas/betaflightF7
Fix more HAL init issues
This commit is contained in:
commit
849c8e5449
|
@ -234,7 +234,6 @@ void i2cInit(I2CDevice device)
|
||||||
IOConfigGPIO(sda, IOCFG_AF_OD);
|
IOConfigGPIO(sda, IOCFG_AF_OD);
|
||||||
#endif
|
#endif
|
||||||
// Init I2C peripheral
|
// Init I2C peripheral
|
||||||
HAL_I2C_DeInit(&i2cHandle[device].Handle);
|
|
||||||
|
|
||||||
i2cHandle[device].Handle.Instance = i2cHardwareMap[device].dev;
|
i2cHandle[device].Handle.Instance = i2cHardwareMap[device].dev;
|
||||||
/// TODO: HAL check if I2C timing is correct
|
/// TODO: HAL check if I2C timing is correct
|
||||||
|
|
|
@ -138,32 +138,25 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
const IO_t motorIO = IOGetByTag(timerHardware->tag);
|
const IO_t motorIO = IOGetByTag(timerHardware->tag);
|
||||||
|
|
||||||
const uint8_t timerIndex = getTimerIndex(timer);
|
const uint8_t timerIndex = getTimerIndex(timer);
|
||||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
|
||||||
|
|
||||||
IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
|
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
|
||||||
|
|
||||||
__DMA1_CLK_ENABLE();
|
__DMA1_CLK_ENABLE();
|
||||||
|
|
||||||
if (configureTimer) {
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
|
||||||
|
|
||||||
motor->TimHandle.Instance = timerHardware->tim;
|
motor->TimHandle.Instance = timerHardware->tim;
|
||||||
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;;
|
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / getDshotHz(pwmProtocolType)) - 1;;
|
||||||
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
||||||
motor->TimHandle.Init.RepetitionCounter = 0;
|
motor->TimHandle.Init.RepetitionCounter = 0;
|
||||||
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
|
motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||||
{
|
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
|
||||||
/* Initialization Error */
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
{
|
||||||
motor->TimHandle = dmaMotors[timerIndex].TimHandle;
|
/* Initialization Error */
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
|
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
|
||||||
|
|
|
@ -267,6 +267,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
||||||
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
|
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 || tim == TIM9)
|
||||||
{
|
{
|
||||||
TIM_ClockConfigTypeDef sClockSourceConfig;
|
TIM_ClockConfigTypeDef sClockSourceConfig;
|
||||||
|
memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig));
|
||||||
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
|
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
|
||||||
if (HAL_TIM_ConfigClockSource(&timerHandle[timerIndex].Handle, &sClockSourceConfig) != HAL_OK)
|
if (HAL_TIM_ConfigClockSource(&timerHandle[timerIndex].Handle, &sClockSourceConfig) != HAL_OK)
|
||||||
{
|
{
|
||||||
|
@ -276,7 +277,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
||||||
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
|
if(tim == TIM1 || tim == TIM2 || tim == TIM3 || tim == TIM4 || tim == TIM5 || tim == TIM8 )
|
||||||
{
|
{
|
||||||
TIM_MasterConfigTypeDef sMasterConfig;
|
TIM_MasterConfigTypeDef sMasterConfig;
|
||||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
memset(&sMasterConfig, 0, sizeof(sMasterConfig));
|
||||||
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||||
if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle[timerIndex].Handle, &sMasterConfig) != HAL_OK)
|
if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle[timerIndex].Handle, &sMasterConfig) != HAL_OK)
|
||||||
{
|
{
|
||||||
|
@ -908,4 +909,4 @@ uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
||||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
||||||
{
|
{
|
||||||
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
|
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
|
||||||
}
|
}
|
||||||
|
|
|
@ -109,6 +109,7 @@
|
||||||
#define SPI4_MOSI_PIN PE14
|
#define SPI4_MOSI_PIN PE14
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
|
#define SDCARD_DETECT_INVERTED
|
||||||
#define SDCARD_DETECT_PIN PD3
|
#define SDCARD_DETECT_PIN PD3
|
||||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line3
|
#define SDCARD_DETECT_EXTI_LINE EXTI_Line3
|
||||||
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource3
|
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource3
|
||||||
|
|
Loading…
Reference in New Issue