Really easy to stall a motor

Hi everyone!

I am working on my speed and position project with SimpleFOC.

I’m using a SunnySky X2212 motor with a B_431_ESC1 and an AS5600 encoder. Everything is working well so far! However, I’m wondering which parameters I should adjust to make the controller drive the motor a bit harder — right now, it stalls quite easily and doesn’t spin at low speeds. The motor is currently drawing less than 250 mA.

Any tutorial or guidance is appreciated!

Code that I use for speed control:

#include <SimpleFOC.h>
#include <Wire.h>

BLDCMotor motor = BLDCMotor(7, 0.133, 980);  // SunnySky x2122

BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH,
                                       A_PHASE_UL,
                                       A_PHASE_VH,
                                       A_PHASE_VL,
                                       A_PHASE_WH,
                                       A_PHASE_WL);

MagneticSensorI2C as5600 = MagneticSensorI2C(AS5600_I2C);

// angle set point variable
float target_angle = 0;
// commander interface
Commander command = Commander(Serial);
void onTarget(char* cmd){ command.scalar(&target_angle, cmd); }

// the setup routine runs once when you press reset:
void setup() {
  Serial.begin(115200);
  _delay(1000);
  Serial.println("Initializing....");
  _delay(1000);
  // comment out if not needed
  motor.useMonitoring(Serial);
  _delay(1000);
  
  // sensor
  as5600.init();
  motor.linkSensor(&as5600);
  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12.0;
  //driver.voltage_limit = 2.4;  // limit the source voltage because it heats up
  driver.init();

  // Need to setup velocity!
  
  // default P=0.5 I = 10 D =0
  motor.PID_velocity.P = 1;
  motor.PID_velocity.I = 10;
  //motor.PID_velocity.D = 0.001;
  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 1000;

  // link the motor and the driver
  motor.linkDriver(&driver);
  // choose FOC modulation
  //motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
  // limiting motor movements
  motor.voltage_limit = 1;  // [V]// do not increase it more! 133mΩ so 1V / 0.133 = 7.5A. Also, half of 'driver.voltage_limit' NOTE THAT too big voltage limit when power supply is not good to deliver amps will make motor fail and make weird sounds!
  // limit current
  //motor.current_limit = 9.0; // amps
  motor.P_angle.P = 25;
  // motor.P_angle.I = 0.001;
  // motor.LPF_angle.Tf = 0.01f;
  // this variable is in rad/s^2 and sets the limit of acceleration
  motor.P_angle.output_ramp = 1000000; // default 1e6 rad/s^2

  // --- Filtering ---
  motor.LPF_angle.Tf = 0.01;    // reduce AS5600 noise
  motor.LPF_velocity.Tf = 0.02; // smooth measured speed
  
  // limit speed
  motor.velocity_limit = 50;  // [rad/s]
  // open loop control config
  motor.controller = MotionControlType::angle;

  Serial.println("Motor initialization started!");
  // init motor hardware
  motor.init();
  Serial.println("Motor initialization! Aligning encoder!");
  _delay(1000);
  // align encoder and start FOC
  motor.initFOC();

  Serial.println("Motor initialization!");

  // add target command T
  command.add('T', onTarget, "target angle");

  Serial.println("Motor ready.");
  delay(1000);
}

// the loop routine runs over and over again forever:
void loop() {
  // iterative setting FOC phase voltage
  motor.loopFOC();
  // 
  motor.move(target_angle);
  // user communication
  command.run();
}

Issue video:

Probably just the low voltage and current limits (which is a wise choice for initial setup). Once you get the current sense set up, you can set voltage limit 6 with SinePWM or 7 with SpaceVectorPWM, and current limit 5 amps, or 10 if you have a fan blowing on the driver or can reasonably guarantee that it won’t need more than 5 amps for more than a few seconds at a time. The documentation claims 40 amp capability, but according to my personal testing using my finger as a temperature probe, it’s uncomfortably hot to touch after running at 6 amps until it reaches equilibrium temperature.