Skip to content

Commit 5dbf3d0

Browse files
committed
Update stm32_mcu.cpp
1 parent d8d6158 commit 5dbf3d0

File tree

1 file changed

+109
-57
lines changed

1 file changed

+109
-57
lines changed

src/drivers/hardware_specific/stm32/stm32_mcu.cpp

Lines changed: 109 additions & 57 deletions
Original file line numberDiff line numberDiff line change
@@ -658,65 +658,117 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
658658

659659

660660

661-
// function setting the high pwm frequency to the supplied pins
662-
// - Stepper motor - 8PWM setting
663-
// - hardware specific
664-
void* _configure8PWM(long pwm_frequency, float dead_zone, const int pin1A, const int pin1B, const int pin2A, const int pin2B,
665-
const int pin3A, const int pin3B, const int pin4A, const int pin4B)
666-
{
667-
if (numTimerPinsUsed+8 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
668-
SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
669-
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
670-
}
671-
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
672-
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
673-
// center-aligned frequency is uses two periods
674-
pwm_frequency *=2;
675661

676-
// find configuration
677-
int pins[8] = { pin1A, pin1B, pin2A, pin2B, pin3A, pin3B, pin4A, pin4B };
678-
PinMap* pinTimers[8] = { NP, NP, NP, NP, NP, NP, NP, NP };
679-
int score = findBestTimerCombination(8, pins, pinTimers);
662+
#include "stm32g4xx_hal.h"
663+
#include "stm32g4xx_hal_gpio.h"
664+
#include "stm32g4xx_hal_tim.h"
665+
#include "stm32g4xx_hal_tim_ex.h"
680666

681-
STM32DriverParams* params;
682-
// configure accordingly
683-
if (score<0)
684-
params = (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
685-
else if (score<10) // hardware pwm
686-
params = _initHardware8PWMInterface(pwm_frequency, dead_zone, pinTimers[0], pinTimers[1], pinTimers[2], pinTimers[3], pinTimers[4], pinTimers[5], pinTimers[6], pinTimers[7]);
687-
else { // software pwm
688-
HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinTimers[0]);
689-
HardwareTimer* HT2 = _initPinPWMLow(pwm_frequency, pinTimers[1]);
690-
HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency, pinTimers[2]);
691-
HardwareTimer* HT4 = _initPinPWMLow(pwm_frequency, pinTimers[3]);
692-
HardwareTimer* HT5 = _initPinPWMHigh(pwm_frequency, pinTimers[4]);
693-
HardwareTimer* HT6 = _initPinPWMLow(pwm_frequency, pinTimers[5]);
694-
HardwareTimer* HT7 = _initPinPWMHigh(pwm_frequency, pinTimers[6]);
695-
HardwareTimer* HT8 = _initPinPWMLow(pwm_frequency, pinTimers[7]);
696-
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
697-
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
698-
uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
699-
uint32_t channel4 = STM_PIN_CHANNEL(pinTimers[3]->function);
700-
uint32_t channel5 = STM_PIN_CHANNEL(pinTimers[4]->function);
701-
uint32_t channel6 = STM_PIN_CHANNEL(pinTimers[5]->function);
702-
uint32_t channel7 = STM_PIN_CHANNEL(pinTimers[6]->function);
703-
uint32_t channel8 = STM_PIN_CHANNEL(pinTimers[7]->function);
704-
params = new STM32DriverParams {
705-
706-
.timers = { HT1, HT2, HT3, HT4, HT5, HT6, HT7, HT8},
707-
.channels = { channel1, channel2, channel3, channel4, channel5, channel6, channel7, channel8 },
708-
.pwm_frequency = pwm_frequency,
709-
.dead_zone = dead_zone,
710-
.interface_type = _SOFTWARE_8PWM
711-
};
712-
}
713-
if (score>=0) {
714-
for (int i=0; i<8; i++)
715-
timerPinsUsed[numTimerPinsUsed++] = pinTimers[i];
716-
_alignTimersNew();
717-
}
718-
return params; // success
719-
}
667+
TIM_HandleTypeDef htim1;
668+
TIM_HandleTypeDef htim8;
669+
670+
void configure8PWM(void)
671+
{
672+
673+
HAL_Init();
674+
675+
GPIO_InitTypeDef GPIO_InitStruct = {0};
676+
677+
// Enable clock for TIM1 and TIM8
678+
__HAL_RCC_TIM1_CLK_ENABLE();
679+
__HAL_RCC_TIM8_CLK_ENABLE();
680+
681+
// Configure TIM1 pins
682+
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_7 | GPIO_PIN_9 | GPIO_PIN_6 | GPIO_PIN_0 | GPIO_PIN_1;
683+
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
684+
GPIO_InitStruct.Pull = GPIO_NOPULL;
685+
GPIO_InitStruct.Alternate = GPIO_AF6_TIM1;
686+
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
687+
GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1;
688+
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
689+
690+
// Configure TIM8 pins
691+
GPIO_InitStruct.Pin = GPIO_PIN_6 | GPIO_PIN_7;
692+
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
693+
GPIO_InitStruct.Pull = GPIO_NOPULL;
694+
GPIO_InitStruct.Alternate = GPIO_AF3_TIM8;
695+
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
696+
697+
// Set TIM1 and TIM8 dead time values to 50 ns
698+
TIM_MasterConfigTypeDef sMasterConfig = {0};
699+
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
700+
htim1.Instance = TIM1;
701+
htim1.Init.Prescaler = 0;
702+
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
703+
htim1.Init.Period = 100;
704+
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
705+
htim1.Init.RepetitionCounter= 0;
706+
HAL_TIM_PWM_Init(&htim1);
707+
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
708+
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
709+
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
710+
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
711+
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
712+
sBreakDeadTimeConfig.DeadTime = 50;
713+
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
714+
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
715+
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
716+
HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig);
717+
HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig);
718+
719+
// Continue with configuring TIM8
720+
htim8.Instance = TIM8;
721+
htim8.Init.Prescaler = 0;
722+
htim8.Init.CounterMode = TIM_COUNTERMODE_UP;
723+
htim8.Init.Period = 100;
724+
htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
725+
htim8.Init.RepetitionCounter= 0;
726+
HAL_TIM_PWM_Init(&htim8);
727+
HAL_TIMEx_ConfigBreakDeadTime(&htim8, &sBreakDeadTimeConfig);
728+
HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig);
729+
730+
// Configure TIM1 and TIM8 PWM channels
731+
TIM_OC_InitTypeDef sConfigOC = {0};
732+
sConfigOC.OCMode = TIM_OCMODE_PWM1;
733+
sConfigOC.Pulse = 0;
734+
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
735+
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
736+
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
737+
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
738+
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
739+
740+
// TIM1 Channel 1
741+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1);
742+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1);
743+
744+
// TIM1 Channel 2
745+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2);
746+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2);
747+
748+
// TIM1 Channel 3
749+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3);
750+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3);
751+
752+
// TIM1 Channel 4
753+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_4);
754+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_4);
755+
756+
// TIM1 Channel 5
757+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_5);
758+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_5);
759+
760+
// TIM1 Channel 6
761+
HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_6);
762+
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_6);
763+
764+
// TIM8 Channel 1
765+
HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_1);
766+
HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_1);
767+
768+
// TIM8 Channel 2
769+
HAL_TIM_PWM_ConfigChannel(&htim8, &sConfigOC, TIM_CHANNEL_2);
770+
HAL_TIM_PWM_Start(&htim8, TIM_CHANNEL_2);
771+
}
720772

721773

722774

0 commit comments

Comments
 (0)