User LED and Fault LED both getting PWMed

I’m encountering some strange behavior when I try to run my setup in open loop. Here are my two previous threads about separate, but maybe related problems: Thread 1, Thread 2.

Here’s my motor setup:

//BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int en = NOT_SET);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB1, PB5);

One obvious problem would be one of these pins being shared with the User LED, but the LED is on PA5, which should not be shared. Here is a video of the strange behavior. The User LED and Fault LED’s PWM speed is proportional to the target speed set over serial. e.g. if the target speed is 0, the LEDs do not PWM. If the target speed is 1, the LEDs complete a full cycle about every four seconds. If the target speed is 4, they complete a full cycle about every second.

All the motor pins are on Timer 1 in PeripheralPins.c, and PA5 is on Timer 3.

@Owen_Williams I wonder if I could pick you brain about this for a second?

What does it mean for PA9 to be defined as 8 here? Is 8 the actual pin number on the MCU?

If so, maybe I have found a problem because STM32CubeMX shows PA9 to be pin 42. There are other discrepancies between pins as well.


Edit: Ok, I think I have figured out that the numbers those definitions map to are an abstraction based on the Arduino pins, then adding the rest of the STM32 pins. Unfortunately, I am not any closer to understanding what the problem is – why the user LED and fault LED are PWMing, and why the motor controller is not getting the correct signals.


Edit 2: I realized maybe the pins need to be referenced this way:

BLDCDriver6PWM driver = BLDCDriver6PWM(PA_8, PB_13, PA_9, PB_14, PA_10, PB_1, PB_5);

I tried that, and partial success! The User LED and fault LED have stopped PWMing. The motor driver is still not getting the correct signals though. I’m continuing to tinker with it.

Ok, now I feel like I’m going crazy. This pinout is giving me so much trouble. I put a multimeter on each of the pins on the CN10 header for several different motor instantiations, and nothing is making sense.

I was apparently wrong above because for this motor instantiation:

BLDCDriver6PWM driver = BLDCDriver6PWM(PA_8, PB_13, PA_9, PB_14, PA_10, PB_1, PB_5);

no pins at all PWM.


For this motor instantiation:

BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB1, PB5);

The pins behave this way: (Note: bolded voltages are PWMing)

Pin Role Voltage Pin Pin Voltage Pin Role
IO_BEFM 1 2
3 4
5 6
3.3V 7 8 5V
GND GND 9 10
LED 0-3V 11 12 0-3V
13 14 0-3V
BEFM3 0-3V 15 16
17 18
Reset 0-3V 19 20
V_High 21 22 0-3V
U_High 23 24 W_Low
H3 25 26 BEFM3
Fault 3.3V 27 28 V_Low
Enable 3.3V 29 30 U_Low
H2 31 32
W_High 33 34
0-3V 35 36 3.3V
0-3V 37 38 3.3V

Apart from the fact that I can’t tell which pin is assigned where, I am troubled by the fact that there are eight pins being PWMed, rather than the six I would expect.

Hey @armaanhammer,

I think you’ll need to redefine your peripheral pin declaration map. You can see that for your variant the PB_13 and PB_15 are not associated with the timer TIM1. You can go to your variant file in the package stm32duino. And change PeripheralPins.c file or include this map in your arduino code with undocumented right configuration.

#ifdef HAL_TIM_MODULE_ENABLED
WEAK const PinMap PinMap_PWM[] = {
  {PA_0,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
  {PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
  //  {PA_1,  TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 1, 1)}, // TIM15_CH1N
  //  {PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
  //  {PA_2,  TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 1, 0)}, // TIM15_CH1
  //  {PA_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
  //  {PA_3,  TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 2, 0)}, // TIM15_CH2
  {PA_5,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
  {PA_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
  //  {PA_6,  TIM16,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM16, 1, 0)}, // TIM16_CH1
  //  {PA_7,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
  {PA_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
  {PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
  {PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
  {PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
  {PA_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
  {PA_15, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
  //  {PB_0,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
  {PB_0,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
  //  {PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
  {PB_1,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
  {PB_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
  {PB_4,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
  {PB_5,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
  {PB_6,  TIM16,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM16, 1, 1)}, // TIM16_CH1N
  {PB_8,  TIM16,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM16, 1, 0)}, // TIM16_CH1
  {PB_10, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
  {PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
  //  {PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
  {PB_13, TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 1, 1)}, // TIM15_CH1N
  {PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
  //  {PB_14, TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 1, 0)}, // TIM15_CH1
  //  {PB_15, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
  {PB_15, TIM15,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_TIM15, 2, 0)}, // TIM15_CH2
  {PC_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
  {PC_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
  {PC_8,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
  {PC_9,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
  {NC,    NP,    0}
};
#endif

Regarding why 8 pins are being PWMd (instead of 6)
It is possible that TIM1_CH4 (default PA11) and TIM1_CH4N (default ??) are being PWMd . This would be a misconfiguration.

Timer 1 can PWM 8 pins on its 4 channels. SimpleFOC only wants to use CH1, CH2, CH3 but I guess CH4 might want to join the party!

I agree that the pin naming is confusing. For stm32, I use the ‘PA1’ naming and never use the arduino numbers (even though they can be swapped) as those numbers aren’t mentioned on stm32 datasheets so are harder to cross reference. The ‘PA_1’ naming is for stm32 PinNames which is only useful if you want to directly use the stm32 APIS.

Antun has pointed out that you need to change peripheral maps. I agree.

Thanks for the replies, guys! Unfortunately, I had already changed my PeripheralPins.c file before I started all this. Assuming that I’ve changed the correct one – how do I tell which file I’m actually using to build with?

I’ve gone so far as to delete everything else from that code block like so:

#ifdef HAL_TIM_MODULE_ENABLED
WEAK const PinMap PinMap_PWM[] = {
  {PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
  {PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
  {PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
  {PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
  {PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
  {PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
  {NC,    NP,    0}
};
#endif

The behavior remains the same – eight pins are being PWMed, and none of them are the correct pins. I’m going to continue tinkering.


Edit: I also tried pasting the codeblock into the top of my sketch, with the same behavior.

If placing pinmaps in your ino, i wouldn’t include the #ifdef and WEAK.

const PinMap PinMap_PWM[] = {
  {PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
  {PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
  {PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
  {PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
  {PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
  {PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
  {NC,    NP,    0}
};

I’m not confident this will help. Your problems feel like that there are problems with the board variant definition of you’ve selected the wrong board variant.
Are you able to step through/debug the code? I can do this with platformio and an stlink/v2.
It is possible that something weird is happening in simplefoc hardware specific code: