diff --git a/.github/workflows/arduino.yml b/.github/workflows/arduino.yml
index cadd8ccc..9a4bc6c4 100644
--- a/.github/workflows/arduino.yml
+++ b/.github/workflows/arduino.yml
@@ -25,7 +25,7 @@ jobs:
- arduino-boards-fqbn: arduino:avr:uno # arudino uno - compiling almost all examples
sketch-names: '**.ino'
required-libraries: PciManager
- sketches-exclude: teensy4_current_control_low_side, full_control_serial, angle_control, bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm, osc_esp32_fullcontrol, nano33IoT_velocity_control, smartstepper_control,esp32_current_control_low_side, stm32_spi_alt_example, esp32_spi_alt_example, B_G431B_ESC1, odrive_example_spi, odrive_example_encoder, single_full_control_example, double_full_control_example, stm32_current_control_low_side, open_loop_velocity_6pwm
+ sketches-exclude: measure_inductance_and_resistance, teensy4_current_control_low_side, full_control_serial, angle_control, bluepill_position_control, esp32_position_control, esp32_i2c_dual_bus_example, stm32_i2c_dual_bus_example, magnetic_sensor_spi_alt_example, osc_esp32_3pwm, osc_esp32_fullcontrol, nano33IoT_velocity_control, smartstepper_control,esp32_current_control_low_side, stm32_spi_alt_example, esp32_spi_alt_example, B_G431B_ESC1, odrive_example_spi, odrive_example_encoder, single_full_control_example, double_full_control_example, stm32_current_control_low_side, open_loop_velocity_6pwm
- arduino-boards-fqbn: arduino:sam:arduino_due_x # arduino due - one full example
sketch-names: single_full_control_example.ino
diff --git a/.github/workflows/esp32.yml b/.github/workflows/esp32.yml
index db551b41..2f5accd5 100644
--- a/.github/workflows/esp32.yml
+++ b/.github/workflows/esp32.yml
@@ -33,7 +33,7 @@ jobs:
- arduino-boards-fqbn: esp32:esp32:esp32c3 # esp32c3
platform-url: https://espressif.github.io/arduino-esp32/package_esp32_index.json
- sketch-names: esp32_position_control.ino, esp32_i2c_dual_bus_example.ino, stepper_driver_2pwm_standalone.ino, stepper_driver_4pwm_standalone.ino
+ sketch-names: esp32_position_control.ino, stepper_driver_2pwm_standalone.ino, stepper_driver_4pwm_standalone.ino
- arduino-boards-fqbn: esp32:esp32:esp32doit-devkit-v1 # esp32
platform-url: https://espressif.github.io/arduino-esp32/package_esp32_index.json
diff --git a/README.md b/README.md
index 4fbb7517..3dcc7385 100644
--- a/README.md
+++ b/README.md
@@ -29,27 +29,13 @@ Therefore this is an attempt to:
- For official driver boards see [SimpleFOCBoards](https://docs.simplefoc.com/boards)
- Many many more boards developed by the community members, see [SimpleFOCCommunity](https://community.simplefoc.com/)
-> NEXT RELEASE 📢 : SimpleFOClibrary v2.3.4
-> - ESP32 MCUs extended support [#414](https://github.com/simplefoc/Arduino-FOC/pull/414)
-> - Transition to the arduino-esp32 version v3.x (ESP-IDF v5.x) [#387](https://github.com/espressif/arduino-esp32/releases)
-> - New support for MCPWM driver
-> - New support for LEDC drivers - center-aligned PWM and 6PWM available
-> - Rewritten and simplified the fast ADC driver code (`adcRead`) - for low-side and inline current sensing.
-> - Stepper motors current sensing support [#421](https://github.com/simplefoc/Arduino-FOC/pull/421)
-> - Support for current sensing (low-side and inline) - [see in docs](https://docs.simplefoc.com/current_sense)
-> - Support for true FOC control - `foc_current` torque control - [see in docs](https://docs.simplefoc.com/motion_control)
-> - New current sense alignment procedure [#422](https://github.com/simplefoc/Arduino-FOC/pull/422) - [see in docs](https://docs.simplefoc.com/current_sense_align)
-> - Support for steppers
-> - Much more robust and reliable
-> - More verbose and informative
-> - Support for HallSensors without interrupts [#424](https://docs.simplefoc.com/https://github.com/simplefoc/Arduino-FOC/pull/424) - [see in docs](hall_sensors)
-> - Docs
-> - A short guide to debugging of common issues
-> - A short guide to the units in the library - [see in docs](https://docs.simplefoc.com/library_units)
-> - See the complete list of bugfixes and new features of v2.3.4 [fixes and PRs](https://github.com/simplefoc/Arduino-FOC/milestone/11)
-
-
-## Arduino *SimpleFOClibrary* v2.3.4
+> NEXT RELEASE 📢 : SimpleFOClibrary v2.3.5
+> - Motor characterization code thanks to @mcells
+> - Bugfix for ESP32 C6 thanks to @kondor1622
+> - See the complete list of bugfixes and new features of v2.3.5 [fixes and PRs](https://github.com/simplefoc/Arduino-FOC/milestone/12)
+
+
+## Arduino *SimpleFOClibrary* v2.3.5
diff --git a/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino b/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino
index 0516ede1..a25e1c04 100644
--- a/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino
+++ b/examples/utils/sensor_test/magnetic_sensors/magnetic_sensor_i2c/magnetic_sensor_i2c_dual_bus_examples/esp32_i2c_dual_bus_example/esp32_i2c_dual_bus_example.ino
@@ -1,4 +1,5 @@
#include
+#include
/** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus
* This example shows how a second i2c bus can be used to communicate with a second sensor.
@@ -7,6 +8,8 @@
MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C);
MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
+// example of esp32 defining 2nd bus, if not already defined
+//TwoWire Wire1(1);
void setup() {
diff --git a/library.properties b/library.properties
index 5daa49d9..354a2118 100644
--- a/library.properties
+++ b/library.properties
@@ -1,5 +1,5 @@
name=Simple FOC
-version=2.3.4
+version=2.3.5
author=Simplefoc
maintainer=Simplefoc
sentence=A library demistifying FOC for BLDC motors
diff --git a/src/BLDCMotor.cpp b/src/BLDCMotor.cpp
index 501a8bc9..5ad8a93f 100644
--- a/src/BLDCMotor.cpp
+++ b/src/BLDCMotor.cpp
@@ -290,9 +290,7 @@ int BLDCMotor::alignSensor() {
zero_electric_angle = electricalAngle();
//zero_electric_angle = _normalizeAngle(_electricalAngle(sensor_direction*sensor->getAngle(), pole_pairs));
_delay(20);
- if(monitor_port){
- SIMPLEFOC_DEBUG("MOT: Zero elec. angle: ", zero_electric_angle);
- }
+ SIMPLEFOC_DEBUG("MOT: Zero elec. angle: ", zero_electric_angle);
// stop everything
setPhaseVoltage(0, 0, 0);
_delay(200);
diff --git a/src/common/base_classes/CurrentSense.h b/src/common/base_classes/CurrentSense.h
index d3f7f8ed..f3d15b31 100644
--- a/src/common/base_classes/CurrentSense.h
+++ b/src/common/base_classes/CurrentSense.h
@@ -34,7 +34,7 @@ class CurrentSense{
FOCDriver* driver = nullptr; //!< driver link
bool initialized = false; // true if current sense was successfully initialized
void* params = 0; //!< pointer to hardware specific parameters of current sensing
- DriverType driver_type = DriverType::Unknown; //!< driver type (BLDC or Stepper)
+ DriverType driver_type = DriverType::UnknownDriver; //!< driver type (BLDC or Stepper)
// ADC measurement gain for each phase
diff --git a/src/common/base_classes/FOCDriver.h b/src/common/base_classes/FOCDriver.h
index 944251a4..15ba1c47 100644
--- a/src/common/base_classes/FOCDriver.h
+++ b/src/common/base_classes/FOCDriver.h
@@ -13,7 +13,7 @@ enum PhaseState : uint8_t {
enum DriverType{
- Unknown=0,
+ UnknownDriver=0,
BLDC=1,
Stepper=2
};
diff --git a/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp b/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp
index 46cb20be..697a2f0f 100644
--- a/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/b_g431/b_g431_mcu.cpp
@@ -132,7 +132,7 @@ void* _configureADCLowSide(const void* driver_params, const int pinA,const int p
Stm32CurrentSenseParams* params = new Stm32CurrentSenseParams {
.pins = { pinA, pinB, pinC },
.adc_voltage_conv = (_ADC_VOLTAGE) / (_ADC_RESOLUTION),
- .timer_handle = (HardwareTimer *)(HardwareTimer_Handle[get_timer_index(TIM1)]->__this)
+ .timer_handle = ((STM32DriverParams*)driver_params)->timers_handle[0],
};
return params;
@@ -153,21 +153,21 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
Stm32CurrentSenseParams* cs_params = (Stm32CurrentSenseParams*)_cs_params;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger for DMA transfer aligns with the pwm peaks instead of throughs.
// only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
diff --git a/src/current_sense/hardware_specific/stm32/stm32_mcu.h b/src/current_sense/hardware_specific/stm32/stm32_mcu.h
index 6e238170..055f20db 100644
--- a/src/current_sense/hardware_specific/stm32/stm32_mcu.h
+++ b/src/current_sense/hardware_specific/stm32/stm32_mcu.h
@@ -14,7 +14,7 @@ typedef struct Stm32CurrentSenseParams {
int pins[3] = {(int)NOT_SET};
float adc_voltage_conv;
ADC_HandleTypeDef* adc_handle = NP;
- HardwareTimer* timer_handle = NP;
+ TIM_HandleTypeDef* timer_handle = NP;
} Stm32CurrentSenseParams;
#endif
diff --git a/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp b/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp
index d3bea81e..880fb3d6 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_hal.cpp
@@ -7,19 +7,19 @@
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_adc_ex.h#L215
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
#endif
#ifdef TIM5 // if defined timer 5
- else if(timer->getHandle()->Instance == TIM5)
+ else if(timer->Instance == TIM5)
return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
#endif
else
@@ -28,11 +28,11 @@ uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_adc_ex.h#L215
-uint32_t _timerToRegularTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM3)
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM3)
return ADC_EXTERNALTRIGCONV_T3_TRGO;
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGCONV_T8_TRGO;
#endif
else
@@ -82,8 +82,8 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// automating TRGO flag finding - hardware specific
uint8_t tim_num = 0;
- while(driver_params->timers[tim_num] != NP && tim_num < 6){
- uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ while(driver_params->timers_handle[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers_handle[tim_num++]);
if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
// if the code comes here, it has found the timer available
@@ -91,7 +91,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
sConfigInjected.ExternalTrigInjecConv = trigger_flag;
// this will be the timer with which the ADC will sync
- cs_params->timer_handle = driver_params->timers[tim_num-1];
+ cs_params->timer_handle = driver_params->timers_handle[tim_num-1];
// done
break;
}
@@ -105,7 +105,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// display which timer is being used
#ifdef SIMPLEFOC_STM32_DEBUG
// it would be better to use the getTimerNumber from driver
- SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->Instance) + 1);
#endif
// first channel
diff --git a/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp b/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp
index 49f2f3d5..7d31f966 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f1/stm32f1_mcu.cpp
@@ -56,17 +56,17 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger
// - for DMA transfer aligns with the pwm peaks instead of throughs.
// - for interrupt based ADC transfer
// - only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
// remember that this timer has repetition counter - no need to downasmple
needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
}else{
@@ -79,7 +79,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// Start the adc calibration
HAL_ADCEx_Calibration_Start(cs_params->adc_handle);
@@ -96,7 +96,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
diff --git a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp
index bd0df4b6..5320cc3e 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_hal.cpp
@@ -76,8 +76,8 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// automating TRGO flag finding - hardware specific
uint8_t tim_num = 0;
- while(driver_params->timers[tim_num] != NP && tim_num < 6){
- uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ while(driver_params->timers_handle[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers_handle[tim_num++]);
if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
// if the code comes here, it has found the timer available
@@ -85,7 +85,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
sConfigInjected.ExternalTrigInjecConv = trigger_flag;
// this will be the timer with which the ADC will sync
- cs_params->timer_handle = driver_params->timers[tim_num-1];
+ cs_params->timer_handle = driver_params->timers_handle[tim_num-1];
// done
break;
}
@@ -99,7 +99,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// display which timer is being used
#ifdef SIMPLEFOC_STM32_DEBUG
// it would be better to use the getTimerNumber from driver
- SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->Instance) + 1);
#endif
diff --git a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp
index 6b597d4e..d3c7bd7f 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_mcu.cpp
@@ -48,17 +48,17 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger
// - for DMA transfer aligns with the pwm peaks instead of throughs.
// - for interrupt based ADC transfer
// - only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
// remember that this timer has repetition counter - no need to downasmple
needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
}else{
@@ -71,7 +71,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// start the adc
if (use_adc_interrupt){
@@ -85,7 +85,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
diff --git a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp
index 20793d8c..8a636c84 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.cpp
@@ -133,19 +133,19 @@ uint32_t _getADCChannel(PinName pin)
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
#endif
#ifdef TIM5 // if defined timer 5
- else if(timer->getHandle()->Instance == TIM5)
+ else if(timer->Instance == TIM5)
return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
#endif
else
@@ -154,15 +154,15 @@ uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
-uint32_t _timerToRegularTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM2)
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGCONV_T2_TRGO;
#ifdef TIM3 // if defined timer 3
- else if(timer->getHandle()->Instance == TIM3)
+ else if(timer->Instance == TIM3)
return ADC_EXTERNALTRIGCONV_T3_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGCONV_T8_TRGO;
#endif
else
diff --git a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h
index b4549bad..05303965 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h
+++ b/src/current_sense/hardware_specific/stm32/stm32f4/stm32f4_utils.h
@@ -19,11 +19,11 @@ uint32_t _getADCChannel(PinName pin);
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer);
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
-uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer);
// function returning index of the ADC instance
int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
diff --git a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp
index d4cffec6..04575397 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_hal.cpp
@@ -77,8 +77,8 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// automating TRGO flag finding - hardware specific
uint8_t tim_num = 0;
for (size_t i=0; i<6; i++) {
- HardwareTimer *timer_to_check = driver_params->timers[tim_num++];
- TIM_TypeDef *instance_to_check = timer_to_check->getHandle()->Instance;
+ TIM_HandleTypeDef *timer_to_check = driver_params->timers_handle[tim_num++];
+ TIM_TypeDef *instance_to_check = timer_to_check->Instance;
// bool TRGO_already_configured = instance_to_check->CR2 & LL_TIM_TRGO_UPDATE;
// if(TRGO_already_configured) continue;
@@ -110,7 +110,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// display which timer is being used
#ifdef SIMPLEFOC_STM32_DEBUG
// it would be better to use the getTimerNumber from driver
- SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->getHandle()->Instance) + 1);
+ SIMPLEFOC_DEBUG("STM32-CS: injected trigger for timer index: ", get_timer_index(cs_params->timer_handle->Instance) + 1);
#endif
diff --git a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp
index f5ca70f3..e4b9c850 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_mcu.cpp
@@ -42,23 +42,23 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger
// - for DMA transfer aligns with the pwm peaks instead of throughs.
// - for interrupt based ADC transfer
// - only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
// remember that this timer has repetition counter - no need to downasmple
needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// start the adc
#ifdef SIMPLEFOC_STM32_ADC_INTERRUPT
@@ -68,7 +68,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
#endif
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
diff --git a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp
index d5f8c6b2..2321c5da 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.cpp
@@ -163,28 +163,28 @@ ADC_EXTERNALTRIGINJECCONV_T6_TRGO
*/
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer){
- if(timer->getHandle()->Instance == TIM1)
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGINJECCONV_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGINJECCONV_T2_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGINJECCONV_T4_TRGO;
#endif
#ifdef TIM5 // if defined timer 5
- else if(timer->getHandle()->Instance == TIM5)
+ else if(timer->Instance == TIM5)
return ADC_EXTERNALTRIGINJECCONV_T5_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIGINJECCONV_T6_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGINJECCONV_T8_TRGO;
#endif
else
@@ -204,27 +204,27 @@ ADC_EXTERNALTRIGCONV_T6_TRGO
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
-uint32_t _timerToRegularTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGCONV_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGCONV_T2_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGCONV_T4_TRGO;
#endif
#ifdef TIM5 // if defined timer 5
- else if(timer->getHandle()->Instance == TIM5)
+ else if(timer->Instance == TIM5)
return ADC_EXTERNALTRIGCONV_T5_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIGCONV_T6_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGCONV_T8_TRGO;
#endif
else
diff --git a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h
index 017ff464..47465e5d 100644
--- a/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h
+++ b/src/current_sense/hardware_specific/stm32/stm32f7/stm32f7_utils.h
@@ -17,11 +17,11 @@ uint32_t _getADCChannel(PinName pin);
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h#L179
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer);
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h#L331
-uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer);
// function returning index of the ADC instance
int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
diff --git a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp
index fd1090ae..84a9560c 100644
--- a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_hal.cpp
@@ -126,8 +126,8 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// automating TRGO flag finding - hardware specific
uint8_t tim_num = 0;
- while(driver_params->timers[tim_num] != NP && tim_num < 6){
- uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ while(driver_params->timers_handle[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers_handle[tim_num++]);
if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
// if the code comes here, it has found the timer available
@@ -135,7 +135,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
sConfigInjected.ExternalTrigInjecConv = trigger_flag;
// this will be the timer with which the ADC will sync
- cs_params->timer_handle = driver_params->timers[tim_num-1];
+ cs_params->timer_handle = driver_params->timers_handle[tim_num-1];
// done
break;
}
diff --git a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp
index 9c73f6d7..9be98860 100644
--- a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_mcu.cpp
@@ -50,17 +50,17 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger
// - for DMA transfer aligns with the pwm peaks instead of throughs.
// - for interrupt based ADC transfer
// - only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
// remember that this timer has repetition counter - no need to downasmple
needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
}else{
@@ -74,7 +74,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// Start the adc calibration
HAL_ADCEx_Calibration_Start(cs_params->adc_handle,ADC_SINGLE_ENDED);
@@ -122,7 +122,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
diff --git a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp
index 89a9bc34..2f9e7e4d 100644
--- a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.cpp
@@ -133,39 +133,39 @@ uint32_t _getADCChannel(PinName pin)
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGINJEC_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGINJEC_T2_TRGO;
#endif
#ifdef TIM3 // if defined timer 3
- else if(timer->getHandle()->Instance == TIM3)
+ else if(timer->Instance == TIM3)
return ADC_EXTERNALTRIGINJEC_T3_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGINJEC_T4_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIGINJEC_T6_TRGO;
#endif
#ifdef TIM7 // if defined timer 7
- else if(timer->getHandle()->Instance == TIM7)
+ else if(timer->Instance == TIM7)
return ADC_EXTERNALTRIGINJEC_T7_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGINJEC_T8_TRGO;
#endif
#ifdef TIM15 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM15)
+ else if(timer->Instance == TIM15)
return ADC_EXTERNALTRIGINJEC_T15_TRGO;
#endif
#ifdef TIM20 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM20)
+ else if(timer->Instance == TIM20)
return ADC_EXTERNALTRIGINJEC_T20_TRGO;
#endif
else
@@ -174,39 +174,39 @@ uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
-uint32_t _timerToRegularTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIG_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIG_T2_TRGO;
#endif
#ifdef TIM3 // if defined timer 3
- else if(timer->getHandle()->Instance == TIM3)
+ else if(timer->Instance == TIM3)
return ADC_EXTERNALTRIG_T3_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIG_T4_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIG_T6_TRGO;
#endif
#ifdef TIM7 // if defined timer 7
- else if(timer->getHandle()->Instance == TIM7)
+ else if(timer->Instance == TIM7)
return ADC_EXTERNALTRIG_T7_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIG_T7_TRGO;
#endif
#ifdef TIM15 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM15)
+ else if(timer->Instance == TIM15)
return ADC_EXTERNALTRIG_T15_TRGO;
#endif
#ifdef TIM20 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM20)
+ else if(timer->Instance == TIM20)
return ADC_EXTERNALTRIG_T20_TRGO;
#endif
else
diff --git a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h
index fa857bd0..5a3aca29 100644
--- a/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h
+++ b/src/current_sense/hardware_specific/stm32/stm32g4/stm32g4_utils.h
@@ -19,11 +19,11 @@ uint32_t _getADCChannel(PinName pin);
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer);
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
-uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer);
// function returning index of the ADC instance
int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
diff --git a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp
index 67a0473b..8f7889c4 100644
--- a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_hal.cpp
@@ -125,8 +125,8 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
// automating TRGO flag finding - hardware specific
uint8_t tim_num = 0;
- while(driver_params->timers[tim_num] != NP && tim_num < 6){
- uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers[tim_num++]);
+ while(driver_params->timers_handle[tim_num] != NP && tim_num < 6){
+ uint32_t trigger_flag = _timerToInjectedTRGO(driver_params->timers_handle[tim_num++]);
if(trigger_flag == _TRGO_NOT_AVAILABLE) continue; // timer does not have valid trgo for injected channels
// if the code comes here, it has found the timer available
@@ -134,7 +134,7 @@ int _adc_init(Stm32CurrentSenseParams* cs_params, const STM32DriverParams* drive
sConfigInjected.ExternalTrigInjecConv = trigger_flag;
// this will be the timer with which the ADC will sync
- cs_params->timer_handle = driver_params->timers[tim_num-1];
+ cs_params->timer_handle = driver_params->timers_handle[tim_num-1];
// done
break;
}
diff --git a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp
index 5de6432a..ed55b482 100644
--- a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_mcu.cpp
@@ -49,17 +49,17 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
if (cs_params->timer_handle == NULL) return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
// stop all the timers for the driver
- _stopTimers(driver_params->timers, 6);
+ stm32_pause(driver_params);
// if timer has repetition counter - it will downsample using it
// and it does not need the software downsample
- if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->getHandle()->Instance) ){
+ if( IS_TIM_REPETITION_COUNTER_INSTANCE(cs_params->timer_handle->Instance) ){
// adjust the initial timer state such that the trigger
// - for DMA transfer aligns with the pwm peaks instead of throughs.
// - for interrupt based ADC transfer
// - only necessary for the timers that have repetition counters
- cs_params->timer_handle->getHandle()->Instance->CR1 |= TIM_CR1_DIR;
- cs_params->timer_handle->getHandle()->Instance->CNT = cs_params->timer_handle->getHandle()->Instance->ARR;
+ cs_params->timer_handle->Instance->CR1 |= TIM_CR1_DIR;
+ cs_params->timer_handle->Instance->CNT = cs_params->timer_handle->Instance->ARR;
// remember that this timer has repetition counter - no need to downasmple
needs_downsample[_adcToIndex(cs_params->adc_handle)] = 0;
}else{
@@ -73,7 +73,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
// set the trigger output event
- LL_TIM_SetTriggerOutput(cs_params->timer_handle->getHandle()->Instance, LL_TIM_TRGO_UPDATE);
+ LL_TIM_SetTriggerOutput(cs_params->timer_handle->Instance, LL_TIM_TRGO_UPDATE);
// Start the adc calibration
HAL_ADCEx_Calibration_Start(cs_params->adc_handle,ADC_SINGLE_ENDED);
@@ -119,7 +119,7 @@ void* _driverSyncLowSide(void* _driver_params, void* _cs_params){
}
// restart all the timers of the driver
- _startTimers(driver_params->timers, 6);
+ stm32_resume(driver_params);
// return the cs parameters
// successfully initialized
// TODO verify if success in future
diff --git a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp
index 376d9d68..f93e63a4 100644
--- a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp
+++ b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.cpp
@@ -133,31 +133,31 @@ uint32_t _getADCChannel(PinName pin)
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/e156c32db24d69cb4818208ccc28894e2f427cfa/system/Drivers/STM32L4xx_HAL_Driver/Inc/stm32l4xx_hal_adc_ex.h#L210
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIGINJEC_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIGINJEC_T2_TRGO;
#endif
#ifdef TIM3 // if defined timer 3
- else if(timer->getHandle()->Instance == TIM3)
+ else if(timer->Instance == TIM3)
return ADC_EXTERNALTRIGINJEC_T3_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIGINJEC_T4_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIGINJEC_T6_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIGINJEC_T8_TRGO;
#endif
#ifdef TIM15 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM15)
+ else if(timer->Instance == TIM15)
return ADC_EXTERNALTRIGINJEC_T15_TRGO;
#endif
else
@@ -166,31 +166,31 @@ uint32_t _timerToInjectedTRGO(HardwareTimer* timer){
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
-uint32_t _timerToRegularTRGO(HardwareTimer* timer){
- if(timer->getHandle()->Instance == TIM1)
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer){
+ if(timer->Instance == TIM1)
return ADC_EXTERNALTRIG_T1_TRGO;
#ifdef TIM2 // if defined timer 2
- else if(timer->getHandle()->Instance == TIM2)
+ else if(timer->Instance == TIM2)
return ADC_EXTERNALTRIG_T2_TRGO;
#endif
#ifdef TIM3 // if defined timer 3
- else if(timer->getHandle()->Instance == TIM3)
+ else if(timer->Instance == TIM3)
return ADC_EXTERNALTRIG_T3_TRGO;
#endif
#ifdef TIM4 // if defined timer 4
- else if(timer->getHandle()->Instance == TIM4)
+ else if(timer->Instance == TIM4)
return ADC_EXTERNALTRIG_T4_TRGO;
#endif
#ifdef TIM6 // if defined timer 6
- else if(timer->getHandle()->Instance == TIM6)
+ else if(timer->Instance == TIM6)
return ADC_EXTERNALTRIG_T6_TRGO;
#endif
#ifdef TIM8 // if defined timer 8
- else if(timer->getHandle()->Instance == TIM8)
+ else if(timer->Instance == TIM8)
return ADC_EXTERNALTRIG_T8_TRGO;
#endif
#ifdef TIM15 // if defined timer 15
- else if(timer->getHandle()->Instance == TIM15)
+ else if(timer->Instance == TIM15)
return ADC_EXTERNALTRIG_T15_TRGO;
#endif
else
diff --git a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h
index ceef9be7..e30bf0ce 100644
--- a/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h
+++ b/src/current_sense/hardware_specific/stm32/stm32l4/stm32l4_utils.h
@@ -19,11 +19,11 @@ uint32_t _getADCChannel(PinName pin);
// timer to injected TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc_ex.h#L217
-uint32_t _timerToInjectedTRGO(HardwareTimer* timer);
+uint32_t _timerToInjectedTRGO(TIM_HandleTypeDef* timer);
// timer to regular TRGO
// https://github.com/stm32duino/Arduino_Core_STM32/blob/6588dee03382e73ed42c4a5e473900ab3b79d6e4/system/Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_adc.h#L519
-uint32_t _timerToRegularTRGO(HardwareTimer* timer);
+uint32_t _timerToRegularTRGO(TIM_HandleTypeDef* timer);
// function returning index of the ADC instance
int _adcToIndex(ADC_HandleTypeDef *AdcHandle);
diff --git a/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp b/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
index a481c6ff..80d936d1 100644
--- a/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
+++ b/src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
@@ -181,7 +181,7 @@ uint8_t _findNextTimer(int group){
*/
int _findBestGroup(int no_pins, long pwm_freq, int* group, int* timer){
// an empty group is always the best option
- for(int i=0; i<2; i++){
+ for(int i=0; iperipheral)) {
+ return true;
+ }
+ for (int i=0; itimers_handle[j] == NULL) break;
+ if (motorsUsed[i]->channels[j] == STM_PIN_CHANNEL(pin->function) && ((TIM_TypeDef*)pin->peripheral) == motorsUsed[i]->timers_handle[j]->Instance)
+ return true;
+ }
+ }
+ return false;
+}
+TIM_HandleTypeDef* stm32_getTimer(PinMap* timer) {
+ for (int i=0; iInstance == (TIM_TypeDef*)timer->peripheral)
+ return timersUsed[i];
+ }
+ return NULL;
+}
+bool stm32_reserveTimer(TIM_TypeDef* timer) {
+ if (numTimersReserved >= SIMPLEFOC_STM32_MAX_TIMERSRESERVED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many timers reserved");
+ return false;
+ }
+ reservedTimers[numTimersReserved++] = timer;
+ return true;
+}
+// function to get a timer handle given the pinmap entry of the pin you want to use
+// after calling this function, the timer is marked as used by SimpleFOC
+TIM_HandleTypeDef* stm32_useTimer(PinMap* timer) {
+ TIM_HandleTypeDef* handle = stm32_getTimer(timer);
+ if (handle != NULL) return handle;
+ if (numTimersUsed >= SIMPLEFOC_STM32_MAX_TIMERSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many timers used");
+ return NULL;
+ }
+ if (stm32_isTimerReserved((TIM_TypeDef*)timer->peripheral)) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: timer reserved");
+ return NULL;
+ }
+ handle = new TIM_HandleTypeDef();
+ handle->Instance = (TIM_TypeDef*)timer->peripheral;
+ handle->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED;
+ handle->Lock = HAL_UNLOCKED;
+ handle->State = HAL_TIM_STATE_RESET;
+ handle->hdma[0] = NULL;
+ handle->hdma[1] = NULL;
+ handle->hdma[2] = NULL;
+ handle->hdma[3] = NULL;
+ handle->hdma[4] = NULL;
+ handle->hdma[5] = NULL;
+ handle->hdma[6] = NULL;
+ handle->Init.Prescaler = 0;
+ handle->Init.Period = ((1 << 16) - 1);
+ handle->Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED2;
+ handle->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
+ handle->Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
+ #if defined(TIM_RCR_REP)
+ handle->Init.RepetitionCounter = 1;
+ #endif
+ enableTimerClock(handle);
+ HAL_TIM_Base_Init(handle);
+ stm32_pauseTimer(handle);
+ timersUsed[numTimersUsed++] = handle;
+ return handle;
+}
-#ifndef SIMPLEFOC_STM32_MAX_PINTIMERSUSED
-#define SIMPLEFOC_STM32_MAX_PINTIMERSUSED 12
-#endif
-int numTimerPinsUsed;
-PinMap* timerPinsUsed[SIMPLEFOC_STM32_MAX_PINTIMERSUSED];
-
bool _getPwmState(void* params) {
// assume timers are synchronized and that there's at least one timer
- HardwareTimer* pHT = ((STM32DriverParams*)params)->timers[0];
- TIM_HandleTypeDef* htim = pHT->getHandle();
-
- bool dir = __HAL_TIM_IS_TIM_COUNTING_DOWN(htim);
-
+ bool dir = __HAL_TIM_IS_TIM_COUNTING_DOWN(((STM32DriverParams*)params)->timers_handle[0]);
return dir;
}
-// setting pwm to hardware pin - instead analogWrite()
-void _setPwm(HardwareTimer *HT, uint32_t channel, uint32_t value, int resolution)
-{
- // TODO - remove commented code
- // PinName pin = digitalPinToPinName(ulPin);
- // TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
- // uint32_t index = get_timer_index(Instance);
- // HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
-
- HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution);
-}
-
-
-int getLLChannel(PinMap* timer) {
-#if defined(TIM_CCER_CC1NE)
- if (STM_PIN_INVERTED(timer->function)) {
- switch (STM_PIN_CHANNEL(timer->function)) {
- case 1: return LL_TIM_CHANNEL_CH1N;
- case 2: return LL_TIM_CHANNEL_CH2N;
- case 3: return LL_TIM_CHANNEL_CH3N;
-#if defined(LL_TIM_CHANNEL_CH4N)
- case 4: return LL_TIM_CHANNEL_CH4N;
-#endif
- default: return -1;
- }
- } else
-#endif
- {
- switch (STM_PIN_CHANNEL(timer->function)) {
- case 1: return LL_TIM_CHANNEL_CH1;
- case 2: return LL_TIM_CHANNEL_CH2;
- case 3: return LL_TIM_CHANNEL_CH3;
- case 4: return LL_TIM_CHANNEL_CH4;
- default: return -1;
+void stm32_pause(STM32DriverParams* params) {
+ if (params->master_timer != NULL) {
+ stm32_pauseTimer(params->master_timer);
+ }
+ else {
+ for (int i=0; inum_timers; i++) {
+ stm32_pauseTimer(params->timers_handle[i]);
}
}
- return -1;
}
+void stm32_resume(STM32DriverParams* params) {
+ if (params->master_timer != NULL) {
+ stm32_resumeTimer(params->master_timer);
+ }
+ else {
+ for (int i=0; inum_timers; i++) {
+ stm32_resumeTimer(params->timers_handle[i]);
+ }
+ }
+}
+
// init pin pwm
-HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
+TIM_HandleTypeDef* stm32_initPinPWM(uint32_t PWM_freq, PinMap* timer, uint32_t mode = TIM_OCMODE_PWM1, uint32_t polarity = TIM_OCPOLARITY_HIGH, uint32_t Npolarity = TIM_OCNPOLARITY_HIGH) {
// sanity check
- if (timer==NP)
- return NP;
- uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
- bool init = false;
- if (HardwareTimer_Handle[index] == NULL) {
- HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
- HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
- HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
- HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
- init = true;
- }
- HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
+ if (timer==NULL)
+ return NULL;
+ TIM_HandleTypeDef* handle = stm32_getTimer(timer);
uint32_t channel = STM_PIN_CHANNEL(timer->function);
- HT->pause();
- if (init)
- HT->setOverflow(PWM_freq, HERTZ_FORMAT);
- HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, timer->pin);
- #if SIMPLEFOC_PWM_ACTIVE_HIGH==false
- LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
- #endif
-#ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Configuring high timer ", (int)getTimerNumber(get_timer_index(HardwareTimer_Handle[index]->handle.Instance)));
- SIMPLEFOC_DEBUG("STM32-DRV: Configuring high channel ", (int)channel);
+ if (handle==NULL) {
+ handle = stm32_useTimer(timer);
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: Initializing TIM", (int)stm32_getTimerNumber(handle->Instance));
+ #endif
+ uint32_t arr = stm32_setClockAndARR(handle, PWM_freq);
+ if (arrpin, PinMap_TIM);
+ LL_TIM_CC_EnableChannel(handle->Instance, stm32_getLLChannel(timer));
+ if (IS_TIM_BREAK_INSTANCE(handle->Instance)) {
+ __HAL_TIM_MOE_ENABLE(handle);
+ }
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SimpleFOCDebug::print("STM32-DRV: Configured TIM");
+ SimpleFOCDebug::print((int)stm32_getTimerNumber(handle->Instance));
+ SIMPLEFOC_DEBUG("_CH", (int)channel);
+ #endif
+ return handle;
}
@@ -117,382 +223,100 @@ HardwareTimer* _initPinPWM(uint32_t PWM_freq, PinMap* timer) {
-
+/**
+0110: PWM mode 1 - In upcounting, channel 1 is active as long as TIMx_CNTTIMx_CCR1 else active (OC1REF=’1’).
+0111: PWM mode 2 - In upcounting, channel 1 is inactive as long as
+TIMx_CNTTIMx_CCR1 else inactive
+ */
// init high side pin
-HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, PinMap* timer) {
- HardwareTimer* HT = _initPinPWM(PWM_freq, timer);
- #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false && SIMPLEFOC_PWM_ACTIVE_HIGH==true
- LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
- #endif
- return HT;
+TIM_HandleTypeDef* _stm32_initPinPWMHigh(uint32_t PWM_freq, PinMap* timer) {
+ uint32_t polarity = SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW ;
+ TIM_HandleTypeDef* handle = stm32_initPinPWM(PWM_freq, timer, TIM_OCMODE_PWM1, polarity);
+ LL_TIM_OC_EnablePreload(handle->Instance, stm32_getLLChannel(timer));
+ return handle;
}
// init low side pin
-HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, PinMap* timer)
-{
- uint32_t index = get_timer_index((TIM_TypeDef*)timer->peripheral);
-
- bool init = false;
- if (HardwareTimer_Handle[index] == NULL) {
- HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)timer->peripheral);
- HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
- HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
- HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
- init = true;
- }
- HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
- uint32_t channel = STM_PIN_CHANNEL(timer->function);
-
-#ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Configuring low timer ", (int)getTimerNumber(get_timer_index(HardwareTimer_Handle[index]->handle.Instance)));
- SIMPLEFOC_DEBUG("STM32-DRV: Configuring low channel ", (int)channel);
-#endif
-
- HT->pause();
- if (init)
- HT->setOverflow(PWM_freq, HERTZ_FORMAT);
- // sets internal fields of HT, but we can't set polarity here
- HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, timer->pin);
- #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
- LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(timer), LL_TIM_OCPOLARITY_LOW);
- #endif
- return HT;
+TIM_HandleTypeDef* _stm32_initPinPWMLow(uint32_t PWM_freq, PinMap* timer) {
+ uint32_t polarity = SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW;
+ TIM_HandleTypeDef* handle = stm32_initPinPWM(PWM_freq, timer, TIM_OCMODE_PWM2, polarity);
+ LL_TIM_OC_EnablePreload(handle->Instance, stm32_getLLChannel(timer));
+ return handle;
}
-// align the timers to end the init
-void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3)
-{
- HT1->pause();
- HT1->refresh();
- HT2->pause();
- HT2->refresh();
- HT3->pause();
- HT3->refresh();
- HT1->resume();
- HT2->resume();
- HT3->resume();
-}
+// // align the timers to end the init
+// void _startTimers(TIM_HandleTypeDef *timers_to_start[], int timer_num) {
+// stm32_alignTimers(timers_to_start, timer_num);
+// }
-// align the timers to end the init
-void _alignPWMTimers(HardwareTimer *HT1, HardwareTimer *HT2, HardwareTimer *HT3, HardwareTimer *HT4)
-{
- HT1->pause();
- HT1->refresh();
- HT2->pause();
- HT2->refresh();
- HT3->pause();
- HT3->refresh();
- HT4->pause();
- HT4->refresh();
- HT1->resume();
- HT2->resume();
- HT3->resume();
- HT4->resume();
-}
+// void _stopTimers(TIM_HandleTypeDef **timers_to_stop, int timer_num) {
+// TIM_HandleTypeDef* timers_distinct[6];
+// timer_num = stm32_distinctTimers(timers_to_stop, timer_num, timers_distinct);
+// for (int i=0; i < timer_num; i++) {
+// if(timers_distinct[i] == NULL) return;
+// stm32_pauseTimer(timers_distinct[i]);
+// stm32_refreshTimer(timers_distinct[i]);
+// #ifdef SIMPLEFOC_STM32_DEBUG
+// SIMPLEFOC_DEBUG("STM32-DRV: Stopping timer ", stm32_getTimerNumber(timers_distinct[i]->Instance));
+// #endif
+// }
+// }
-// align the timers to end the init
-void _stopTimers(HardwareTimer **timers_to_stop, int timer_num)
-{
- // TODO - stop each timer only once
- // stop timers
- for (int i=0; i < timer_num; i++) {
- if(timers_to_stop[i] == NP) return;
- timers_to_stop[i]->pause();
- timers_to_stop[i]->refresh();
- #ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Stopping timer ", getTimerNumber(get_timer_index(timers_to_stop[i]->getHandle()->Instance)));
- #endif
- }
-}
-#if defined(STM32G4xx)
-// function finds the appropriate timer source trigger for the master/slave timer combination
-// returns -1 if no trigger source is found
-// currently supports the master timers to be from TIM1 to TIM4 and TIM8
-int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) { // put master and slave in temp variables to avoid arrows
- TIM_TypeDef *TIM_master = master->getHandle()->Instance;
- #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
- if (TIM_master == TIM1) return LL_TIM_TS_ITR0;// return TIM_TS_ITR0;
- #endif
- #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
- else if (TIM_master == TIM2) return LL_TIM_TS_ITR1;//return TIM_TS_ITR1;
- #endif
- #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
- else if (TIM_master == TIM3) return LL_TIM_TS_ITR2;//return TIM_TS_ITR2;
- #endif
- #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
- else if (TIM_master == TIM4) return LL_TIM_TS_ITR3;//return TIM_TS_ITR3;
- #endif
- #if defined(TIM5) && defined(LL_TIM_TS_ITR4)
- else if (TIM_master == TIM5) return LL_TIM_TS_ITR4;//return TIM_TS_ITR4;
- #endif
- #if defined(TIM8) && defined(LL_TIM_TS_ITR5)
- else if (TIM_master == TIM8) return LL_TIM_TS_ITR5;//return TIM_TS_ITR5;
- #endif
- return -1;
-}
-#elif defined(STM32F4xx) || defined(STM32F1xx) || defined(STM32L4xx) || defined(STM32F7xx)
-
-// function finds the appropriate timer source trigger for the master/slave timer combination
-// returns -1 if no trigger source is found
-// currently supports the master timers to be from TIM1 to TIM4 and TIM8
-int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) {
- // put master and slave in temp variables to avoid arrows
- TIM_TypeDef *TIM_master = master->getHandle()->Instance;
- TIM_TypeDef *TIM_slave = slave->getHandle()->Instance;
- #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
- if (TIM_master == TIM1){
- #if defined(TIM2)
- if(TIM_slave == TIM2) return LL_TIM_TS_ITR0;
- #endif
- #if defined(TIM3)
- else if(TIM_slave == TIM3) return LL_TIM_TS_ITR0;
- #endif
- #if defined(TIM4)
- else if(TIM_slave == TIM4) return LL_TIM_TS_ITR0;
- #endif
- #if defined(TIM8)
- else if(TIM_slave == TIM8) return LL_TIM_TS_ITR0;
- #endif
- }
- #endif
- #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
- else if (TIM_master == TIM2){
- #if defined(TIM1)
- if(TIM_slave == TIM1) return LL_TIM_TS_ITR1;
- #endif
- #if defined(TIM3)
- else if(TIM_slave == TIM3) return LL_TIM_TS_ITR1;
- #endif
- #if defined(TIM4)
- else if(TIM_slave == TIM4) return LL_TIM_TS_ITR1;
- #endif
- #if defined(TIM8)
- else if(TIM_slave == TIM8) return LL_TIM_TS_ITR1;
- #endif
- #if defined(TIM5)
- else if(TIM_slave == TIM5) return LL_TIM_TS_ITR0;
- #endif
- }
- #endif
- #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
- else if (TIM_master == TIM3){
- #if defined(TIM1)
- if(TIM_slave == TIM1) return LL_TIM_TS_ITR2;
- #endif
- #if defined(TIM2)
- else if(TIM_slave == TIM2) return LL_TIM_TS_ITR2;
- #endif
- #if defined(TIM4)
- else if(TIM_slave == TIM4) return LL_TIM_TS_ITR2;
- #endif
- #if defined(TIM5)
- else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
- #endif
- }
- #endif
- #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
- else if (TIM_master == TIM4){
- #if defined(TIM1)
- if(TIM_slave == TIM1) return LL_TIM_TS_ITR3;
- #endif
- #if defined(TIM2)
- else if(TIM_slave == TIM2) return LL_TIM_TS_ITR3;
- #endif
- #if defined(TIM3)
- else if(TIM_slave == TIM3) return LL_TIM_TS_ITR3;
- #endif
- #if defined(TIM8)
- else if(TIM_slave == TIM8) return LL_TIM_TS_ITR2;
- #endif
- #if defined(TIM5)
- else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
- #endif
- }
- #endif
- #if defined(TIM5)
- else if (TIM_master == TIM5){
- #if !defined(STM32L4xx) // only difference between F4,F1 and L4
- #if defined(TIM1)
- if(TIM_slave == TIM1) return LL_TIM_TS_ITR0;
- #endif
- #if defined(TIM3)
- else if(TIM_slave == TIM3) return LL_TIM_TS_ITR2;
- #endif
- #endif
- #if defined(TIM8)
- if(TIM_slave == TIM8) return LL_TIM_TS_ITR3;
- #endif
- }
- #endif
- #if defined(TIM8)
- else if (TIM_master == TIM8){
- #if defined(TIM2)
- if(TIM_slave==TIM2) return LL_TIM_TS_ITR1;
- #endif
- #if defined(TIM4)
- else if(TIM_slave == TIM4) return LL_TIM_TS_ITR3;
- #endif
- #if defined(TIM5)
- else if(TIM_slave == TIM5) return LL_TIM_TS_ITR3;
- #endif
- }
- #endif
- return -1; // combination not supported
-}
-#else
-// Alignment not supported for this architecture
-int _getInternalSourceTrigger(HardwareTimer* master, HardwareTimer* slave) {
- return -1;
-}
-#endif
-void syncTimerFrequency(long pwm_frequency, HardwareTimer *timers[], uint8_t num_timers) {
- uint32_t max_frequency = 0;
- uint32_t min_frequency = UINT32_MAX;
- for (size_t i=0; igetTimerClkFreq();
- if (freq > max_frequency) {
- max_frequency = freq;
- } else if (freq < min_frequency) {
- min_frequency = freq;
- }
- }
- if (max_frequency==min_frequency) return;
- uint32_t overflow_value = min_frequency/pwm_frequency;
- for (size_t i=0; igetTimerClkFreq()/min_frequency;
- #ifdef SIMPLEFOC_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Setting prescale to ", (float)prescale_factor);
- SIMPLEFOC_DEBUG("STM32-DRV: Setting Overflow to ", (float)overflow_value);
- #endif
- timers[i]->setPrescaleFactor(prescale_factor);
- timers[i]->setOverflow(overflow_value,TICK_FORMAT);
- timers[i]->refresh();
- }
-}
-void _alignTimersNew() {
- int numTimers = 0;
- HardwareTimer *timers[numTimerPinsUsed];
-
- // find the timers used
- for (int i=0; iperipheral);
- HardwareTimer *timer = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
- bool found = false;
- for (int j=0; jInstance->ARR;
+ uint32_t prescaler = timers_distinct[i]->Instance->PSC;
+ float pwm_freq = (float)freq/(prescaler+1.0f)/(arr+1.0f)/2.0f;
+ if (i==0) {
+ common_pwm_freq = pwm_freq;
+ } else {
+ if (pwm_freq != common_pwm_freq) {
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SimpleFOCDebug::print("STM32-DRV: ERR: Timer frequency different: TIM");
+ SimpleFOCDebug::print(stm32_getTimerNumber(timers_distinct[0]->Instance));
+ SimpleFOCDebug::print(" freq: ");
+ SimpleFOCDebug::print(common_pwm_freq);
+ SimpleFOCDebug::print(" != TIM");
+ SimpleFOCDebug::print(stm32_getTimerNumber(timers_distinct[i]->Instance));
+ SimpleFOCDebug::println(" freq: ", pwm_freq);
+ #endif
+ return -1;
}
}
- if (!found)
- timers[numTimers++] = timer;
}
-
- #ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Syncronising timers! Timer no. ", numTimers);
- #endif
-
- // see if there is more then 1 timers used for the pwm
- // if yes, try to align timers
- if(numTimers > 1){
- // find the master timer
- int16_t master_index = -1;
- int triggerEvent = -1;
- for (int i=0; igetHandle()->Instance)) {
- // check if timer already configured in TRGO update mode (used for ADC triggering)
- // in that case we should not change its TRGO configuration
- if(timers[i]->getHandle()->Instance->CR2 & LL_TIM_TRGO_UPDATE) continue;
- // check if the timer has the supported internal trigger for other timers
- for (int slave_i=0; slave_i 1.0f) {
#ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Aligning PWM to master timer: ", getTimerNumber(get_timer_index(timers[master_index]->getHandle()->Instance)));
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: Common timer frequency unexpected: ", common_pwm_freq);
#endif
- // make the master timer generate ITRGx event
- // if it was already configured in slave mode
- LL_TIM_SetSlaveMode(timers[master_index]->getHandle()->Instance, LL_TIM_SLAVEMODE_DISABLED );
- // Configure the master timer to send a trigger signal on enable
- LL_TIM_SetTriggerOutput(timers[master_index]->getHandle()->Instance, LL_TIM_TRGO_ENABLE);
- // configure other timers to get the input trigger from the master timer
- for (int slave_index=0; slave_index < numTimers; slave_index++) {
- if (slave_index == master_index)
- continue;
- // Configure the slave timer to be triggered by the master enable signal
- LL_TIM_SetTriggerInput(timers[slave_index]->getHandle()->Instance, _getInternalSourceTrigger(timers[master_index], timers[slave_index]));
- LL_TIM_SetSlaveMode(timers[slave_index]->getHandle()->Instance, LL_TIM_SLAVEMODE_TRIGGER);
- }
- }
+ return -1;
}
-
- // enable timer clock
- for (int i=0; ipause();
- // timers[i]->refresh();
- #ifdef SIMPLEFOC_STM32_DEBUG
- SIMPLEFOC_DEBUG("STM32-DRV: Restarting timer ", getTimerNumber(get_timer_index(timers[i]->getHandle()->Instance)));
- #endif
- }
-
- for (int i=0; iresume();
- }
-
-}
-
-
-
-// align the timers to end the init
-void _startTimers(HardwareTimer **timers_to_start, int timer_num)
-{
- // // TODO - start each timer only once
- // // start timers
- // for (int i=0; i < timer_num; i++) {
- // if(timers_to_start[i] == NP) return;
- // timers_to_start[i]->resume();
- // #ifdef SIMPLEFOC_STM32_DEBUG
- // SIMPLEFOC_DEBUG("STM32-DRV: Starting timer ", getTimerNumber(get_timer_index(timers_to_start[i]->getHandle()->Instance)));
- // #endif
- // }
- _alignTimersNew();
+ return 0;
}
// configure hardware 6pwm for a complementary pair of channels
-STM32DriverParams* _initHardware6PWMPair(long PWM_freq, float dead_zone, PinMap* pinH, PinMap* pinL, STM32DriverParams* params, int paramsPos) {
+STM32DriverParams* _stm32_initHardware6PWMPair(long PWM_freq, float dead_zone, PinMap* pinH, PinMap* pinL, STM32DriverParams* params, int paramsPos) {
// sanity check
- if (pinH==NP || pinL==NP)
+ if (pinH==NULL || pinL==NULL)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
-
#if defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
return SIMPLEFOC_DRIVER_INIT_FAILED; // return nothing
#endif
@@ -504,68 +328,56 @@ STM32DriverParams* _initHardware6PWMPair(long PWM_freq, float dead_zone, PinMap*
if (channel1!=channel2 || pinH->peripheral!=pinL->peripheral)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- uint32_t index = get_timer_index((TIM_TypeDef*)pinH->peripheral);
-
- if (HardwareTimer_Handle[index] == NULL) {
- HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef*)pinH->peripheral);
- HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
- HardwareTimer_Handle[index]->handle.Init.RepetitionCounter = 1;
- // HardwareTimer_Handle[index]->handle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
- HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
- ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow((uint32_t)PWM_freq, HERTZ_FORMAT);
- }
- HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
-
- HT->setMode(channel1, TIMER_OUTPUT_COMPARE_PWM1, pinH->pin);
- HT->setMode(channel2, TIMER_OUTPUT_COMPARE_PWM1, pinL->pin);
+ uint32_t polarity = SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW;
+ uint32_t Npolarity = SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW;
+ TIM_HandleTypeDef* handle = stm32_initPinPWM(PWM_freq, pinH, TIM_OCMODE_PWM1, polarity, Npolarity);
+ pinmap_pinout(pinL->pin, PinMap_TIM); // also init the low side pin
// dead time is set in nanoseconds
uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
- uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);
+ uint32_t dead_time = __LL_TIM_CALC_DEADTIME(stm32_getTimerClockFreq(handle), LL_TIM_GetClockDivision(handle->Instance), dead_time_ns);
if (dead_time>255) dead_time = 255;
if (dead_time==0 && dead_zone>0) {
dead_time = 255; // LL_TIM_CALC_DEADTIME returns 0 if dead_time_ns is too large
SIMPLEFOC_DEBUG("STM32-DRV: WARN: dead time too large, setting to max");
}
- LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear!
- #if SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH==false
- LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(pinH), LL_TIM_OCPOLARITY_LOW);
- #endif
- #if SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH==false
- LL_TIM_OC_SetPolarity(HT->getHandle()->Instance, getLLChannel(pinL), LL_TIM_OCPOLARITY_LOW);
- #endif
- LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, getLLChannel(pinH) | getLLChannel(pinL));
- HT->pause();
-
// make sure timer output goes to LOW when timer channels are temporarily disabled
- LL_TIM_SetOffStates(HT->getHandle()->Instance, LL_TIM_OSSI_DISABLE, LL_TIM_OSSR_ENABLE);
-
- params->timers[paramsPos] = HT;
- params->timers[paramsPos+1] = HT;
+ // TODO why init this here, and not generally in the initPWM or init timer functions?
+ // or, since its a rather specialized and hardware-speific setting, why not move it to
+ // another function?
+ LL_TIM_SetOffStates(handle->Instance, LL_TIM_OSSI_DISABLE, LL_TIM_OSSR_ENABLE);
+ LL_TIM_OC_SetDeadTime(handle->Instance, dead_time); // deadtime is non linear!
+ LL_TIM_CC_EnableChannel(handle->Instance, stm32_getLLChannel(pinH) | stm32_getLLChannel(pinL));
+ params->timers_handle[paramsPos] = handle;
+ params->timers_handle[paramsPos+1] = handle;
params->channels[paramsPos] = channel1;
params->channels[paramsPos+1] = channel2;
+ params->llchannels[paramsPos] = stm32_getLLChannel(pinH);
+ params->llchannels[paramsPos+1] = stm32_getLLChannel(pinL);
return params;
}
-STM32DriverParams* _initHardware6PWMInterface(long PWM_freq, float dead_zone, PinMap* pinA_h, PinMap* pinA_l, PinMap* pinB_h, PinMap* pinB_l, PinMap* pinC_h, PinMap* pinC_l) {
+STM32DriverParams* _stm32_initHardware6PWMInterface(long PWM_freq, float dead_zone, PinMap* pinA_h, PinMap* pinA_l, PinMap* pinB_h, PinMap* pinB_l, PinMap* pinC_h, PinMap* pinC_l) {
STM32DriverParams* params = new STM32DriverParams {
- .timers = { NP, NP, NP, NP, NP, NP },
+ .timers_handle = { NULL, NULL, NULL, NULL, NULL, NULL },
.channels = { 0, 0, 0, 0, 0, 0 },
+ .llchannels = { 0, 0, 0, 0, 0, 0 },
.pwm_frequency = PWM_freq,
+ .num_timers = 0,
+ .master_timer = NULL,
.dead_zone = dead_zone,
.interface_type = _HARDWARE_6PWM
};
-
- if (_initHardware6PWMPair(PWM_freq, dead_zone, pinA_h, pinA_l, params, 0) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ if (_stm32_initHardware6PWMPair(PWM_freq, dead_zone, pinA_h, pinA_l, params, 0) == SIMPLEFOC_DRIVER_INIT_FAILED)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- if(_initHardware6PWMPair(PWM_freq, dead_zone, pinB_h, pinB_l, params, 2) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ if(_stm32_initHardware6PWMPair(PWM_freq, dead_zone, pinB_h, pinB_l, params, 2) == SIMPLEFOC_DRIVER_INIT_FAILED)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- if (_initHardware6PWMPair(PWM_freq, dead_zone, pinC_h, pinC_l, params, 4) == SIMPLEFOC_DRIVER_INIT_FAILED)
+ if (_stm32_initHardware6PWMPair(PWM_freq, dead_zone, pinC_h, pinC_l, params, 4) == SIMPLEFOC_DRIVER_INIT_FAILED)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
-
+ params->num_timers = stm32_countTimers(params->timers_handle, 6);
return params;
}
@@ -574,214 +386,33 @@ STM32DriverParams* _initHardware6PWMInterface(long PWM_freq, float dead_zone, Pi
-/*
- timer combination scoring function
- assigns a score, and also checks the combination is valid
- returns <0 if combination is invalid, >=0 if combination is valid. lower (but positive) score is better
- for 6 pwm, hardware 6-pwm is preferred over software 6-pwm
- hardware 6-pwm is possible if each low channel is the inverted counterpart of its high channel
- inverted channels are not allowed except when using hardware 6-pwm (in theory they could be but lets not complicate things)
-*/
-int scoreCombination(int numPins, PinMap* pinTimers[]) {
- // check already used - TODO move this to outer loop also...
- for (int i=0; iperipheral == timerPinsUsed[i]->peripheral
- && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(timerPinsUsed[i]->function))
- return -2; // bad combination - timer channel already used
- }
-
- // TODO LPTIM and HRTIM should be ignored for now
-
- // check for inverted channels
- if (numPins < 6) {
- for (int i=0; ifunction))
- return -3; // bad combination - inverted channel used in non-hardware 6pwm
- }
- }
- // check for duplicated channels
- for (int i=0; iperipheral == pinTimers[j]->peripheral
- && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(pinTimers[j]->function)
- && STM_PIN_INVERTED(pinTimers[i]->function) == STM_PIN_INVERTED(pinTimers[j]->function))
- return -4; // bad combination - duplicated channel
- }
- }
- int score = 0;
- for (int i=0; iperipheral == pinTimers[j]->peripheral)
- found = true;
- }
- if (!found) score++;
- }
- if (numPins==6) {
- // check for inverted channels - best: 1 timer, 3 channels, 3 matching inverted channels
- // >1 timer, 3 channels, 3 matching inverted channels
- // 1 timer, 6 channels (no inverted channels)
- // >1 timer, 6 channels (no inverted channels)
- // check for inverted high-side channels - TODO is this a configuration we should allow? what if all 3 high side channels are inverted and the low-side non-inverted?
- if (STM_PIN_INVERTED(pinTimers[0]->function) || STM_PIN_INVERTED(pinTimers[2]->function) || STM_PIN_INVERTED(pinTimers[4]->function))
- return -5; // bad combination - inverted channel used on high-side channel
- if (pinTimers[0]->peripheral == pinTimers[1]->peripheral
- && pinTimers[2]->peripheral == pinTimers[3]->peripheral
- && pinTimers[4]->peripheral == pinTimers[5]->peripheral
- && STM_PIN_CHANNEL(pinTimers[0]->function) == STM_PIN_CHANNEL(pinTimers[1]->function)
- && STM_PIN_CHANNEL(pinTimers[2]->function) == STM_PIN_CHANNEL(pinTimers[3]->function)
- && STM_PIN_CHANNEL(pinTimers[4]->function) == STM_PIN_CHANNEL(pinTimers[5]->function)
- && STM_PIN_INVERTED(pinTimers[1]->function) && STM_PIN_INVERTED(pinTimers[3]->function) && STM_PIN_INVERTED(pinTimers[5]->function)) {
- // hardware 6pwm, score <10
-
- // TODO F37xxx doesn't support dead-time insertion, it has no TIM1/TIM8
- // F301, F302 --> 6 channels, but only 1-3 have dead-time insertion
- // TIM2/TIM3/TIM4/TIM5 don't do dead-time insertion
- // TIM15/TIM16/TIM17 do dead-time insertion only on channel 1
-
- // TODO check these defines
- #if defined(STM32F4xx_HAL_TIM_H) || defined(STM32F3xx_HAL_TIM_H) || defined(STM32F2xx_HAL_TIM_H) || defined(STM32F1xx_HAL_TIM_H) || defined(STM32F100_HAL_TIM_H) || defined(STM32FG0x1_HAL_TIM_H) || defined(STM32G0x0_HAL_TIM_H)
- if (STM_PIN_CHANNEL(pinTimers[0]->function)>3 || STM_PIN_CHANNEL(pinTimers[2]->function)>3 || STM_PIN_CHANNEL(pinTimers[4]->function)>3 )
- return -8; // channel 4 does not have dead-time insertion
- #endif
- #ifdef STM32G4xx_HAL_TIM_H
- if (STM_PIN_CHANNEL(pinTimers[0]->function)>4 || STM_PIN_CHANNEL(pinTimers[2]->function)>4 || STM_PIN_CHANNEL(pinTimers[4]->function)>4 )
- return -8; // channels 5 & 6 do not have dead-time insertion
- #endif
- }
- else {
- // check for inverted low-side channels
- if (STM_PIN_INVERTED(pinTimers[1]->function) || STM_PIN_INVERTED(pinTimers[3]->function) || STM_PIN_INVERTED(pinTimers[5]->function))
- return -6; // bad combination - inverted channel used on low-side channel in software 6-pwm
- if (pinTimers[0]->peripheral != pinTimers[1]->peripheral
- || pinTimers[2]->peripheral != pinTimers[3]->peripheral
- || pinTimers[4]->peripheral != pinTimers[5]->peripheral)
- return -7; // bad combination - non-matching timers for H/L side in software 6-pwm
- score += 10; // software 6pwm, score >10
- }
- }
- return score;
-}
-
-
-
-
-int findIndexOfFirstPinMapEntry(int pin) {
- PinName pinName = digitalPinToPinName(pin);
- int i = 0;
- while (PinMap_TIM[i].pin!=NC) {
- if (pinName == PinMap_TIM[i].pin)
- return i;
- i++;
- }
- return -1;
-}
-
-
-int findIndexOfLastPinMapEntry(int pin) {
- PinName pinName = digitalPinToPinName(pin);
- int i = 0;
- while (PinMap_TIM[i].pin!=NC) {
- if ( pinName == (PinMap_TIM[i].pin & ~ALTX_MASK)
- && pinName != (PinMap_TIM[i+1].pin & ~ALTX_MASK))
- return i;
- i++;
- }
- return -1;
-}
-
-
-
-
-
-
-#define NOT_FOUND 1000
-
-int findBestTimerCombination(int numPins, int index, int pins[], PinMap* pinTimers[]) {
- PinMap* searchArray[numPins];
- for (int j=0;j=0 && score= 0) {
- #ifdef SIMPLEFOC_STM32_DEBUG
- SimpleFOCDebug::print("STM32-DRV: best: ");
- printTimerCombination(numPins, pinTimers, bestScore);
- #endif
- }
- return bestScore;
-};
-
-
-
void* _configure1PWM(long pwm_frequency, const int pinA) {
- if (numTimerPinsUsed+1 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
- SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ if (numMotorsUsed+1 > SIMPLEFOC_STM32_MAX_MOTORSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many drivers used");
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
}
- if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
- else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
- // center-aligned frequency is uses two periods
- pwm_frequency *=2;
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = SIMPLEFOC_STM32_PWM_FREQUENCY; // default frequency 25khz
int pins[1] = { pinA };
- PinMap* pinTimers[1] = { NP };
- if (findBestTimerCombination(1, pins, pinTimers)<0)
+ PinMap* pinTimers[1] = { NULL };
+ if (stm32_findBestTimerCombination(1, pins, pinTimers)<0)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);\
- // align the timers
- _alignTimersNew();
-
+ TIM_HandleTypeDef* HT1 = stm32_initPinPWM(pwm_frequency, pinTimers[0], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
STM32DriverParams* params = new STM32DriverParams {
- .timers = { HT1 },
+ .timers_handle = { HT1 },
.channels = { channel1 },
- .pwm_frequency = pwm_frequency
+ .llchannels = { stm32_getLLChannel(pinTimers[0]) },
+ .pwm_frequency = pwm_frequency,
+ .num_timers = 1,
+ .master_timer = NULL
};
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
+ // align the timers (in this case, just start them)
+ params->master_timer = stm32_alignTimers(params->timers_handle, 1);
+ motorsUsed[numMotorsUsed++] = params;
return params;
}
@@ -793,87 +424,79 @@ void* _configure1PWM(long pwm_frequency, const int pinA) {
// - Stepper motor - 2PWM setting
// - hardware speciffic
void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
- if (numTimerPinsUsed+2 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
- SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ if (numMotorsUsed+1 > SIMPLEFOC_STM32_MAX_MOTORSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many drivers used");
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
}
- if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
- else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
- // center-aligned frequency is uses two periods
- pwm_frequency *=2;
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = SIMPLEFOC_STM32_PWM_FREQUENCY; // default frequency 25khz
int pins[2] = { pinA, pinB };
- PinMap* pinTimers[2] = { NP, NP };
- if (findBestTimerCombination(2, pins, pinTimers)<0)
+ PinMap* pinTimers[2] = { NULL, NULL };
+ if (stm32_findBestTimerCombination(2, pins, pinTimers)<0)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
- HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
- HardwareTimer *timers[2] = {HT1, HT2};
- syncTimerFrequency(pwm_frequency, timers, 2);
- // allign the timers
- _alignPWMTimers(HT1, HT2, HT2);
+ TIM_HandleTypeDef* HT1 = stm32_initPinPWM(pwm_frequency, pinTimers[0], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT2 = stm32_initPinPWM(pwm_frequency, pinTimers[1], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef *timers[2] = {HT1, HT2};
+ stm32_checkTimerFrequency(pwm_frequency, timers, 2);
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
STM32DriverParams* params = new STM32DriverParams {
- .timers = { HT1, HT2 },
+ .timers_handle = { HT1, HT2 },
.channels = { channel1, channel2 },
- .pwm_frequency = pwm_frequency
+ .llchannels = { stm32_getLLChannel(pinTimers[0]), stm32_getLLChannel(pinTimers[1]) },
+ .pwm_frequency = pwm_frequency, // TODO set to actual frequency
+ .num_timers = stm32_countTimers(timers, 2),
+ .master_timer = NULL
};
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
+ // align the timers
+ params->master_timer = stm32_alignTimers(timers, 2);
+ motorsUsed[numMotorsUsed++] = params;
return params;
}
-TIM_MasterConfigTypeDef sMasterConfig;
-TIM_SlaveConfigTypeDef sSlaveConfig;
-
// function setting the high pwm frequency to the supplied pins
// - BLDC motor - 3PWM setting
// - hardware speciffic
void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
- if (numTimerPinsUsed+3 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
- SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ if (numMotorsUsed+1 > SIMPLEFOC_STM32_MAX_MOTORSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many drivers used");
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
}
- if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
- else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
- // center-aligned frequency is uses two periods
- pwm_frequency *=2;
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = SIMPLEFOC_STM32_PWM_FREQUENCY; // default frequency 25khz
int pins[3] = { pinA, pinB, pinC };
- PinMap* pinTimers[3] = { NP, NP, NP };
- if (findBestTimerCombination(3, pins, pinTimers)<0)
+ PinMap* pinTimers[3] = { NULL, NULL, NULL };
+ if (stm32_findBestTimerCombination(3, pins, pinTimers)<0)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
- HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
- HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinTimers[2]);
+ TIM_HandleTypeDef* HT1 = stm32_initPinPWM(pwm_frequency, pinTimers[0], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT2 = stm32_initPinPWM(pwm_frequency, pinTimers[1], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT3 = stm32_initPinPWM(pwm_frequency, pinTimers[2], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
- HardwareTimer *timers[3] = {HT1, HT2, HT3};
- syncTimerFrequency(pwm_frequency, timers, 3);
+ TIM_HandleTypeDef *timers[3] = {HT1, HT2, HT3};
+ stm32_checkTimerFrequency(pwm_frequency, timers, 3);
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
STM32DriverParams* params = new STM32DriverParams {
- .timers = { HT1, HT2, HT3 },
+ .timers_handle = { HT1, HT2, HT3 },
.channels = { channel1, channel2, channel3 },
- .pwm_frequency = pwm_frequency
+ .llchannels = { stm32_getLLChannel(pinTimers[0]), stm32_getLLChannel(pinTimers[1]), stm32_getLLChannel(pinTimers[2]) },
+ .pwm_frequency = pwm_frequency,
+ .num_timers = stm32_countTimers(timers, 3),
+ .master_timer = NULL
};
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[2];
-
- _alignTimersNew();
-
+ params->master_timer = stm32_alignTimers(timers, 3);
+ motorsUsed[numMotorsUsed++] = params;
return params;
}
@@ -883,28 +506,23 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
// - Stepper motor - 4PWM setting
// - hardware speciffic
void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
- if (numTimerPinsUsed+4 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
- SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ if (numMotorsUsed+1 > SIMPLEFOC_STM32_MAX_MOTORSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many drivers used");
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
}
- if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
- else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
- // center-aligned frequency is uses two periods
- pwm_frequency *=2;
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = SIMPLEFOC_STM32_PWM_FREQUENCY; // default frequency 25khz
int pins[4] = { pinA, pinB, pinC, pinD };
- PinMap* pinTimers[4] = { NP, NP, NP, NP };
- if (findBestTimerCombination(4, pins, pinTimers)<0)
+ PinMap* pinTimers[4] = { NULL, NULL, NULL, NULL };
+ if (stm32_findBestTimerCombination(4, pins, pinTimers)<0)
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
- HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinTimers[0]);
- HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinTimers[1]);
- HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinTimers[2]);
- HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinTimers[3]);
- HardwareTimer *timers[4] = {HT1, HT2, HT3, HT4};
- syncTimerFrequency(pwm_frequency, timers, 4);
- // allign the timers
- _alignPWMTimers(HT1, HT2, HT3, HT4);
+ TIM_HandleTypeDef* HT1 = stm32_initPinPWM(pwm_frequency, pinTimers[0], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT2 = stm32_initPinPWM(pwm_frequency, pinTimers[1], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT3 = stm32_initPinPWM(pwm_frequency, pinTimers[2], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef* HT4 = stm32_initPinPWM(pwm_frequency, pinTimers[3], TIM_OCMODE_PWM1, (SIMPLEFOC_PWM_ACTIVE_HIGH)?TIM_OCPOLARITY_HIGH:TIM_OCPOLARITY_LOW);
+ TIM_HandleTypeDef *timers[4] = {HT1, HT2, HT3, HT4};
+ stm32_checkTimerFrequency(pwm_frequency, timers, 4);
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
@@ -912,14 +530,15 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
uint32_t channel4 = STM_PIN_CHANNEL(pinTimers[3]->function);
STM32DriverParams* params = new STM32DriverParams {
- .timers = { HT1, HT2, HT3, HT4 },
+ .timers_handle = { HT1, HT2, HT3, HT4 },
.channels = { channel1, channel2, channel3, channel4 },
- .pwm_frequency = pwm_frequency
+ .llchannels = { stm32_getLLChannel(pinTimers[0]), stm32_getLLChannel(pinTimers[1]), stm32_getLLChannel(pinTimers[2]), stm32_getLLChannel(pinTimers[3]) },
+ .pwm_frequency = pwm_frequency,
+ .num_timers = stm32_countTimers(timers, 4),
+ .master_timer = NULL
};
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[0];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[1];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[2];
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[3];
+ params->master_timer = stm32_alignTimers(timers, 4);
+ motorsUsed[numMotorsUsed++] = params;
return params;
}
@@ -927,43 +546,55 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
// function setting the pwm duty cycle to the hardware
// - DC motor - 1PWM setting
-// - hardware speciffic
+// - hardware specific
void _writeDutyCycle1PWM(float dc_a, void* params){
- // transform duty cycle from [0,1] to [0,255]
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
+ uint32_t duty = dc_a*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty);
}
// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
-//- hardware speciffic
+//- hardware specific
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
- // transform duty cycle from [0,1] to [0,4095]
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
+ uint32_t duty1 = dc_a*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ uint32_t duty2 = dc_b*(((STM32DriverParams*)params)->timers_handle[1]->Instance->ARR+1);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty1);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[1], ((STM32DriverParams*)params)->channels[1], duty2);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
}
// function setting the pwm duty cycle to the hardware
// - BLDC motor - 3PWM setting
-//- hardware speciffic
+//- hardware specific
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
- // transform duty cycle from [0,1] to [0,4095]
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
+ uint32_t duty1 = dc_a*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ uint32_t duty2 = dc_b*(((STM32DriverParams*)params)->timers_handle[1]->Instance->ARR+1);
+ uint32_t duty3 = dc_c*(((STM32DriverParams*)params)->timers_handle[2]->Instance->ARR+1);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty1);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[1], ((STM32DriverParams*)params)->channels[1], duty2);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->channels[2], duty3);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
}
// function setting the pwm duty cycle to the hardware
// - Stepper motor - 4PWM setting
-//- hardware speciffic
+//- hardware specific
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
- // transform duty cycle from [0,1] to [0,4095]
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
- _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
+ uint32_t duty1 = dc_1a*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ uint32_t duty2 = dc_1b*(((STM32DriverParams*)params)->timers_handle[1]->Instance->ARR+1);
+ uint32_t duty3 = dc_2a*(((STM32DriverParams*)params)->timers_handle[2]->Instance->ARR+1);
+ uint32_t duty4 = dc_2b*(((STM32DriverParams*)params)->timers_handle[3]->Instance->ARR+1);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty1);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[1], ((STM32DriverParams*)params)->channels[1], duty2);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->channels[2], duty3);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[3], ((STM32DriverParams*)params)->channels[3], duty4);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
}
@@ -973,35 +604,32 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, vo
// - BLDC driver - 6PWM setting
// - hardware specific
void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
- if (numTimerPinsUsed+6 > SIMPLEFOC_STM32_MAX_PINTIMERSUSED) {
- SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many pins used");
+ if (numMotorsUsed+1 > SIMPLEFOC_STM32_MAX_MOTORSUSED) {
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: too many drivers used");
return (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
}
- if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
- else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
- // center-aligned frequency is uses two periods
- pwm_frequency *=2;
+ if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = SIMPLEFOC_STM32_PWM_FREQUENCY; // default frequency 25khz
// find configuration
int pins[6] = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l };
- PinMap* pinTimers[6] = { NP, NP, NP, NP, NP, NP };
- int score = findBestTimerCombination(6, pins, pinTimers);
+ PinMap* pinTimers[6] = { NULL, NULL, NULL, NULL, NULL, NULL };
+ int score = stm32_findBestTimerCombination(6, pins, pinTimers);
STM32DriverParams* params;
// configure accordingly
if (score<0)
params = (STM32DriverParams*)SIMPLEFOC_DRIVER_INIT_FAILED;
else if (score<10) // hardware pwm
- params = _initHardware6PWMInterface(pwm_frequency, dead_zone, pinTimers[0], pinTimers[1], pinTimers[2], pinTimers[3], pinTimers[4], pinTimers[5]);
+ params = _stm32_initHardware6PWMInterface(pwm_frequency, dead_zone, pinTimers[0], pinTimers[1], pinTimers[2], pinTimers[3], pinTimers[4], pinTimers[5]);
else { // software pwm
- HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinTimers[0]);
- HardwareTimer* HT2 = _initPinPWMLow(pwm_frequency, pinTimers[1]);
- HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency, pinTimers[2]);
- HardwareTimer* HT4 = _initPinPWMLow(pwm_frequency, pinTimers[3]);
- HardwareTimer* HT5 = _initPinPWMHigh(pwm_frequency, pinTimers[4]);
- HardwareTimer* HT6 = _initPinPWMLow(pwm_frequency, pinTimers[5]);
- HardwareTimer *timers[6] = {HT1, HT2, HT3, HT4, HT5, HT6};
- syncTimerFrequency(pwm_frequency, timers, 6);
+ TIM_HandleTypeDef* HT1 = _stm32_initPinPWMHigh(pwm_frequency, pinTimers[0]);
+ TIM_HandleTypeDef* HT2 = _stm32_initPinPWMLow(pwm_frequency, pinTimers[1]);
+ TIM_HandleTypeDef* HT3 = _stm32_initPinPWMHigh(pwm_frequency, pinTimers[2]);
+ TIM_HandleTypeDef* HT4 = _stm32_initPinPWMLow(pwm_frequency, pinTimers[3]);
+ TIM_HandleTypeDef* HT5 = _stm32_initPinPWMHigh(pwm_frequency, pinTimers[4]);
+ TIM_HandleTypeDef* HT6 = _stm32_initPinPWMLow(pwm_frequency, pinTimers[5]);
+ TIM_HandleTypeDef *timers[6] = {HT1, HT2, HT3, HT4, HT5, HT6};
+ stm32_checkTimerFrequency(pwm_frequency, timers, 6);
uint32_t channel1 = STM_PIN_CHANNEL(pinTimers[0]->function);
uint32_t channel2 = STM_PIN_CHANNEL(pinTimers[1]->function);
uint32_t channel3 = STM_PIN_CHANNEL(pinTimers[2]->function);
@@ -1009,33 +637,41 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
uint32_t channel5 = STM_PIN_CHANNEL(pinTimers[4]->function);
uint32_t channel6 = STM_PIN_CHANNEL(pinTimers[5]->function);
params = new STM32DriverParams {
- .timers = { HT1, HT2, HT3, HT4, HT5, HT6 },
+ .timers_handle = { HT1, HT2, HT3, HT4, HT5, HT6 },
.channels = { channel1, channel2, channel3, channel4, channel5, channel6 },
+ .llchannels = { stm32_getLLChannel(pinTimers[0]), stm32_getLLChannel(pinTimers[1]), stm32_getLLChannel(pinTimers[2]), stm32_getLLChannel(pinTimers[3]), stm32_getLLChannel(pinTimers[4]), stm32_getLLChannel(pinTimers[5]) },
.pwm_frequency = pwm_frequency,
+ .num_timers = stm32_countTimers(timers, 6),
+ .master_timer = NULL,
.dead_zone = dead_zone,
.interface_type = _SOFTWARE_6PWM
};
}
if (score>=0) {
- for (int i=0; i<6; i++)
- timerPinsUsed[numTimerPinsUsed++] = pinTimers[i];
- _alignTimersNew();
+ params->master_timer = stm32_alignTimers(params->timers_handle, 6);
+ motorsUsed[numMotorsUsed++] = params;
}
return params; // success
}
-void _setSinglePhaseState(PhaseState state, HardwareTimer *HT, int channel1,int channel2) {
- _UNUSED(channel2);
+void _setSinglePhaseState(PhaseState state, TIM_HandleTypeDef *HT, int llchannel_hi, int llchannel_lo) {
switch (state) {
case PhaseState::PHASE_OFF:
- // Due to a weird quirk in the arduino timer API, pauseChannel only disables the complementary channel (e.g. CC1NE).
- // To actually make the phase floating, we must also set pwm to 0.
- HT->pauseChannel(channel1);
+ stm32_pauseChannel(HT, llchannel_hi | llchannel_lo);
break;
+ case PhaseState::PHASE_HI:
+ stm32_pauseChannel(HT, llchannel_lo);
+ stm32_resumeChannel(HT, llchannel_hi);
+ break;
+ case PhaseState::PHASE_LO:
+ stm32_pauseChannel(HT, llchannel_hi);
+ stm32_resumeChannel(HT, llchannel_lo);
+ break;
+ case PhaseState::PHASE_ON:
default:
- HT->resumeChannel(channel1);
+ stm32_resumeChannel(HT, llchannel_hi | llchannel_lo);
break;
}
}
@@ -1045,146 +681,72 @@ void _setSinglePhaseState(PhaseState state, HardwareTimer *HT, int channel1,int
// - BLDC driver - 6PWM setting
// - hardware specific
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState* phase_state, void* params){
+ uint32_t duty1;
+ uint32_t duty2;
+ uint32_t duty3;
switch(((STM32DriverParams*)params)->interface_type){
case _HARDWARE_6PWM:
- // phase a
- _setSinglePhaseState(phase_state[0], ((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], ((STM32DriverParams*)params)->channels[1]);
- if(phase_state[0] == PhaseState::PHASE_OFF) dc_a = 0.0f;
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _PWM_RANGE*dc_a, _PWM_RESOLUTION);
- // phase b
- _setSinglePhaseState(phase_state[1], ((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], ((STM32DriverParams*)params)->channels[3]);
- if(phase_state[1] == PhaseState::PHASE_OFF) dc_b = 0.0f;
- _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _PWM_RANGE*dc_b, _PWM_RESOLUTION);
- // phase c
- _setSinglePhaseState(phase_state[2], ((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], ((STM32DriverParams*)params)->channels[5]);
- if(phase_state[2] == PhaseState::PHASE_OFF) dc_c = 0.0f;
- _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], _PWM_RANGE*dc_c, _PWM_RESOLUTION);
+ duty1 = dc_a*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ duty2 = dc_b*(((STM32DriverParams*)params)->timers_handle[2]->Instance->ARR+1);
+ duty3 = dc_c*(((STM32DriverParams*)params)->timers_handle[4]->Instance->ARR+1);
+ if(phase_state[0] == PhaseState::PHASE_OFF) duty1 = 0;
+ if(phase_state[1] == PhaseState::PHASE_OFF) duty2 = 0;
+ if(phase_state[2] == PhaseState::PHASE_OFF) duty3 = 0;
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
+ _setSinglePhaseState(phase_state[0], ((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->llchannels[0], ((STM32DriverParams*)params)->llchannels[1]);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty1);
+ _setSinglePhaseState(phase_state[1], ((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->llchannels[2], ((STM32DriverParams*)params)->llchannels[3]);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->channels[2], duty2);
+ _setSinglePhaseState(phase_state[2], ((STM32DriverParams*)params)->timers_handle[4], ((STM32DriverParams*)params)->llchannels[4], ((STM32DriverParams*)params)->llchannels[5]);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[4], ((STM32DriverParams*)params)->channels[4], duty3);
+ if (((STM32DriverParams*)params)->num_timers == 1) LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
break;
case _SOFTWARE_6PWM:
float dead_zone = ((STM32DriverParams*)params)->dead_zone / 2.0f;
+ duty1 = _constrain(dc_a - dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[0]->Instance->ARR+1);
+ duty2 = _constrain(dc_b - dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[2]->Instance->ARR+1);
+ duty3 = _constrain(dc_c - dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[4]->Instance->ARR+1);
+ uint32_t duty1N = _constrain(dc_a + dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[1]->Instance->ARR+1);
+ uint32_t duty2N = _constrain(dc_b + dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[3]->Instance->ARR+1);
+ uint32_t duty3N = _constrain(dc_c + dead_zone, 0.0f, 1.0f)*(((STM32DriverParams*)params)->timers_handle[5]->Instance->ARR+1);
+
+ LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance); // timers for high and low side assumed to be the same timer
if (phase_state[0] == PhaseState::PHASE_ON || phase_state[0] == PhaseState::PHASE_HI)
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], _constrain(dc_a - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], duty1);
else
- _setPwm(((STM32DriverParams*)params)->timers[0], ((STM32DriverParams*)params)->channels[0], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[0], ((STM32DriverParams*)params)->channels[0], 0);
if (phase_state[0] == PhaseState::PHASE_ON || phase_state[0] == PhaseState::PHASE_LO)
- _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], _constrain(dc_a + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[1], ((STM32DriverParams*)params)->channels[1], duty1N);
else
- _setPwm(((STM32DriverParams*)params)->timers[1], ((STM32DriverParams*)params)->channels[1], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[1], ((STM32DriverParams*)params)->channels[1], 0);
+ LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[2]->Instance); // timers for high and low side assumed to be the same timer
if (phase_state[1] == PhaseState::PHASE_ON || phase_state[1] == PhaseState::PHASE_HI)
- _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], _constrain(dc_b - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->channels[2], duty2);
else
- _setPwm(((STM32DriverParams*)params)->timers[2], ((STM32DriverParams*)params)->channels[2], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[2], ((STM32DriverParams*)params)->channels[2], 0);
if (phase_state[1] == PhaseState::PHASE_ON || phase_state[1] == PhaseState::PHASE_LO)
- _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], _constrain(dc_b + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[3], ((STM32DriverParams*)params)->channels[3], duty2N);
else
- _setPwm(((STM32DriverParams*)params)->timers[3], ((STM32DriverParams*)params)->channels[3], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[3], ((STM32DriverParams*)params)->channels[3], 0);
+ LL_TIM_DisableUpdateEvent(((STM32DriverParams*)params)->timers_handle[4]->Instance); // timers for high and low side assumed to be the same timer
if (phase_state[2] == PhaseState::PHASE_ON || phase_state[2] == PhaseState::PHASE_HI)
- _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], _constrain(dc_c - dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[4], ((STM32DriverParams*)params)->channels[4], duty3);
else
- _setPwm(((STM32DriverParams*)params)->timers[4], ((STM32DriverParams*)params)->channels[4], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[4], ((STM32DriverParams*)params)->channels[4], 0);
if (phase_state[2] == PhaseState::PHASE_ON || phase_state[2] == PhaseState::PHASE_LO)
- _setPwm(((STM32DriverParams*)params)->timers[5], ((STM32DriverParams*)params)->channels[5], _constrain(dc_c + dead_zone, 0.0f, 1.0f)*_PWM_RANGE, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[5], ((STM32DriverParams*)params)->channels[5], duty3N);
else
- _setPwm(((STM32DriverParams*)params)->timers[5], ((STM32DriverParams*)params)->channels[5], 0.0f, _PWM_RESOLUTION);
+ stm32_setPwm(((STM32DriverParams*)params)->timers_handle[5], ((STM32DriverParams*)params)->channels[5], 0);
+
+ LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[0]->Instance);
+ LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[2]->Instance);
+ LL_TIM_EnableUpdateEvent(((STM32DriverParams*)params)->timers_handle[4]->Instance);
break;
}
- _UNUSED(phase_state);
}
-#ifdef SIMPLEFOC_STM32_DEBUG
-
-int getTimerNumber(int timerIndex) {
- #if defined(TIM1_BASE)
- if (timerIndex==TIMER1_INDEX) return 1;
- #endif
- #if defined(TIM2_BASE)
- if (timerIndex==TIMER2_INDEX) return 2;
- #endif
- #if defined(TIM3_BASE)
- if (timerIndex==TIMER3_INDEX) return 3;
- #endif
- #if defined(TIM4_BASE)
- if (timerIndex==TIMER4_INDEX) return 4;
- #endif
- #if defined(TIM5_BASE)
- if (timerIndex==TIMER5_INDEX) return 5;
- #endif
- #if defined(TIM6_BASE)
- if (timerIndex==TIMER6_INDEX) return 6;
- #endif
- #if defined(TIM7_BASE)
- if (timerIndex==TIMER7_INDEX) return 7;
- #endif
- #if defined(TIM8_BASE)
- if (timerIndex==TIMER8_INDEX) return 8;
- #endif
- #if defined(TIM9_BASE)
- if (timerIndex==TIMER9_INDEX) return 9;
- #endif
- #if defined(TIM10_BASE)
- if (timerIndex==TIMER10_INDEX) return 10;
- #endif
- #if defined(TIM11_BASE)
- if (timerIndex==TIMER11_INDEX) return 11;
- #endif
- #if defined(TIM12_BASE)
- if (timerIndex==TIMER12_INDEX) return 12;
- #endif
- #if defined(TIM13_BASE)
- if (timerIndex==TIMER13_INDEX) return 13;
- #endif
- #if defined(TIM14_BASE)
- if (timerIndex==TIMER14_INDEX) return 14;
- #endif
- #if defined(TIM15_BASE)
- if (timerIndex==TIMER15_INDEX) return 15;
- #endif
- #if defined(TIM16_BASE)
- if (timerIndex==TIMER16_INDEX) return 16;
- #endif
- #if defined(TIM17_BASE)
- if (timerIndex==TIMER17_INDEX) return 17;
- #endif
- #if defined(TIM18_BASE)
- if (timerIndex==TIMER18_INDEX) return 18;
- #endif
- #if defined(TIM19_BASE)
- if (timerIndex==TIMER19_INDEX) return 19;
- #endif
- #if defined(TIM20_BASE)
- if (timerIndex==TIMER20_INDEX) return 20;
- #endif
- #if defined(TIM21_BASE)
- if (timerIndex==TIMER21_INDEX) return 21;
- #endif
- #if defined(TIM22_BASE)
- if (timerIndex==TIMER22_INDEX) return 22;
- #endif
- return -1;
-}
-
-
-void printTimerCombination(int numPins, PinMap* timers[], int score) {
- for (int i=0; iperipheral)));
- SimpleFOCDebug::print("-CH");
- SimpleFOCDebug::print(STM_PIN_CHANNEL(timers[i]->function));
- if (STM_PIN_INVERTED(timers[i]->function))
- SimpleFOCDebug::print("N");
- }
- SimpleFOCDebug::print(" ");
- }
- SimpleFOCDebug::println("score: ", score);
-}
-
-#endif
-
#endif
diff --git a/src/drivers/hardware_specific/stm32/stm32_mcu.h b/src/drivers/hardware_specific/stm32/stm32_mcu.h
index 411c43b2..feee6ba2 100644
--- a/src/drivers/hardware_specific/stm32/stm32_mcu.h
+++ b/src/drivers/hardware_specific/stm32/stm32_mcu.h
@@ -1,14 +1,39 @@
-#ifndef STM32_DRIVER_MCU_DEF
-#define STM32_DRIVER_MCU_DEF
+#pragma once
+
#include "../../hardware_api.h"
-#if defined(_STM32_DEF_)
+#if defined(_STM32_DEF_) || defined(TARGET_STM32H7)
+// TARGET_M4 / TARGET_M7
+
+#ifndef SIMPLEFOC_STM32_MAX_TIMERSUSED
+#define SIMPLEFOC_STM32_MAX_TIMERSUSED 6
+#endif
+#ifndef SIMPLEFOC_STM32_MAX_TIMERSRESERVED
+#define SIMPLEFOC_STM32_MAX_TIMERSRESERVED 4
+#endif
+#ifndef SIMPLEFOC_STM32_MAX_MOTORSUSED
+#define SIMPLEFOC_STM32_MAX_MOTORSUSED 4
+#endif
+
-// default pwm parameters
-#define _PWM_RESOLUTION 12 // 12bit
-#define _PWM_RANGE 4095.0f // 2^12 -1 = 4095
-#define _PWM_FREQUENCY 25000 // 25khz
-#define _PWM_FREQUENCY_MAX 50000 // 50khz
+#ifndef SIMPLEFOC_STM32_DEBUG
+// comment me out to disable debug output
+#define SIMPLEFOC_STM32_DEBUG
+#endif
+
+#if defined(__MBED__)
+#define PinMap_TIM PinMap_PWM
+#define ALTX_MASK 0
+#endif
+
+
+/**
+ * No limits are placed on PWM frequency, so very fast or very slow frequencies can be set.
+ * A warning is displayed to debug if you get less than 8bit resolution for the PWM duty cycle.
+ * If no pwm_frequency is set, the default value is 25kHz.
+ */
+#define SIMPLEFOC_STM32_PWM_FREQUENCY 25000 // 25khz
+#define SIMPLEFOC_STM32_MIN_RESOLUTION 255
// 6pwm parameters
#define _HARDWARE_6PWM 1
@@ -17,19 +42,37 @@
typedef struct STM32DriverParams {
- HardwareTimer* timers[6] = {NULL};
+ TIM_HandleTypeDef* timers_handle[6] = {NULL};
uint32_t channels[6];
+ uint32_t llchannels[6];
long pwm_frequency;
+ uint8_t num_timers;
+ TIM_HandleTypeDef* master_timer = NULL;
float dead_zone;
uint8_t interface_type;
} STM32DriverParams;
-// timer synchornisation functions
-void _stopTimers(HardwareTimer **timers_to_stop, int timer_num=6);
-void _startTimers(HardwareTimer **timers_to_start, int timer_num=6);
-// timer query functions
-bool _getPwmState(void* params);
+// timer allocation functions
+int stm32_getNumTimersUsed();
+int stm32_getNumMotorsUsed();
+int stm32_getNumTimersReserved();
+STM32DriverParams* stm32_getMotorUsed(int index);
+bool stm32_isTimerUsed(TIM_HandleTypeDef* timer);
+bool stm32_isChannelUsed(PinMap* pin);
+bool stm32_isTimerReserved(TIM_TypeDef* timer);
+TIM_HandleTypeDef* stm32_getTimer(PinMap* timer);
+TIM_HandleTypeDef* stm32_useTimer(PinMap* timer);
+bool stm32_reserveTimer(TIM_TypeDef* timer);
+
+void stm32_pause(STM32DriverParams* params);
+void stm32_resume(STM32DriverParams* params);
+
+// // timer synchornisation functions
+// void _stopTimers(TIM_HandleTypeDef **timers_to_stop, int timer_num=6);
+// void _startTimers(TIM_HandleTypeDef **timers_to_start, int timer_num=6);
+
+// // timer query functions
+// bool _getPwmState(void* params);
-#endif
#endif
\ No newline at end of file
diff --git a/src/drivers/hardware_specific/stm32/stm32_searchtimers.cpp b/src/drivers/hardware_specific/stm32/stm32_searchtimers.cpp
new file mode 100644
index 00000000..e04fc719
--- /dev/null
+++ b/src/drivers/hardware_specific/stm32/stm32_searchtimers.cpp
@@ -0,0 +1,193 @@
+
+#include "./stm32_searchtimers.h"
+#include "./stm32_timerutils.h"
+
+#if defined(_STM32_DEF_) || defined(TARGET_STM32H7)
+
+
+
+/*
+ timer combination scoring function
+ assigns a score, and also checks the combination is valid
+ returns <0 if combination is invalid, >=0 if combination is valid. lower (but positive) score is better
+ for 6 pwm, hardware 6-pwm is preferred over software 6-pwm
+ hardware 6-pwm is possible if each low channel is the inverted counterpart of its high channel
+ inverted channels are not allowed except when using hardware 6-pwm (in theory they could be but lets not complicate things)
+*/
+int _stm32_scoreCombination(int numPins, PinMap* pinTimers[]) {
+ // check already used - TODO move this to outer loop also...
+ for (int i=0; ifunction))
+ return -3; // bad combination - inverted channel used in non-hardware 6pwm
+ }
+ }
+ // check for duplicated channels
+ for (int i=0; iperipheral == pinTimers[j]->peripheral
+ && STM_PIN_CHANNEL(pinTimers[i]->function) == STM_PIN_CHANNEL(pinTimers[j]->function)
+ && STM_PIN_INVERTED(pinTimers[i]->function) == STM_PIN_INVERTED(pinTimers[j]->function))
+ return -4; // bad combination - duplicated channel
+ }
+ }
+ int score = 0;
+ for (int i=0; iperipheral == pinTimers[j]->peripheral)
+ found = true;
+ }
+ if (!found) score++;
+ }
+ if (numPins==6) {
+ // check for inverted channels - best: 1 timer, 3 channels, 3 matching inverted channels
+ // >1 timer, 3 channels, 3 matching inverted channels
+ // 1 timer, 6 channels (no inverted channels)
+ // >1 timer, 6 channels (no inverted channels)
+ // check for inverted high-side channels
+ if (STM_PIN_INVERTED(pinTimers[0]->function) || STM_PIN_INVERTED(pinTimers[2]->function) || STM_PIN_INVERTED(pinTimers[4]->function))
+ return -5; // bad combination - inverted channel used on high-side channel
+ if (pinTimers[0]->peripheral == pinTimers[1]->peripheral
+ && pinTimers[2]->peripheral == pinTimers[3]->peripheral
+ && pinTimers[4]->peripheral == pinTimers[5]->peripheral
+ && STM_PIN_CHANNEL(pinTimers[0]->function) == STM_PIN_CHANNEL(pinTimers[1]->function)
+ && STM_PIN_CHANNEL(pinTimers[2]->function) == STM_PIN_CHANNEL(pinTimers[3]->function)
+ && STM_PIN_CHANNEL(pinTimers[4]->function) == STM_PIN_CHANNEL(pinTimers[5]->function)
+ && STM_PIN_INVERTED(pinTimers[1]->function) && STM_PIN_INVERTED(pinTimers[3]->function) && STM_PIN_INVERTED(pinTimers[5]->function)) {
+ // hardware 6pwm, score <10
+
+ // TODO F37xxx doesn't support dead-time insertion, it has no TIM1/TIM8
+ // F301, F302 --> 6 channels, but only 1-3 have dead-time insertion
+ // TIM2/TIM3/TIM4/TIM5 don't do dead-time insertion
+ // TIM15/TIM16/TIM17 do dead-time insertion only on channel 1
+
+ // TODO check these defines
+ #if defined(STM32F4xx_HAL_TIM_H) || defined(STM32F3xx_HAL_TIM_H) || defined(STM32F2xx_HAL_TIM_H) || defined(STM32F1xx_HAL_TIM_H) || defined(STM32F100_HAL_TIM_H) || defined(STM32FG0x1_HAL_TIM_H) || defined(STM32G0x0_HAL_TIM_H)
+ if (STM_PIN_CHANNEL(pinTimers[0]->function)>3 || STM_PIN_CHANNEL(pinTimers[2]->function)>3 || STM_PIN_CHANNEL(pinTimers[4]->function)>3 )
+ return -8; // channel 4 does not have dead-time insertion
+ #endif
+ #ifdef STM32G4xx_HAL_TIM_H
+ if (STM_PIN_CHANNEL(pinTimers[0]->function)>4 || STM_PIN_CHANNEL(pinTimers[2]->function)>4 || STM_PIN_CHANNEL(pinTimers[4]->function)>4 )
+ return -8; // channels 5 & 6 do not have dead-time insertion
+ #endif
+ }
+ else {
+ // check for inverted low-side channels
+ if (STM_PIN_INVERTED(pinTimers[1]->function) || STM_PIN_INVERTED(pinTimers[3]->function) || STM_PIN_INVERTED(pinTimers[5]->function))
+ return -6; // bad combination - inverted channel used on low-side channel in software 6-pwm
+ if (pinTimers[0]->peripheral != pinTimers[1]->peripheral
+ || pinTimers[2]->peripheral != pinTimers[3]->peripheral
+ || pinTimers[4]->peripheral != pinTimers[5]->peripheral)
+ return -7; // bad combination - non-matching timers for H/L side in software 6-pwm
+ score += 10; // software 6pwm, score >10
+ }
+ }
+ return score;
+}
+
+
+
+
+int _stm32_findIndexOfFirstPinMapEntry(int pin) {
+ PinName pinName = digitalPinToPinName(pin);
+ int i = 0;
+ while (PinMap_TIM[i].pin!=NC) {
+ if (pinName == PinMap_TIM[i].pin)
+ return i;
+ i++;
+ }
+ return -1;
+}
+
+
+int _stm32_findIndexOfLastPinMapEntry(int pin) {
+ PinName pinName = digitalPinToPinName(pin);
+ int i = 0;
+ while (PinMap_TIM[i].pin!=NC) {
+ if ( pinName == (PinMap_TIM[i].pin & ~ALTX_MASK)
+ && pinName != (PinMap_TIM[i+1].pin & ~ALTX_MASK))
+ return i;
+ i++;
+ }
+ return -1;
+}
+
+
+
+
+
+
+#define NOT_FOUND 1000
+
+int _stm32_findBestTimerCombination(int numPins, int index, int pins[], PinMap* pinTimers[]) {
+ PinMap* searchArray[6] = { NULL, NULL, NULL, NULL, NULL, NULL };
+ for (int j=0;j=0 && score= 0) {
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SimpleFOCDebug::print("STM32-DRV: best: ");
+ stm32_printTimerCombination(numPins, pinTimers, bestScore);
+ #endif
+ }
+ return bestScore;
+};
+
+
+
+
+
+#endif
+
diff --git a/src/drivers/hardware_specific/stm32/stm32_searchtimers.h b/src/drivers/hardware_specific/stm32/stm32_searchtimers.h
new file mode 100644
index 00000000..6001b637
--- /dev/null
+++ b/src/drivers/hardware_specific/stm32/stm32_searchtimers.h
@@ -0,0 +1,11 @@
+#pragma once
+
+#include "./stm32_mcu.h"
+
+#if defined(_STM32_DEF_) || defined(TARGET_STM32H7)
+
+
+int stm32_findBestTimerCombination(int numPins, int pins[], PinMap* pinTimers[]);
+
+
+#endif
diff --git a/src/drivers/hardware_specific/stm32/stm32_timerutils.cpp b/src/drivers/hardware_specific/stm32/stm32_timerutils.cpp
new file mode 100644
index 00000000..3eef0849
--- /dev/null
+++ b/src/drivers/hardware_specific/stm32/stm32_timerutils.cpp
@@ -0,0 +1,932 @@
+
+#include "./stm32_timerutils.h"
+#include
+
+#if defined(_STM32_DEF_) || defined(TARGET_STM32H7)
+
+
+void stm32_pauseTimer(TIM_HandleTypeDef* handle){
+ /* Disable timer unconditionally. Required to guarantee timer is stopped,
+ * even if some channels are still running */
+ LL_TIM_DisableCounter(handle->Instance);
+// handle->State = HAL_TIM_STATE_READY;
+ // on advanced control timers there is also the option of using the brake or the MOE?
+ // TIM1->EGR |= TIM_EGR_BG; // break generation
+}
+
+
+void stm32_resumeTimer(TIM_HandleTypeDef* handle){
+ LL_TIM_EnableCounter(handle->Instance);
+}
+
+
+void stm32_refreshTimer(TIM_HandleTypeDef* handle){
+ handle->Instance->EGR = TIM_EVENTSOURCE_UPDATE;
+}
+
+
+void stm32_pauseChannel(TIM_HandleTypeDef* handle, uint32_t llchannels){
+ LL_TIM_CC_DisableChannel(handle->Instance, llchannels);
+}
+
+
+void stm32_resumeChannel(TIM_HandleTypeDef* handle, uint32_t llchannels){
+ LL_TIM_CC_EnableChannel(handle->Instance, llchannels);
+}
+
+
+
+
+
+
+
+
+uint32_t stm32_setClockAndARR(TIM_HandleTypeDef* handle, uint32_t PWM_freq) {
+ // set the clock
+ uint32_t arr_value = 0;
+ uint32_t cycles = stm32_getTimerClockFreq(handle) / PWM_freq / 2;
+ uint32_t prescaler = (cycles / 0x10000) + 1; // TODO consider 32 bit timers
+ LL_TIM_SetPrescaler(handle->Instance, prescaler - 1);
+ uint32_t ticks = cycles / prescaler;
+ if (ticks > 0) {
+ arr_value = ticks - 1;
+ }
+ __HAL_TIM_SET_AUTORELOAD(handle, arr_value);
+ stm32_refreshTimer(handle);
+ // #ifdef SIMPLEFOC_STM32_DEBUG
+ // SIMPLEFOC_DEBUG("STM32-DRV: Timer clock: ", (int)stm32_getTimerClockFreq(handle));
+ // SIMPLEFOC_DEBUG("STM32-DRV: Timer prescaler: ", (int)prescaler);
+ // SIMPLEFOC_DEBUG("STM32-DRV: Timer ARR: ", (int)arr_value);
+ // #endif
+ return arr_value;
+}
+
+
+
+
+
+// setting pwm to hardware pin - instead analogWrite()
+void stm32_setPwm(TIM_HandleTypeDef *timer, uint32_t channel, uint32_t value) {
+ // value assumed to be in correct range
+ switch (channel) {
+ case 1: timer->Instance->CCR1 = value; break;
+ case 2: timer->Instance->CCR2 = value; break;
+ case 3: timer->Instance->CCR3 = value; break;
+ case 4: timer->Instance->CCR4 = value; break;
+ #ifdef LL_TIM_CHANNEL_CH5
+ case 5: timer->Instance->CCR5 = value; break;
+ #endif
+ #ifdef LL_TIM_CHANNEL_CH6
+ case 6: timer->Instance->CCR6 = value; break;
+ #endif
+ default: break;
+ }
+}
+
+
+uint32_t stm32_getHALChannel(uint32_t channel) {
+ uint32_t return_value;
+ switch (channel) {
+ case 1:
+ return_value = TIM_CHANNEL_1;
+ break;
+ case 2:
+ return_value = TIM_CHANNEL_2;
+ break;
+ case 3:
+ return_value = TIM_CHANNEL_3;
+ break;
+ case 4:
+ return_value = TIM_CHANNEL_4;
+ break;
+ #ifdef TIM_CHANNEL_5
+ case 5:
+ return_value = TIM_CHANNEL_5;
+ break;
+ #endif
+ #ifdef TIM_CHANNEL_6
+ case 6:
+ return_value = TIM_CHANNEL_6;
+ break;
+ #endif
+ default:
+ return_value = -1;
+ }
+ return return_value;
+}
+
+
+
+uint32_t stm32_getLLChannel(PinMap* timer) {
+#if defined(TIM_CCER_CC1NE)
+ if (STM_PIN_INVERTED(timer->function)) {
+ switch (STM_PIN_CHANNEL(timer->function)) {
+ case 1: return LL_TIM_CHANNEL_CH1N;
+ case 2: return LL_TIM_CHANNEL_CH2N;
+ case 3: return LL_TIM_CHANNEL_CH3N;
+#if defined(LL_TIM_CHANNEL_CH4N)
+ case 4: return LL_TIM_CHANNEL_CH4N;
+#endif
+ default: return -1;
+ }
+ } else
+#endif
+ {
+ switch (STM_PIN_CHANNEL(timer->function)) {
+ case 1: return LL_TIM_CHANNEL_CH1;
+ case 2: return LL_TIM_CHANNEL_CH2;
+ case 3: return LL_TIM_CHANNEL_CH3;
+ case 4: return LL_TIM_CHANNEL_CH4;
+ #ifdef LL_TIM_CHANNEL_CH5
+ case 5: return LL_TIM_CHANNEL_CH5;
+ #endif
+ #ifdef LL_TIM_CHANNEL_CH6
+ case 6: return LL_TIM_CHANNEL_CH6;
+ #endif
+ default: return -1;
+ }
+ }
+ return -1;
+}
+
+
+
+uint8_t stm32_countTimers(TIM_HandleTypeDef *timers[], uint8_t num_timers) {
+ uint8_t count = 1;
+ for (int i=1; iInstance;
+ #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
+ if (TIM_master == TIM1) return LL_TIM_TS_ITR0;// return TIM_TS_ITR0;
+ #endif
+ #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
+ else if (TIM_master == TIM2) return LL_TIM_TS_ITR1;//return TIM_TS_ITR1;
+ #endif
+ #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
+ else if (TIM_master == TIM3) return LL_TIM_TS_ITR2;//return TIM_TS_ITR2;
+ #endif
+ #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
+ else if (TIM_master == TIM4) return LL_TIM_TS_ITR3;//return TIM_TS_ITR3;
+ #endif
+ #if defined(TIM5) && defined(LL_TIM_TS_ITR4)
+ else if (TIM_master == TIM5) return LL_TIM_TS_ITR4;//return TIM_TS_ITR4;
+ #endif
+ #if defined(TIM8) && defined(LL_TIM_TS_ITR5)
+ else if (TIM_master == TIM8) return LL_TIM_TS_ITR5;//return TIM_TS_ITR5;
+ #endif
+ return -1;
+}
+#elif defined(STM32F4xx) || defined(STM32F1xx) || defined(STM32L4xx) || defined(STM32F7xx) || defined(TARGET_STM32H7)
+
+// function finds the appropriate timer source trigger for the master/slave timer combination
+// returns -1 if no trigger source is found
+// currently supports the master timers to be from TIM1 to TIM4 and TIM8
+int stm32_getInternalSourceTrigger(TIM_HandleTypeDef* master, TIM_HandleTypeDef* slave) {
+ // put master and slave in temp variables to avoid arrows
+ TIM_TypeDef *TIM_master = master->Instance;
+ TIM_TypeDef *TIM_slave = slave->Instance;
+ #if defined(TIM1) && defined(LL_TIM_TS_ITR0)
+ if (TIM_master == TIM1){
+ #if defined(TIM2)
+ if(TIM_slave == TIM2) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR0;
+ #endif
+ }
+ #endif
+ #if defined(TIM2) && defined(LL_TIM_TS_ITR1)
+ else if (TIM_master == TIM2){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM5) && !defined(TARGET_STM32H7)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR0;
+ #endif
+ }
+ #endif
+ #if defined(TIM3) && defined(LL_TIM_TS_ITR2)
+ else if (TIM_master == TIM3){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM2)
+ else if(TIM_slave == TIM2) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM5) && !defined(TARGET_STM32H7)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM5) && defined(TARGET_STM32H7)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR2;
+ #endif
+ }
+ #endif
+ #if defined(TIM4) && defined(LL_TIM_TS_ITR3)
+ else if (TIM_master == TIM4){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM2)
+ else if(TIM_slave == TIM2) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM8)
+ else if(TIM_slave == TIM8) return LL_TIM_TS_ITR2;
+ #endif
+ #if defined(TIM5) && !defined(TARGET_STM32H7)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM5) && defined(TARGET_STM32H7)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR3;
+ #endif
+ }
+ #endif
+ #if defined(TIM5)
+ else if (TIM_master == TIM5){
+ #if !defined(STM32L4xx) // only difference between F4,F1 and L4
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM3)
+ else if(TIM_slave == TIM3) return LL_TIM_TS_ITR2;
+ #endif
+ #endif
+ #if defined(TIM8)
+ if(TIM_slave == TIM8) return LL_TIM_TS_ITR3;
+ #endif
+ }
+ #endif
+ #if defined(TIM8)
+ else if (TIM_master == TIM8){
+ #if defined(TIM2)
+ if(TIM_slave==TIM2) return LL_TIM_TS_ITR1;
+ #endif
+ #if defined(TIM4)
+ else if(TIM_slave == TIM4) return LL_TIM_TS_ITR3;
+ #endif
+ #if defined(TIM5)
+ else if(TIM_slave == TIM5) return LL_TIM_TS_ITR3;
+ #endif
+ }
+ #endif
+ #if defined(TIM15) && defined(TARGET_STM32H7)
+ else if (TIM_master == TIM15){
+ #if defined(TIM1)
+ if(TIM_slave == TIM1) return LL_TIM_TS_ITR0;
+ #endif
+ #if defined(TIM3)
+ if(TIM_slave == TIM3) return LL_TIM_TS_ITR2;
+ #endif
+ }
+ #endif
+ return -1; // combination not supported
+}
+#else
+// Alignment not supported for this architecture
+int stm32_getInternalSourceTrigger(TIM_HandleTypeDef* master, TIM_HandleTypeDef* slave) {
+ return -1;
+}
+#endif
+
+
+
+
+
+// call with the timers used for a motor. The function will align the timers and
+// start them at the same time (if possible). Results of this function can be:
+// - success, no changes needed
+// - success, different timers aligned and started concurrently
+// - failure, cannot align timers
+// in each case, the timers are started.
+//
+// TODO: this topic is quite complex if we allow multiple motors and multiple timers per motor.
+// that's because the motors could potentially share the same timer. In this case aligning
+// the timers is problematic.
+// Even more problematic is stopping and resetting the timers. Even with a single motor,
+// this would cause problems and mis-align the PWM signals.
+// We can handle three cases:
+// - only one timer needed, no need to align
+// - master timer can be found, and timers used by only this motor: alignment possible
+// - TODO all timers for all motors can be aligned to one master: alignment possible
+// - otherwise, alignment not possible
+// frequency alignment is based on checking their pwm frequencies match.
+// pwm alignment is based on linking timers to start them at the same time, and making sure they are reset in sync.
+// On newer chips supporting it (STM32G4) we use gated + reset mode to start/stop only the master timer. Slaves
+// are started/stopped automatically with the master. TODO probably just using gated mode is better
+// On older chips (STM32F1) we used gated mode to start/stop the slave timers with the master, but have to take
+// care of the reset manually. TODO is it really needed to reset the timers?
+TIM_HandleTypeDef* stm32_alignTimers(TIM_HandleTypeDef *timers_in[], uint8_t num_timers_in) {
+ // find the timers used
+ TIM_HandleTypeDef *timers[6];
+ int numTimers = stm32_distinctTimers(timers_in, num_timers_in, timers);
+
+ // compare with the existing timers used for other motors...
+ for (int i=0; itimers_handle[k] == NULL) break;
+ if (params->timers_handle[k] == timers[i]) {
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: ERR: Timer already used by another motor: TIM", stm32_getTimerNumber(timers[i]->Instance));
+ #endif
+ // TODO handle this case, and make it a warning
+ // two sub-cases we could handle at the moment:
+ // - the other motor does not have a master timer, so we can initialize this motor without a master also
+ }
+ }
+ }
+ }
+
+
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SimpleFOCDebug::print("STM32-DRV: Synchronising ");
+ SimpleFOCDebug::print(numTimers);
+ SimpleFOCDebug::println(" timers");
+ #endif
+
+ // see if there is more then 1 timers used for the pwm
+ // if yes, try to align timers
+ if(numTimers > 1){
+ // find the master timer
+ int16_t master_index = -1;
+ int triggerEvent = -1;
+ for (int i=0; iInstance)) {
+ // check if timer already configured in TRGO update mode (used for ADC triggering)
+ // in that case we should not change its TRGO configuration
+ if(timers[i]->Instance->CR2 & LL_TIM_TRGO_UPDATE) continue;
+ // check if the timer has the supported internal trigger for other timers
+ for (int slave_i=0; slave_iInstance));
+ #endif
+ // make the master timer generate ITRGx event
+ // if it was already configured in slave mode, disable the slave mode on the master
+ LL_TIM_SetSlaveMode(timers[master_index]->Instance, LL_TIM_SLAVEMODE_DISABLED );
+ // Configure the master timer to send a trigger signal on enable
+ LL_TIM_SetTriggerOutput(timers[master_index]->Instance, LL_TIM_TRGO_ENABLE);
+ //LL_TIM_EnableMasterSlaveMode(timers[master_index]->Instance);
+
+ // configure other timers to get the input trigger from the master timer
+ for (int slave_index=0; slave_index < numTimers; slave_index++) {
+ if (slave_index == master_index)
+ continue;
+ #ifdef SIMPLEFOC_STM32_DEBUG
+ SIMPLEFOC_DEBUG("STM32-DRV: slave timer: TIM", stm32_getTimerNumber(timers[slave_index]->Instance));
+ #endif
+ // Configure the slave timer to be triggered by the master enable signal
+ uint32_t trigger = stm32_getInternalSourceTrigger(timers[master_index], timers[slave_index]);
+ // #ifdef SIMPLEFOC_STM32_DEBUG
+ // SIMPLEFOC_DEBUG("STM32-DRV: slave trigger ITR ", (int)trigger);
+ // #endif
+ LL_TIM_SetTriggerInput(timers[slave_index]->Instance, trigger);
+ // #if defined(STM32G4xx)
+ // LL_TIM_SetSlaveMode(timers[slave_index]->Instance, LL_TIM_SLAVEMODE_COMBINED_GATEDRESET);
+ // #else
+ LL_TIM_SetSlaveMode(timers[slave_index]->Instance, LL_TIM_SLAVEMODE_GATED);
+ // #endif
+ }
+ for (int i=0; iInstance->CNT);
+ }
+ stm32_resumeTimer(timers[master_index]);
+ return timers[master_index];
+ }
+ }
+
+ // if we had only one timer, or there was no master timer found
+ for (int i=0; iInstance);
+ uint64_t clkSelection = timerClkSrc == 1 ? RCC_PERIPHCLK_TIMG1 : RCC_PERIPHCLK_TIMG2;
+ return HAL_RCCEx_GetPeriphCLKFreq(clkSelection);
+#else
+ RCC_ClkInitTypeDef clkconfig = {};
+ uint32_t pFLatency = 0U;
+ uint32_t uwTimclock = 0U, uwAPBxPrescaler = 0U;
+
+ /* Get clock configuration */
+ HAL_RCC_GetClockConfig(&clkconfig, &pFLatency);
+ switch (getTimerClkSrc(handle->Instance)) {
+ case 1:
+ uwAPBxPrescaler = clkconfig.APB1CLKDivider;
+ uwTimclock = HAL_RCC_GetPCLK1Freq();
+ break;
+#if !defined(STM32C0xx) && !defined(STM32F0xx) && !defined(STM32G0xx)
+ case 2:
+ uwAPBxPrescaler = clkconfig.APB2CLKDivider;
+ uwTimclock = HAL_RCC_GetPCLK2Freq();
+ break;
+#endif
+ default:
+ case 0: // Unknown timer clock source
+ return 0;
+ }
+
+#if defined(STM32H7xx) || defined(TARGET_STM32H7)
+ /* When TIMPRE bit of the RCC_CFGR register is reset,
+ * if APBx prescaler is 1 or 2 then TIMxCLK = HCLK,
+ * otherwise TIMxCLK = 2x PCLKx.
+ * When TIMPRE bit in the RCC_CFGR register is set,
+ * if APBx prescaler is 1,2 or 4, then TIMxCLK = HCLK,
+ * otherwise TIMxCLK = 4x PCLKx
+ */
+ RCC_PeriphCLKInitTypeDef PeriphClkConfig = {};
+ HAL_RCCEx_GetPeriphCLKConfig(&PeriphClkConfig);
+
+ if (PeriphClkConfig.TIMPresSelection == RCC_TIMPRES_ACTIVATED) {
+ switch (uwAPBxPrescaler) {
+ default:
+ case RCC_APB1_DIV1:
+ case RCC_APB1_DIV2:
+ case RCC_APB1_DIV4:
+ /* case RCC_APB2_DIV1: */
+ case RCC_APB2_DIV2:
+ case RCC_APB2_DIV4:
+ /* Note: in such cases, HCLK = (APBCLK * DIVx) */
+ uwTimclock = HAL_RCC_GetHCLKFreq();
+ break;
+ case RCC_APB1_DIV8:
+ case RCC_APB1_DIV16:
+ case RCC_APB2_DIV8:
+ case RCC_APB2_DIV16:
+ uwTimclock *= 4;
+ break;
+ }
+ } else {
+ switch (uwAPBxPrescaler) {
+ default:
+ case RCC_APB1_DIV1:
+ case RCC_APB1_DIV2:
+ /* case RCC_APB2_DIV1: */
+ case RCC_APB2_DIV2:
+ /* Note: in such cases, HCLK = (APBCLK * DIVx) */
+ uwTimclock = HAL_RCC_GetHCLKFreq();
+ break;
+ case RCC_APB1_DIV4:
+ case RCC_APB1_DIV8:
+ case RCC_APB1_DIV16:
+ case RCC_APB2_DIV4:
+ case RCC_APB2_DIV8:
+ case RCC_APB2_DIV16:
+ uwTimclock *= 2;
+ break;
+ }
+ }
+#else
+ /* When TIMPRE bit of the RCC_DCKCFGR register is reset,
+ * if APBx prescaler is 1, then TIMxCLK = PCLKx,
+ * otherwise TIMxCLK = 2x PCLKx.
+ * When TIMPRE bit in the RCC_DCKCFGR register is set,
+ * if APBx prescaler is 1,2 or 4, then TIMxCLK = HCLK,
+ * otherwise TIMxCLK = 4x PCLKx
+ */
+#if defined(STM32F4xx) || defined(STM32F7xx)
+#if !defined(STM32F405xx) && !defined(STM32F415xx) &&\
+ !defined(STM32F407xx) && !defined(STM32F417xx)
+ RCC_PeriphCLKInitTypeDef PeriphClkConfig = {};
+ HAL_RCCEx_GetPeriphCLKConfig(&PeriphClkConfig);
+
+ if (PeriphClkConfig.TIMPresSelection == RCC_TIMPRES_ACTIVATED)
+ switch (uwAPBxPrescaler) {
+ default:
+ case RCC_HCLK_DIV1:
+ case RCC_HCLK_DIV2:
+ case RCC_HCLK_DIV4:
+ /* Note: in such cases, HCLK = (APBCLK * DIVx) */
+ uwTimclock = HAL_RCC_GetHCLKFreq();
+ break;
+ case RCC_HCLK_DIV8:
+ case RCC_HCLK_DIV16:
+ uwTimclock *= 4;
+ break;
+ } else
+#endif
+#endif
+ switch (uwAPBxPrescaler) {
+ default:
+ case RCC_HCLK_DIV1:
+ // uwTimclock*=1;
+ break;
+ case RCC_HCLK_DIV2:
+ case RCC_HCLK_DIV4:
+ case RCC_HCLK_DIV8:
+ case RCC_HCLK_DIV16:
+ uwTimclock *= 2;
+ break;
+ }
+#endif /* STM32H7xx */
+ return uwTimclock;
+#endif /* STM32MP1xx */
+}
+
+
+
+
+
+
+
+#if defined(__MBED__)
+
+void enableTimerClock(TIM_HandleTypeDef *htim) {
+ // Enable TIM clock
+#if defined(TIM1_BASE)
+ if (htim->Instance == TIM1) {
+ __HAL_RCC_TIM1_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM2_BASE)
+ if (htim->Instance == TIM2) {
+ __HAL_RCC_TIM2_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM3_BASE)
+ if (htim->Instance == TIM3) {
+ __HAL_RCC_TIM3_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM4_BASE)
+ if (htim->Instance == TIM4) {
+ __HAL_RCC_TIM4_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM5_BASE)
+ if (htim->Instance == TIM5) {
+ __HAL_RCC_TIM5_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM6_BASE)
+ if (htim->Instance == TIM6) {
+ __HAL_RCC_TIM6_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM7_BASE)
+ if (htim->Instance == TIM7) {
+ __HAL_RCC_TIM7_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM8_BASE)
+ if (htim->Instance == TIM8) {
+ __HAL_RCC_TIM8_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM9_BASE)
+ if (htim->Instance == TIM9) {
+ __HAL_RCC_TIM9_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM10_BASE)
+ if (htim->Instance == TIM10) {
+ __HAL_RCC_TIM10_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM11_BASE)
+ if (htim->Instance == TIM11) {
+ __HAL_RCC_TIM11_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM12_BASE)
+ if (htim->Instance == TIM12) {
+ __HAL_RCC_TIM12_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM13_BASE)
+ if (htim->Instance == TIM13) {
+ __HAL_RCC_TIM13_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM14_BASE)
+ if (htim->Instance == TIM14) {
+ __HAL_RCC_TIM14_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM15_BASE)
+ if (htim->Instance == TIM15) {
+ __HAL_RCC_TIM15_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM16_BASE)
+ if (htim->Instance == TIM16) {
+ __HAL_RCC_TIM16_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM17_BASE)
+ if (htim->Instance == TIM17) {
+ __HAL_RCC_TIM17_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM18_BASE)
+ if (htim->Instance == TIM18) {
+ __HAL_RCC_TIM18_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM19_BASE)
+ if (htim->Instance == TIM19) {
+ __HAL_RCC_TIM19_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM20_BASE)
+ if (htim->Instance == TIM20) {
+ __HAL_RCC_TIM20_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM21_BASE)
+ if (htim->Instance == TIM21) {
+ __HAL_RCC_TIM21_CLK_ENABLE();
+ }
+#endif
+#if defined(TIM22_BASE)
+ if (htim->Instance == TIM22) {
+ __HAL_RCC_TIM22_CLK_ENABLE();
+ }
+#endif
+}
+
+
+uint8_t getTimerClkSrc(TIM_TypeDef *tim) {
+ uint8_t clkSrc = 0;
+
+ if (tim != (TIM_TypeDef *)NC)
+#if defined(STM32C0xx) || defined(STM32F0xx) || defined(STM32G0xx)
+ /* TIMx source CLK is PCKL1 */
+ clkSrc = 1;
+#else
+ {
+ if (
+ #if defined(TIM2_BASE)
+ tim == TIM2 ||
+ #endif
+ #if defined(TIM3_BASE)
+ tim == TIM3 ||
+ #endif
+ #if defined(TIM4_BASE)
+ tim == TIM4 ||
+ #endif
+ #if defined(TIM5_BASE)
+ tim == TIM5 ||
+ #endif
+ #if defined(TIM6_BASE)
+ tim == TIM6 ||
+ #endif
+ #if defined(TIM7_BASE)
+ tim == TIM7 ||
+ #endif
+ #if defined(TIM12_BASE)
+ tim == TIM12 ||
+ #endif
+ #if defined(TIM13_BASE)
+ tim == TIM13 ||
+ #endif
+ #if defined(TIM14_BASE)
+ tim == TIM14 ||
+ #endif
+ #if defined(TIM18_BASE)
+ tim == TIM18 ||
+ #endif
+ false)
+ clkSrc = 1;
+ else
+ if (
+ #if defined(TIM1_BASE)
+ tim == TIM1 ||
+ #endif
+ #if defined(TIM8_BASE)
+ tim == TIM8 ||
+ #endif
+ #if defined(TIM9_BASE)
+ tim == TIM9 ||
+ #endif
+ #if defined(TIM10_BASE)
+ tim == TIM10 ||
+ #endif
+ #if defined(TIM11_BASE)
+ tim == TIM11 ||
+ #endif
+ #if defined(TIM15_BASE)
+ tim == TIM15 ||
+ #endif
+ #if defined(TIM16_BASE)
+ tim == TIM16 ||
+ #endif
+ #if defined(TIM17_BASE)
+ tim == TIM17 ||
+ #endif
+ #if defined(TIM19_BASE)
+ tim == TIM19 ||
+ #endif
+ #if defined(TIM20_BASE)
+ tim == TIM20 ||
+ #endif
+ #if defined(TIM21_BASE)
+ tim == TIM21 ||
+ #endif
+ #if defined(TIM22_BASE)
+ tim == TIM22 ||
+ #endif
+ false )
+ clkSrc = 2;
+ else
+ return 0;
+ }
+#endif
+ return clkSrc;
+}
+
+#endif
+
+
+
+
+
+
+
+
+#ifdef SIMPLEFOC_STM32_DEBUG
+
+/*
+ some utility functions to print out the timer combinations
+*/
+
+int stm32_getTimerNumber(TIM_TypeDef *instance) {
+ #if defined(TIM1_BASE)
+ if (instance==TIM1) return 1;
+ #endif
+ #if defined(TIM2_BASE)
+ if (instance==TIM2) return 2;
+ #endif
+ #if defined(TIM3_BASE)
+ if (instance==TIM3) return 3;
+ #endif
+ #if defined(TIM4_BASE)
+ if (instance==TIM4) return 4;
+ #endif
+ #if defined(TIM5_BASE)
+ if (instance==TIM5) return 5;
+ #endif
+ #if defined(TIM6_BASE)
+ if (instance==TIM6) return 6;
+ #endif
+ #if defined(TIM7_BASE)
+ if (instance==TIM7) return 7;
+ #endif
+ #if defined(TIM8_BASE)
+ if (instance==TIM8) return 8;
+ #endif
+ #if defined(TIM9_BASE)
+ if (instance==TIM9) return 9;
+ #endif
+ #if defined(TIM10_BASE)
+ if (instance==TIM10) return 10;
+ #endif
+ #if defined(TIM11_BASE)
+ if (instance==TIM11) return 11;
+ #endif
+ #if defined(TIM12_BASE)
+ if (instance==TIM12) return 12;
+ #endif
+ #if defined(TIM13_BASE)
+ if (instance==TIM13) return 13;
+ #endif
+ #if defined(TIM14_BASE)
+ if (instance==TIM14) return 14;
+ #endif
+ #if defined(TIM15_BASE)
+ if (instance==TIM15) return 15;
+ #endif
+ #if defined(TIM16_BASE)
+ if (instance==TIM16) return 16;
+ #endif
+ #if defined(TIM17_BASE)
+ if (instance==TIM17) return 17;
+ #endif
+ #if defined(TIM18_BASE)
+ if (instance==TIM18) return 18;
+ #endif
+ #if defined(TIM19_BASE)
+ if (instance==TIM19) return 19;
+ #endif
+ #if defined(TIM20_BASE)
+ if (instance==TIM20) return 20;
+ #endif
+ #if defined(TIM21_BASE)
+ if (instance==TIM21) return 21;
+ #endif
+ #if defined(TIM22_BASE)
+ if (instance==TIM22) return 22;
+ #endif
+ return -1;
+}
+
+
+void stm32_printTimerCombination(int numPins, PinMap* timers[], int score) {
+ for (int i=0; iperipheral));
+ SimpleFOCDebug::print("-CH");
+ SimpleFOCDebug::print(STM_PIN_CHANNEL(timers[i]->function));
+ if (STM_PIN_INVERTED(timers[i]->function))
+ SimpleFOCDebug::print("N");
+ }
+ SimpleFOCDebug::print(" ");
+ }
+ SimpleFOCDebug::println("score: ", score);
+}
+
+#endif
+
+
+#endif
diff --git a/src/drivers/hardware_specific/stm32/stm32_timerutils.h b/src/drivers/hardware_specific/stm32/stm32_timerutils.h
new file mode 100644
index 00000000..3ba1c558
--- /dev/null
+++ b/src/drivers/hardware_specific/stm32/stm32_timerutils.h
@@ -0,0 +1,33 @@
+
+#pragma once
+
+#include "./stm32_mcu.h"
+
+#if defined(_STM32_DEF_) || defined(TARGET_STM32H7)
+
+void stm32_pauseTimer(TIM_HandleTypeDef* handle);
+void stm32_resumeTimer(TIM_HandleTypeDef* handle);
+void stm32_refreshTimer(TIM_HandleTypeDef* handle);
+void stm32_pauseChannel(TIM_HandleTypeDef* handle, uint32_t llchannels);
+void stm32_resumeChannel(TIM_HandleTypeDef* handle, uint32_t llchannels);
+uint32_t stm32_setClockAndARR(TIM_HandleTypeDef* handle, uint32_t PWM_freq);
+uint8_t stm32_countTimers(TIM_HandleTypeDef *timers[], uint8_t num_timers);
+uint8_t stm32_distinctTimers(TIM_HandleTypeDef* timers_in[], uint8_t num_timers, TIM_HandleTypeDef* timers_out[]);
+uint32_t stm32_getHALChannel(uint32_t channel);
+uint32_t stm32_getLLChannel(PinMap* timer);
+int stm32_getInternalSourceTrigger(TIM_HandleTypeDef* master, TIM_HandleTypeDef* slave);
+TIM_HandleTypeDef* stm32_alignTimers(TIM_HandleTypeDef *timers_in[], uint8_t num_timers_in);
+void stm32_setPwm(TIM_HandleTypeDef *timer, uint32_t channel, uint32_t value);
+uint32_t stm32_getTimerClockFreq(TIM_HandleTypeDef* handle);
+
+#if defined(__MBED__)
+void enableTimerClock(TIM_HandleTypeDef *htim);
+uint8_t getTimerClkSrc(TIM_TypeDef *tim);
+#endif
+
+#if defined(SIMPLEFOC_STM32_DEBUG)
+void stm32_printTimerCombination(int numPins, PinMap* timers[], int score);
+int stm32_getTimerNumber(TIM_TypeDef *instance);
+#endif
+
+#endif
diff --git a/src/sensors/Encoder.h b/src/sensors/Encoder.h
index af6a5ab6..ab494d13 100644
--- a/src/sensors/Encoder.h
+++ b/src/sensors/Encoder.h
@@ -68,7 +68,7 @@ class Encoder: public Sensor{
/**
* returns 0 if it does need search for absolute zero
* 0 - encoder without index
- * 1 - ecoder with index
+ * 1 - encoder with index
*/
int needsSearch() override;