High Current Draw after driver.init()

TLDR

Problem—When driver.init() runs, my motor driver (TMC 6300) draws a high current (1.5A). Once the initial position is set, the current draw goes down. Additionally, I’m able to set the target position correctly when the loop() starts.

Implications—For the prototype I’m developing, there is a single power supply that runs an SBC, microcontroller, and motor. The high current draw causes brownouts on the SBC due to a voltage drop.

Setup

  • Power
    • Benchtop power supply set to 5.15V
    • Sparkfun Voltage regulator set to 5 V
    • A capacitor bank is set up to filter spikes and prevent voltage drops on current draws.
    • USB-C input into Raspberry PI 4B
  • Raspberry Pi - running PlatformIO remote agent
  • Adafruit Feather STM32 F405
    • Connected to USB Type-A port on RPI4b
  • Sparkfun TMC6300 motor driver
    • Driver is connected to a variable voltage regulator set to 9V
    • A capacitor bank is set up to filter spikes and prevent voltage drops on current draws.
  • Motor - 2208 Gimbal Motor from SpeedyFPV

Code

Here is my code:

// Open loop motor control 

#include <Arduino.h>
#include <SimpleFOC.h>

#define SERIAL_BAUD_RATE 115200
#define X_AXIS_MOTOR_DRIVER_PIN 13

// This pin combination results in timer score of 12, which results in SimpleFOC using Software PWM
// High current draw when timers are resumed in stu_mcu.cpp _configure6PWM() within alginTimers() function
// Position control works correctly 

#define UL_PIN 10
#define UH_PIN 9

#define VL_PIN 6
#define VH_PIN 5

#define WL_PIN SDA
#define WH_PIN SCL  // SCL

#define POLE_PAIRS 12 // counted from the motor
#define MOTOR_RESISTANCE 5.6 // Not sure if this is the correct value, it's not in the motor specification
#define MOTOR_KV 80 // from Speedy FPV web site 
// https://speedyfpv.com/products/2208-brushless-gimbal-motor-2-3s-80kv-7-12v-for-gimbals?_pos=7&_sid=3f87ff37c&_ss=r

BLDCMotor motor = BLDCMotor(POLE_PAIRS, MOTOR_RESISTANCE, MOTOR_KV);
BLDCDriver6PWM driver = BLDCDriver6PWM(UH_PIN, UL_PIN, VH_PIN, VL_PIN, WH_PIN, WL_PIN, X_AXIS_MOTOR_DRIVER_PIN);

//target variable
float target_position = 0;

// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_position, cmd); }
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
void doVelocity(char* cmd) { command.scalar(&motor.velocity_limit, cmd); }

void setup() 
{
  SimpleFOCDebug::enable();

  Serial.begin(SERIAL_BAUD_RATE);
  while (!Serial) 
  {
    // Wait for serial port to connect
  }
  
  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 9;
  
  // limit the maximal dc voltage the driver can set
  // as a protection measure for the low-resistance motors
  // this value is fixed on startup
  driver.voltage_limit = 9;
  
  driver.init();
 
  // link the motor and the driver
  motor.linkDriver(&driver);

  // limit/set the velocity of the transition in between 
  // target angles
  motor.voltage_limit = 5; // [V]

  motor.velocity_limit = 5; // [rad/s] cca 50rpm

  // open loop control config
  motor.controller = MotionControlType::angle_openloop;
  
  // init motor hardware
  motor.init();

// add target command T
  command.add('T', doTarget, "target angle");
  command.add('L', doLimit, "voltage limit");
  command.add('V', doLimit, "movement velocity");

  Serial.println("Motor ready!");
  Serial.println("Set target position [rad]");

  _delay(1000);
  

}

void loop() 
{
  // open loop angle movements
  // using motor.voltage_limit and motor.velocity_limit
  // angles can be positive or negative, negative angles correspond to opposite motor direction
  motor.move(target_position);
  
  if (motor.shaft_angle == target_position) 
    {
      // if motor is at target position, set voltage to zero
      motor.target = 0;
	  motor.move(0);
      motor.voltage_limit = 0; // set voltage limit to zero

    } else 
    {
    // if motor is not at target position, run FOC to reach target position
    motor.voltage_limit = 5; // replace with your voltage limit  
    motor.target = target_position;
    motor.loopFOC();
    }
    // user communication
  command.run();

}

I’ve tested the Sparkfun TMC6300 with the same motor running 6PWM on the Sparkfun Redboard (their Arduino Uno equivalent). There is no high current draw at driver.init().

I added extensive debugging to the simpleFoc library and traced when the timers are resumed. Given my pin configuration stm32_mcu.cpp selects SoftwarePWM, even though hardware timer are available on all the pins.

I tried another pin combination and had the same result with high current draw.

// This pin combination results in timer score of 12, which results in SimpleFOC using Software PWM
// High current pull when timers are resumed in stu_mcu.cpp _configure6PWM() within alginTimers() function
// Position control works correctly 
#define UL_PIN PB11 // RX
#define UH_PIN PB10 // TX

#define VL_PIN 6
#define VH_PIN 5

#define WL_PIN SDA
#define WH_PIN SCL  // SCL

How do I prevent the driver from pulling so much current during initiation?

Debug Output

Driver Voltage Power: 9.00
Driver Voltage Limit: 9.00
PWM A high: 9
Phase state: OFF
PWM duty cycles: 0
STM32-DRV: Configuring 6PWM
STM32-DRV: pwm FREQUENCY: 50000
TIM4-CH3 TIM4-CH4 TIM3-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: 12
TIM4-CH3 TIM4-CH4 TIM3-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM4-CH3 TIM4-CH4 TIM8-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM4-CH3 TIM4-CH4 TIM8-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: 12
TIM4-CH3 TIM11-CH1 TIM3-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM4-CH3 TIM11-CH1 TIM3-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM4-CH3 TIM11-CH1 TIM8-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM4-CH3 TIM11-CH1 TIM8-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM4-CH4 TIM3-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM4-CH4 TIM3-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM4-CH4 TIM8-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM4-CH4 TIM8-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM11-CH1 TIM3-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM11-CH1 TIM3-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM11-CH1 TIM8-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: -7
TIM10-CH1 TIM11-CH1 TIM8-CH2 TIM8-CH1 TIM4-CH1 TIM4-CH2 score: -7
STM32-DRV: best: TIM4-CH3 TIM4-CH4 TIM3-CH2 TIM3-CH1 TIM4-CH1 TIM4-CH2 score: 12
STM32-DRV: Best pin combo found with score: 12
STM32-DRV: Configuring Software 6PWM
STM32-DRV: Configuring high timer 4
STM32-DRV: Configuring high channel 3
STM32-DRV: Init low side pin
STM32-DRV: Timer instance created
STM32-DRV: Channel set to channel 4
STM32-DRV: Configuring low timer 4
STM32-DRV: Configuring low channel 4
STM32-DRV: Configuring high timer 3
STM32-DRV: Configuring high channel 2
STM32-DRV: Init low side pin
STM32-DRV: Timer instance created
STM32-DRV: Channel set to channel 1
STM32-DRV: Configuring low timer 3
STM32-DRV: Configuring low channel 1
STM32-DRV: Configuring high timer 4
STM32-DRV: Configuring high channel 1
STM32-DRV: Init low side pin
STM32-DRV: Timer instance created
STM32-DRV: Channel set to channel 2
STM32-DRV: Configuring low timer 4
STM32-DRV: Configuring low channel 2
STM32-DRV: Hardware time objects initialized
STM32-DRV: Pins mapped to channels
STM32-DRV: Align timers start
STM32-DRV: Align timers new()
STM32-DRV: Syncronising timers! Timer no. 2
STM32-DRV: Aligning PWM to master timer: 4
STM32-DRV: Restarting timer 4
STM32-DRV: Restarting timer 3
STM32-DRV: Resume timers : 0
STM32-DRV: resume channel 1
STM32-DRV: resume channel 2
STM32-DRV: resume channel 3
STM32-DRV: resume channel 4 // High Current draw starts here.
STM32-DRV: Resume timers : 1
STM32-DRV: resume channel 1
STM32-DRV: resume channel 2
STM32-DRV: resume channel 3
STM32-DRV: resume channel 4
STM32-DRV: Align timers end
Driver configured
Driver initialized: 1
Driver initialized!
Motor linked to driver!
Motor Voltage limit: 5.00
Motor Velocity limit: 5.00
Motor controller set to angle_openloop
MOT: Init
MOT: Enable driver.
Motor initialized!
setPWM to 0!
Motor ready!
Set target position [rad]
T 0
1.000
T 1
1.000
T -1
-2.000

What’s the resistance of that motor? I see 80kV which should mean large resistance, but it looks quite small in images… you can try to set lower motor.voltage, it should be at most 1/2 power supply, but in this case, maybe even lower, try 2-3 volts?
Anyway, in open loop it is unable to really do anything efficiently, so you will have large current while the motor is trying to align the rotor poles with the stator. If you can do closed loop with some kind of sensor, you’ll get better performance and less startup current.

Edit: this came up recently and may be related, especially as you are also using F4 family with 6PWM 6 PWM driver initialisation causes shoot through - #13 by Cdoel

Also, I saw your note about using a RPi as a platformio remote agent… what do you mean by this? It sounds interesting, I would like to know what the use for this is.

@VIPQualityPost PlatformIO has a feature that allows you to develop remotely on microcontrollers. Instead of the board being connected directly to the host computer, it’s connected to an SBC or computer. The SBC runs a remote agent. When you click “Remote Upload” the local host cross compiles the firmware then it will upload the file to the SBC which then flashes the firmware on to the connected microcontroller.

Here are the docs for the feature.

I’ve only tested PlatformIO’s remote features using a Raspberry Pi. It’s worked well and reliably for me.

In my case, the MCU board is not physically remote. I have a use case where the MCU board is mounted on a platform that can rotated 360 degrees continuously. If I plugged the board in directly to my development host the wires would restrict the platform’s movement during testing. Or I would need to unplug the MCU after each firmware upload. So an RPI with PlatformIO remote solves the issue for me.

I hope this helps!

@VIPQualityPost Thanks for pointing out this post.

I’ve tried some code changes based on the contents of that post, but with no luck.

I also tried changing the ‘motor.voltage_limit = 2’ that did not help. The in rush/shoot through current occurs before motor.init().

I will likely add a position sensor soon (just haven’t gotten to it yet). The position of the platform is off by a lot, so I’m hoping that the sensor will help with accuracy and help optimize current flow during motor operation.

This seems very strange, I was not under the impression the driver is doing anything until the motor initializes. Is the shoothrough happening during driver.init?

Hey @drummerhul

So, simplefoc uses the PWM generation based on the internal timers of the stm32 boards, it even requires it to operate. There is no software emulation of the PWM like some sort of but banging etc.
So we are using the stm32 hardware timers and the PWM generation.

However, we make a discticntion for 6PWM gneration. There we have the

  • hardware 6pwm
  • software 6pwm.

Hadrware 6pwm uses only one timer and generates all 6 signals using it. This is a feature of the stm32 boards that is available usually only on TIM1 and TIM8. This is the preferred way of controlling generating the 6PWM signals as these timers handle the dead-time internally and generate nice complementary signals on the low side (we are only controlling the high-side pwm). Additionally, as all 6 pwm signals are on the same timer, they are inherently perfectly syncronised.

As there are usually only two timers which have the hardware 6pwm available and as their pins are not always available on commonly used boards, simplefoc allows for a differnt form of 6pwm generation which we call Software 6pwm.
In siftware 6pwm we make sure that each pair of high/low pwms is on the same timer, to make sure that they are in sync. In your case you have two pairs that are on the timer TIM4 and one on the timer TIM3.
When suing the software 6PWM it’s the simplefoc (not the stm32 hadrware) that generates the complementary signals and inject the dead-time. This is less preferred way of generating 6pwm but it still works for most of the applications.
The issue with this 6pwm generation is that even though high and low side pwm within the pairs are synced, the pairs might not be in sync between them (as they are all on different timers).
To address this issue, from the release v2.3.3 we are performing the sync of all the timers.

Now in your case it seems like the power surge happens during this sync. What you can try to do is to comment out the timer sync, by commenting this if statement.

Maybe the sync procedure is causing some shoot through or some bad voltage vector to be set to in your driver, which causes the high current draw. I am not really sure.
But in any case, if this is the case, commenting these lines will tell us if this is the issue.

@VIPQualityPost Yes. The shoot through is happening in during driver.init() when the timers resume.

@Antun_Skuric Thanks so much for the explanation of the code. This is very helpful. I tried commenting out the if statement, but no luck. When the timers resume, the shoot through occurs.

Any other thoughts on how to solve the problem?

Good news. I solve the problem. Bad News. I solved the problem.

I have two motors (each using a separate TMC 6300). I could not find a pin combo for both sets of driver pins that had a good timer combo score. It looks like the Adafruit Feather STM32 F405 doesn’t expose the correct to drive two 6 PWM drivers (or at least I could not find one). I also tried an Adafruit M4 Express (SAMD51) but had the same issue with a bad pin/timer combo score.

I’ve instead switched to two separate Seeed Studio Xiao ESP32 S3 boards. I had them in stock and they fit inside the enclosure. There is no shoot through current with either of these boards.

Thanks for all the help.

1 Like