@@ -657,22 +657,22 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
657
657
}
658
658
659
659
660
-
661
-
662
660
#include " stm32g4xx_hal.h"
663
661
#include " stm32g4xx_hal_gpio.h"
664
662
#include " stm32g4xx_hal_tim.h"
665
663
#include " stm32g4xx_hal_tim_ex.h"
666
664
665
+
666
+
667
+
667
668
// Declare timer handles for TIM1 and TIM8
668
669
TIM_HandleTypeDef htim1;
669
670
TIM_HandleTypeDef htim8;
670
671
671
672
// Function to configure PWM output on TIM1 channels 1-6 and TIM8 channel 1
672
- void configure8PWM (void )
673
- {
674
- // Initialize HAL library
675
- HAL_Init ();
673
+ void * _configure8PWM (long pwm_frequency, float dead_zone)
674
+ {
675
+
676
676
677
677
// GPIO pin initialization struct
678
678
GPIO_InitTypeDef GPIO_InitStruct = {0 };
@@ -771,6 +771,34 @@ void configure8PWM(void)
771
771
HAL_TIM_PWM_Start (&htim1, LL_TIM_CHANNEL_CH3N);
772
772
HAL_TIM_PWM_Start (&htim8, LL_TIM_CHANNEL_CH2);
773
773
HAL_TIM_PWM_Start (&htim8, LL_TIM_CHANNEL_CH2N);
774
+
775
+
776
+
777
+ TIM1->CR1 |= TIM_CR1_ARPE; // Auto-reload preload enable
778
+ TIM1->CR1 &= ~TIM_CR1_DIR; // Up counting mode
779
+ TIM1->CCMR1 |= TIM_CCMR1_OC1PE | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2; // PWM mode 1 on OC1
780
+ TIM1->CCER |= TIM_CCER_CC1E; // Enable output on OC1
781
+ TIM1->PSC = 0 ; // Set prescaler to 0
782
+ TIM1->ARR = (SystemCoreClock / (38000 * 2 )) - 1 ; // Set auto-reload value for 38kHz frequency
783
+ TIM1->CCR1 = (SystemCoreClock / (38000 * 2 )) / 2 ; // Set duty cycle to 50%
784
+ TIM1->BDTR |= TIM_BDTR_MOE; // Main output enable
785
+
786
+ TIM8->CR1 |= TIM_CR1_ARPE; // Auto-reload preload enable
787
+ TIM8->CR1 &= ~TIM_CR1_DIR; // Up counting mode
788
+ TIM8->CCMR1 |= TIM_CCMR1_OC1PE | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2; // PWM mode 1 on OC1
789
+ TIM8->CCER |= TIM_CCER_CC1E; // Enable output on OC1
790
+ TIM8->PSC = 0 ; // Set prescaler to 0
791
+ TIM8->ARR = (SystemCoreClock / (38000 * 2 )) - 1 ; // Set auto-reload value for 38kHz frequency
792
+ TIM8->CCR1 = (SystemCoreClock / (38000 * 2 )) / 2 ; // Set duty cycle to 50%
793
+ TIM8->BDTR |= TIM_BDTR_MOE; // Main output enable
794
+
795
+ // Set initial dead time value
796
+ TIM1->BDTR |= (uint32_t )(50 / 11.9 );
797
+
798
+
799
+ return NULL ;
800
+
801
+
774
802
}
775
803
776
804
@@ -823,20 +851,79 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, vo
823
851
_setPwm (((STM32DriverParams*)params)->timers [3 ], ((STM32DriverParams*)params)->channels [3 ], _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
824
852
}
825
853
826
- // function setting the pwm duty cycle to the hardware
827
- // - Stepper motor - 8PWM setting
828
- // - hardware specific
829
- void _writeDutyCycle8PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, float dc_3a, float dc_3b, float dc_4a, float dc_4b, void * params) {
830
- // transform duty cycle from [0,1] to [0,4095]
831
- _setPwm (((STM32DriverParams*)params)->timers [0 ], ((STM32DriverParams*)params)->channels [0 ], _PWM_RANGE * dc_1a, _PWM_RESOLUTION);
832
- _setPwm (((STM32DriverParams*)params)->timers [1 ], ((STM32DriverParams*)params)->channels [1 ], _PWM_RANGE * dc_1b, _PWM_RESOLUTION);
833
- _setPwm (((STM32DriverParams*)params)->timers [2 ], ((STM32DriverParams*)params)->channels [2 ], _PWM_RANGE * dc_2a, _PWM_RESOLUTION);
834
- _setPwm (((STM32DriverParams*)params)->timers [3 ], ((STM32DriverParams*)params)->channels [3 ], _PWM_RANGE * dc_2b, _PWM_RESOLUTION);
835
- _setPwm (((STM32DriverParams*)params)->timers [4 ], ((STM32DriverParams*)params)->channels [4 ], _PWM_RANGE * dc_3a, _PWM_RESOLUTION);
836
- _setPwm (((STM32DriverParams*)params)->timers [5 ], ((STM32DriverParams*)params)->channels [5 ], _PWM_RANGE * dc_3b, _PWM_RESOLUTION);
837
- _setPwm (((STM32DriverParams*)params)->timers [6 ], ((STM32DriverParams*)params)->channels [6 ], _PWM_RANGE * dc_4a, _PWM_RESOLUTION);
838
- _setPwm (((STM32DriverParams*)params)->timers [7 ], ((STM32DriverParams*)params)->channels [7 ], _PWM_RANGE * dc_4b, _PWM_RESOLUTION);
839
- }
854
+
855
+
856
+
857
+ class EightPWMParams {
858
+ public:
859
+ int period;
860
+ TIM_HandleTypeDef tim1_handle;
861
+ TIM_HandleTypeDef tim8_handle;
862
+
863
+ // Public members and methods go here
864
+ };
865
+
866
+ struct EightPWMConfig {
867
+ uint16_t freq; // PWM frequency in Hz
868
+ float duty_cycle_max; // Maximum duty cycle as a fraction of the period (0.0 to 1.0)
869
+ };
870
+
871
+
872
+ // Scale duty cycles to the PWM period
873
+ class EightPWM {
874
+ public:
875
+ EightPWM (int period, TIM_HandleTypeDef tim1_handle, TIM_HandleTypeDef tim8_handle)
876
+ : period(period), tim1_handle(tim1_handle), tim8_handle(tim8_handle) {}
877
+
878
+ void writeDutyCycle (float duty_cycle1A_h1, float duty_cycle1A_h2, float duty_cycle1B_h1, float duty_cycle1B_h2,
879
+ float duty_cycle2A_h1, float duty_cycle2A_h2, float duty_cycle2B_h1, float duty_cycle2B_h2) {
880
+
881
+ // Scale duty cycles to the PWM period
882
+ uint16_t duty1A_h1 = (uint16_t )(duty_cycle1A_h1 * period);
883
+ uint16_t duty1A_h2 = (uint16_t )(duty_cycle1A_h2 * period);
884
+ uint16_t duty1B_h1 = (uint16_t )(duty_cycle1B_h1 * period);
885
+ uint16_t duty1B_h2 = (uint16_t )(duty_cycle1B_h2 * period);
886
+ uint16_t duty2A_h1 = (uint16_t )(duty_cycle2A_h1 * period);
887
+ uint16_t duty2A_h2 = (uint16_t )(duty_cycle2A_h2 * period);
888
+ uint16_t duty2B_h1 = (uint16_t )(duty_cycle2B_h1 * period);
889
+ uint16_t duty2B_h2 = (uint16_t )(duty_cycle2B_h2 * period);
890
+
891
+ // Set duty cycles for TIM1 channels
892
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH1, duty1A_h1);
893
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH1N, duty1A_h2);
894
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH2, duty1B_h1);
895
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH2N, duty1B_h2);
896
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH3, duty2A_h1);
897
+ __HAL_TIM_SET_COMPARE (&tim1_handle, LL_TIM_CHANNEL_CH3N, duty2A_h2);
898
+
899
+ // Set duty cycles for TIM8 channels
900
+ __HAL_TIM_SET_COMPARE (&tim8_handle, LL_TIM_CHANNEL_CH2, duty2B_h1);
901
+ __HAL_TIM_SET_COMPARE (&tim8_handle, LL_TIM_CHANNEL_CH2N, duty2B_h2);
902
+
903
+ // Enable PWM outputs
904
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH1);
905
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH1);
906
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH1N);
907
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH1N);
908
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH2);
909
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH2);
910
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH2N);
911
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH2N);
912
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH3);
913
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH3);
914
+ HAL_TIM_PWM_Start (&tim1_handle, LL_TIM_CHANNEL_CH3N);
915
+ HAL_TIMEx_PWMN_Start (&tim1_handle, LL_TIM_CHANNEL_CH3N);
916
+ HAL_TIM_PWM_Start (&tim8_handle, LL_TIM_CHANNEL_CH2);
917
+ HAL_TIMEx_PWMN_Start (&tim8_handle, LL_TIM_CHANNEL_CH2);
918
+ HAL_TIM_PWM_Start (&tim8_handle, LL_TIM_CHANNEL_CH2N);
919
+ HAL_TIMEx_PWMN_Start (&tim8_handle, LL_TIM_CHANNEL_CH2N);
920
+ }
921
+
922
+ private:
923
+ int period;
924
+ TIM_HandleTypeDef tim1_handle;
925
+ TIM_HandleTypeDef tim8_handle;
926
+ };
840
927
841
928
842
929
// Configuring PWM frequency, resolution and alignment
0 commit comments