Page 1 of 1

PWM not working on STM32F401CEU6

Posted: Sun Jan 26, 2025 12:58 pm
by Blank
Hi, I am trying to make a project to drive ESCs for a drone, for the same I am trying to generate PWM pulses using the STM32 TIM2_CHx, but it does not seem to work as my ESCs are not responding.

My code is as below
===============================================================================================================================
#include <libmaple/scb.h>
uint32_t loop_timer,now, receiver_input1, receiver_input1_previous,systick_counter;;
uint8_t int_flag;

void setup() {
pinMode(PA5,PWM); //PA5 seems to be the PIN for TIM2_CH1 as per the datasheet.
//all the needed registers are initialized.
TIMER2_BASE->CR1 = TIMER_CR1_CEN|TIMER_CR1_ARPE;
TIMER2_BASE->CR2 = 0;
TIMER2_BASE->SMCR = 0;
TIMER2_BASE->DIER = 0;
TIMER2_BASE->EGR = 0;
TIMER2_BASE->CCMR1 = (0b110 << 4) | TIMER_CCMR1_OC1PE;
TIMER2_BASE->CCMR2 =0;
TIMER2_BASE->PSC = 84; // Pre-scaler is set to 84 as processor clock is 84Mhz, so I can get 84/84 = 1Mhz for the timer
TIMER2_BASE->ARR = 5000;
TIMER2_BASE->DCR = 0;
TIMER2_BASE->CCR1 = 1000;
Serial.begin(57600);
attachInterrupt(PB10, ch1, CHANGE); // interrupt routine for detecting the receiver input pulse (this part is working)
// put your setup code here, to run once:

}

void loop() {
loop_timer = micros()+4000; // software reset of the timer to keep program loop at 250Hz
TIMER2_BASE->CNT = 5000;
// Flight Controller Code Start
TIMER2_BASE->CCR1 = receiver_input1; //storing the receiver input in the Capture Compare Register 1
Serial.println(receiver_input1);
// Flight Controller Code End
while(loop_timer > micros());
}

void ch1(){

systick_counter = SYSTICK_BASE->VAL;
if (0b1 & SCB_BASE->ICSR >> 26){
int_flag =1;
systick_counter = SYSTICK_BASE->VAL;
}
else int_flag = 0;

now = (systick_uptime_millis * 1000) + (SYSTICK_RELOAD_VAL + 1 - systick_counter) / CYCLES_PER_MICROSECOND;
if (int_flag)now += 1000;

if(0B1 & GPIOB_BASE->IDR >> 10)receiver_input1_previous = now;
else receiver_input1 = now - receiver_input1_previous;
}
==============================================================================================================================

Maybe I am missing something, Do I have to enable the DTG register for output ?

PS: The code compiles without errors, and the ESCs are working with an Arduino.

Thank you for the help :)

Re: PWM not working on STM32F401CEU6

Posted: Sun Jan 26, 2025 1:45 pm
by ag123
if you are using Arduino_Core_STM32
https://github.com/stm32duino/Arduino_Core_STM32/wiki
https://github.com/stm32duino/Arduino_Core_STM32/

you can try using the HardwareTimer
https://github.com/stm32duino/Arduino_C ... er-library
e.g.

Code: Select all

HardwareTimer *MyTim = new HardwareTimer(TIM2); 

// blink the led
void timer_callback() {
	digitalWrite(LED_BUILTIN, ! digitalRead(LED_BUILTIN));
}

void setup() {
	uint8_t channel = 1;	
	pinMode(LED_BUILTIN, OUTPUT);
	
	/* this set of commands configure PWM output 1 Mhz, 50% duty cycle on pin PA5 */
	MyTim->pause();	
	MyTim->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, PA5); // this has to be a valid timer output pin
	MyTim->setOverflow(200, HERTZ_FORMAT); //200 hz
	MyTim->setCaptureCompare(channel, 128, RESOLUTION_8B_COMPARE_FORMAT); // used for Dutycycle: [0.. 255], so 128 ~ 50% duty cycle
	MyTim->attachInterrupt(timer_callback); // once per period, update event
	MyTim->attachInterrupt(channel, timer_callback); // at the CCR capture compare (i.e. PWM, falling) edge 
	MyTim->refresh();
	MyTim->resume();
	
	Serial.begin();
}

void loop() {
	/* well nothing here because the hardware timer does PWM on its own, it is a hardware timer ;) */
	delay(100);
}
personally, I prefer to use ticks, i.e. you need to know the prescalers, peripheral clock freq, registers, how it works etc, but above is 'convenient' without really knowing / studying the hardware.

more examples are here:
https://github.com/stm32duino/STM32Exam ... dwareTimer

in libmaple, it is quite similar
http://static.leaflabs.com/pub/leaflabs ... dwaretimer
https://github.com/leaflabs/leaflabs-do ... etimer.rst

the built-in API doesn't do everything that HardwareTimer has, for those, you can update the registers if you want.

oh and if you are operating at > a few 100 khz speeds/frequencies (about 500khz max), don't bother with attachInterrupt(), the interrupts can't catch up to respond in time. e.g. it can't call your ISR callback function in time.

stm32duino is the internet's 'forgotten' treasure to play with things like stm32 hardware timers, that api is practically 'high level'.

if you are using stm32f411ceu 'blackpill' boards
https://stm32-base.org/boards/STM32F411 ... -V2.0.html
https://github.com/WeActStudio/WeActStu ... iSTM32F4x1

libmaple has usb serial. i.e. Serial() goes to your virtual com port.
for 'official' stm core (Arduino_Core_STM32), select USB (CDC) Serial as your serial port, and you get your virtual com port.
'baud rates' are more like 1 Mbps, because it is usb full speed 12 Mbps (max bandwidth).