Using motor.enable or disable in the code is drawing over current

When we call setup, we usually set:

motor.init(); 
motor.initFOC();

However, if I were to use motor.enable or disable inside of the loop() (only to use when there is a trigger) it’s drawing over current and burning my fuses.

void loop()
{
motor.loopFOC();
motor.move();
if(trigger1)
 {
  motor.enable();
 }
if(trigger2)
 {
  motor.disable();
 }
}

It happens right after motor is fully initialized. Even if trigger1 or tigger2 are not called. It works fine if I remove motor.disable() and motor.enable() from the trigger functions.

Not sure if this is a bug? I don’t see why the motor would draw over-current even if motor.enable or disable is called or not called.

We’ll need a bit more information to help you troubleshoot. Please share which driver and MCU you’re using, how they’re wired together (especially the driver’s EN pin), and your full SimpleFOC initialization code.

Hi @quentin , thank you for getting back.

Thank you for all the efforts you guys are putting on this library.

It’s a custom board built based off of the BG431-ESC1.

The moment I put motor.init(); motor.initFOC(); in loop(), it’s drawing over current and burning the fuses.

#include <SimpleFOC.h>
#include "mxx_can.h"

#define CAN_ID 0x001
#define GEAR 25
#define TERM_CAN_BUS false
#define DELAY_BETWEEN_CMDS 150
#define MIN_POS -12.5
#define MAX_POS 12.5
#define MIN_VEL -5.0
#define MAX_VEL 5.0
#define POWER_SUPPLY 54
#define MAX_RPM 200 // we have run it upto 230 rad/s as well
#define MAX_BATTRYBRD_CMD 10.0

MxxCan can;
bool enableFlag=false;
bool motorUP=false;
bool motorDOWN=false;
bool motorInitialized=false;
float currentAngle = 0.0;
long lastUpdate = 0;
float vel_cmd = 0.0;
float notused_cmd = 0.0;

BLDCMotor motor = BLDCMotor(21);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003, -64.0/7.0, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);

Encoder encoder = Encoder(A_HALL1, A_HALL2, 1000);

void doA(){encoder.handleA();}
void doB(){encoder.handleB();}

FDCAN_RxHeaderTypeDef canRxHeader;
uint8_t canRxData[4];

// converts from 0 to 1, to 0 to MAX_RPM range
float mapSpeed(float value)
{
	value = (value / MAX_BATTRYBRD_CMD) * MAX_RPM;
	return value;
}

void can_callback(FDCAN_RxHeaderTypeDef rx_header, uint8_t *rx_data)
{
	can.packetRcvd = true;
	canRxHeader = rx_header;
	memcpy(&canRxData[0], &rx_data[0], 4);	
	//can.process_packet(rx_header, rx_data);
	//digitalToggle(LED_BUILTIN);
}

void setup()
{
  Serial.begin(115200);
  delay(1000);

  pinMode(PB10, INPUT_PULLDOWN);
  pinMode(LED_BUILTIN, OUTPUT);
  pinMode(PB13, OUTPUT);
  digitalWrite(LED_BUILTIN, LOW);
  digitalWrite(PB13, LOW);

  SimpleCan::RxHandler *can_rx_handler = new SimpleCan::RxHandler(4, can_callback);
	if(!can.init(CAN_ID, TERM_CAN_BUS, MIN_POS, MAX_POS, MIN_VEL, MAX_VEL, can_rx_handler)) 
	{
		Serial.println("CAN init failed");
		// while(1);
	}

  // initialize encoder sensor hardware
  encoder.init();
  encoder.enableInterrupts(doA, doB); 
  // link the motor to the sensor
  motor.linkSensor(&encoder);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = POWER_SUPPLY;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  currentSense.linkDriver(&driver);

  // current sensing
  currentSense.init();
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  // aligning voltage [V] - reduced to prevent overcurrent
  motor.voltage_sensor_align = 1.0;  // Reduced from 3V to 1V
  // index search velocity [rad/s]
  motor.velocity_index_search = 3;
  
  // Skip sensor alignment if you know the motor parameters
  // Uncomment these lines if you want to skip alignment entirely:
  // motor.sensor_direction = Direction::CW;  // or CCW
  // motor.zero_electric_angle = 0.0;  // Set to your motor's electrical zero angle

  // set motion control loop to be used
  motor.controller = MotionControlType::velocity;
  motor.torque_controller = TorqueControlType::foc_current;

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 20;
  // default voltage_power_supply
  motor.voltage_limit = POWER_SUPPLY;
  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 1000;

  // velocity low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01;

  // angle P controller
  motor.P_angle.P = 30;
  //  maximal velocity of the position control
  motor.current_limit = 30;
  motor.velocity_limit = 10; //previously 19

  // Motor initialization deferred until first enable command
  // This prevents overcurrent during startup when no CAN commands are sent
  
  
  //assign some delay
  delay(1000);

}

void loop()
{
  // main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  motor.move();

  if(can.packetRcvd) 
  {
    // Serial.println("CAN received from motherST");
		can.process_packet(canRxHeader, canRxData);
    lastUpdate = millis();
    
		switch(can.check_rx())
		{
			case RX_TYPE::MOTOR_ENABLE:
        // Initialize motor on first enable command
        if (!motorInitialized) {
          motorInitialized = true;
motor.init();        // This already calls motor.enable()
  motor.initFOC();
        }
        vel_cmd = 0.0;
        enableFlag = true;
				break;
			case RX_TYPE::MOTOR_DISABLE:
				// Disable motor
motor.disable()
        enableFlag = false;
        motorInitialized = false;
				break;
			case RX_TYPE::MOTOR_CMD:
				can.get_cmd(vel_cmd, notused_cmd);
				break;
		}
		// can.update_tx_data(motor.shaft_angle/gear, motor.shaft_velocity/gear,
		// 	currentSense.getDCCurrent(), motor.current.q, temperature, motor.voltage.q);
		// can.send_data();
    digitalToggle(LED_BUILTIN);
		can.packetRcvd = false;
	}

  unsigned long curr_time = millis();

  
  if(enableFlag)
  {
    if ((curr_time - lastUpdate) > DELAY_BETWEEN_CMDS)
    {
      // stop the motor
      motor.target = 0.0;
    }
    else
    {
      motor.target =  mapSpeed(vel_cmd);
    }

  }

}


Hi @mizzi_labs ,

it sounds a lot like there is too much current going through your driver… what resistance is your motor?

Here are some points to try:

  1. set a much lower motor voltage limit - it should be at most half the power supply voltage, to prevent clipping, but for initial testing you should set it much lower, like 1V or even less.

  2. ideally, use a high ohm gimbal motor for first testing. These are easy to control and their high resistance means things won’t immediately burn up even if the code is wrong.

  3. start simple! First test open loop with low voltage, to make sure the PWM stage is working. Then add the encoder and test torque-voltage mode. Then try to add the more complicated modes like foc_current or velocity/position mode. One thing at a time…

Hi @runger , thank you for getting back. I firstly want to thank you for your efforts over the past few years on this library. It’s super helpful.

Its around 0.12R and L is 0.02mH

I’m not worried about the voltage limit at the moment. I have been playing with simplefoc for the past few years and those voltage limits work great for our use case. Problem is arising when the motor is mechanically running into issues (for example the bearing breaking or gears running into issues, or the roto coming too close to the encoder. During which we are noticing huge current draw by the firmware and it’s blowing the fuse.

I can detect the current draw using currentSense.getDCCurrent() . But when I try to disable the motor, it’s drawing over-current for some reason. I was able to make it work last evening by putting a Serial println statement just before the disable request. Not sure if that could be a bug ? The issue goes away if I remove the disable function.

Secondly. I was hoping to find a better solution than disabling the motor. As the motor.disable() function in simplefoc simply turns off the FETs. Which is not good when you are in position control and holding a pay-load. I was hoping to put brakes on the motor, by shorting the low-side or high-side FETs. But couldn’t find any function in simplefoc. How can I go about implementing my own brake function?

Thanks again.

You can call driver.setPwm(0, 0, 0); to short the motor coils. But unless you’ve provided a driver disable pin, that’s all disable() does anyway. And in my experience, it does still spike the power supply even though the motor’s momentum is being converted to heat in the coils. If your hardware can’t use a brake resistor, the best way I’ve found to decelerate without spiking the power supply is to gradually ramp the target velocity or motor.voltage limit to 0.

Hi @mizzi_labs ,

thank you for your kind words.

Note that if you suddenly disable the motor there can be a large voltage spike, maybe it could be part of your problems?

To control the motor phases individually is possible if you have 6-PWM control. You can use the function

driver.setPhaseState() to put the phases in hi-z mode, or set or PWM just the low or high sides. The settings take effect with the next call to setPwm().

It’s a not yet well documented feature, because braking is a bit difficult. Different use cases require different control techniques and often there is additional hardware involved like brake resistances.

That sounds very strange, I can’t really explain that. Perhaps if you can share your code we can spot some problems?

Hi Runger, here is the code.

All I did was change Serial.println("Overcurrent"); (which I originally had, where it would simply go into over-current and blow out the fuses) to Serial.println("Overcurrent Turning OFF"); You’ll notice that in the last section of the code.

#include <SimpleFOC.h>
#include "mxx_can.h"

float runningSum = 0;
float avgCurrent = 0;
const int BUFFER_SIZE = 10;         // Number of samples for averaging
const float OVERCURRENT_LIMIT = 5;  // Amp threshold
float currentBuffer[BUFFER_SIZE];   // Circular buffer storage
int bufferIndex = 0;                // Points to where the next sample goes
bool bufferFull = false;            // True once buffer has filled up once

unsigned long lastSampleTime = 0;
const unsigned long SAMPLE_INTERVAL = 1; // ms between samples

unsigned long lastPrintTime = 0;
const unsigned long printInterval = 10; // milliseconds

void addSample(float newValue) {
  // Subtract the old value and add the new one
  runningSum -= currentBuffer[bufferIndex];
  currentBuffer[bufferIndex] = newValue;
  runningSum += newValue;

  bufferIndex = (bufferIndex + 1) % BUFFER_SIZE;
  if (bufferIndex == 0) bufferFull = true;

  if (bufferFull) avgCurrent = runningSum / BUFFER_SIZE;
}
// Testing disable ability

#define CAN_ID 0x001
#define GEAR 25
#define TERM_CAN_BUS false
#define DELAY_BETWEEN_CMDS 150
#define MIN_POS -12.5
#define MAX_POS 12.5
#define MIN_VEL -5.0
#define MAX_VEL 5.0
#define POWER_SUPPLY 54
#define MAX_RPM 200 // we have run it upto 230 rad/s as well
#define MAX_BATTRYBRD_CMD 10.0
#define FAIL_LIMIT 100

MxxCan can;
bool enableFlag=false;
bool motorUP=false;
bool motorDOWN=false;
bool motorInitialized=false;
float currentAngle = 0.0;
long lastUpdate = 0;
float vel_cmd = 0.0;
float notused_cmd = 0.0;

BLDCMotor motor = BLDCMotor(21);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, PB14, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003, -64.0/7.0, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);

Encoder encoder = Encoder(A_HALL1, A_HALL2, 1000);

void doA(){encoder.handleA();}
void doB(){encoder.handleB();}

FDCAN_RxHeaderTypeDef canRxHeader;
uint8_t canRxData[4];

// converts from 0 to 1, to 0 to MAX_RPM range
float mapSpeed(float value)
{
	value = (value / MAX_BATTRYBRD_CMD) * MAX_RPM;
	return value;
}

void can_callback(FDCAN_RxHeaderTypeDef rx_header, uint8_t *rx_data)
{
	can.packetRcvd = true;
	canRxHeader = rx_header;
	memcpy(&canRxData[0], &rx_data[0], 4);	
	//can.process_packet(rx_header, rx_data);
	//digitalToggle(LED_BUILTIN);
}

void setup()
{
  Serial.begin(115200);
  delay(1000);

  pinMode(PB10, INPUT_PULLDOWN);
  pinMode(LED_BUILTIN, OUTPUT);
  pinMode(PB13, OUTPUT);
  digitalWrite(LED_BUILTIN, LOW);
  digitalWrite(PB13, LOW);

  SimpleCan::RxHandler *can_rx_handler = new SimpleCan::RxHandler(4, can_callback);
	if(!can.init(CAN_ID, TERM_CAN_BUS, MIN_POS, MAX_POS, MIN_VEL, MAX_VEL, can_rx_handler)) 
	{
		Serial.println("CAN init failed");
		// while(1);
	}

  // initialize encoder sensor hardware
  encoder.init();
  encoder.enableInterrupts(doA, doB); 
  // link the motor to the sensor
  motor.linkSensor(&encoder);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = POWER_SUPPLY;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  currentSense.linkDriver(&driver);

  // current sensing
  currentSense.init();
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  // aligning voltage [V] - reduced to prevent overcurrent
  motor.voltage_sensor_align = 1.0;  // Reduced from 3V to 1V
  // index search velocity [rad/s]
  motor.velocity_index_search = 3;
  
  // Skip sensor alignment if you know the motor parameters
  // Uncomment these lines if you want to skip alignment entirely:
  // motor.sensor_direction = Direction::CW;  // or CCW
  // motor.zero_electric_angle = 0.0;  // Set to your motor's electrical zero angle

  // set motion control loop to be used
  motor.controller = MotionControlType::velocity;
  motor.torque_controller = TorqueControlType::foc_current;

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 20;
  // default voltage_power_supply
  motor.voltage_limit = POWER_SUPPLY;
  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 1000;

  // velocity low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01;

  // angle P controller
  motor.P_angle.P = 30;
  //  maximal velocity of the position control
  motor.current_limit = 30;
  motor.velocity_limit = 10; //previously 19

  // Motor initialization deferred until first enable command
  // This prevents overcurrent during startup when no CAN commands are sent
  motor.init();        // This already calls motor.enable()
  motor.initFOC();
  
  //assign some delay
  delay(1000);

}

void loop()
{
  // main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  motor.move();

  if(can.packetRcvd) 
  {
    // Serial.println("CAN received from motherST");
		can.process_packet(canRxHeader, canRxData);
    lastUpdate = millis();
    
		switch(can.check_rx())
		{
			case RX_TYPE::MOTOR_ENABLE:
        // Initialize motor on first enable command
        if (!motorInitialized) {
          motorInitialized = true;
        }
        vel_cmd = 0.0;
        enableFlag = true;
				break;
			case RX_TYPE::MOTOR_DISABLE:
				// Disable motor
        enableFlag = false;
        motorInitialized = false;
				break;
			case RX_TYPE::MOTOR_CMD:
				can.get_cmd(vel_cmd, notused_cmd);
				break;
		}
		// can.update_tx_data(motor.shaft_angle/gear, motor.shaft_velocity/gear,
		// 	currentSense.getDCCurrent(), motor.current.q, temperature, motor.voltage.q);
		// can.send_data();
    digitalToggle(LED_BUILTIN);
		can.packetRcvd = false;
	}

  unsigned long curr_time = millis();

  
  if(enableFlag)
  {
    if ((curr_time - lastUpdate) > DELAY_BETWEEN_CMDS)
    {
      // stop the motor
      motor.target = 0.0;
    }
    else
    {
      motor.target =  mapSpeed(vel_cmd);
    }
  }

  if (curr_time - lastPrintTime >= printInterval) {
    Serial.print(motor.shaft_velocity);
    Serial.print(",");
    Serial.println(currentSense.getDCCurrent());
    lastPrintTime = curr_time;
  }
  
  if (motor.shaft_velocity > FAIL_LIMIT)
  {
    Serial.println("Turning OFF");
    motor.disable();
  }

   // Sample every 1 ms (adjust as needed)
  if (curr_time - lastSampleTime >= SAMPLE_INTERVAL) {
    lastSampleTime = curr_time;
    addSample(currentSense.getDCCurrent());
    if (bufferFull && avgCurrent > OVERCURRENT_LIMIT) {
    Serial.println("Overcurrent Turning OFF");
    motor.disable();
    }
  }

}