Strange behavior of bldc motor, regardless of the control type

Hello everyone. What you are doing here is amazing, I am impressed with the possibilities with this library.
This is my first project and it is quite advanced.

My configuration:
MCU: esp32-wroom
Driver: A3935
datasheet A3935
Mosfet: 3QN04H2 up to 200A
datasheet 3QN04H2
Current sense x2: ACS754 +/-150A
datasheet ACS754
Motor BLDC: about 600w, 3PP, 0.3ohm
Feedback: 3x hall sensor from motor

ESP32 pinout

The problem is that the engine runs very erratically. It seems to me that regardless of the control mode. I’m a very beginner in this matter. I used various sample sketches.
The hall sensor example test appears to be working properly. However, when you move your hand quickly, it gets lost, or is it due to delay(100); in the code.
The PWM test sets the desired voltage on all 3 motor phases (tests without motor).
Openloop works the same way, also without a current sensor.

Please suggest where to look and what to change.

PS. I am testing at motor.voltage_sensor_align = 0.5f; because otherwise the 5A test power supply turns off.

Video

Hi @deeppl , welcome to SimpleFOC!

If you have some delays in the code, you definitely need to remove that…
The loopFOC() and move() functions need to be called very frequently, without delays…

It’s hard to tell from the video what’s up. If you can share your code here then maybe we can take a look at it and help you find the issue…

Delays are only in test sketch.

The video shows pulsating operation. Every few seconds I increase the speed, T0.1->T0.5->T1->T2->T3 the power supply switches off. You can feel it best if you block the rotor with your hand. The torque is high but not constant. At higher speeds the engine starts jumping cyclically. As if it were braking? It looks like some impulse is missing or is at the wrong moment.

#include <SimpleFOC.h>
//define motor 
#define POLEPAIR 3
//define hall pins
#define HALL_A 36
#define HALL_B 39
#define HALL_C 34
//define driver pins
#define PHASE_A_H 25
#define PHASE_A_L 26
#define PHASE_B_H 27
#define PHASE_B_L 14
#define PHASE_C_H 12
#define PHASE_C_L 13
#define ENABLE_DRV 33
#define SENSE_A 35
#define SENSE_B 32

// BLDC motor instance BLDCMotor(polepairs, (R), (KV), (L))
BLDCMotor motor = BLDCMotor(POLEPAIR);

// BLDC driver instance BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, (en))
BLDCDriver6PWM driver = BLDCDriver6PWM(PHASE_A_H, PHASE_A_L, PHASE_B_H, PHASE_B_L, PHASE_C_H, PHASE_C_L, ENABLE_DRV);

// inline current sense instance InlineCurrentSense(mVpA, phA, phB, (phC))
InlineCurrentSense currentsense = InlineCurrentSense(13.3f, SENSE_A, SENSE_B);

// position / angle sensor instance HallSensor(hallA, hallB , hallC , pole pairs)
HallSensor sensor = HallSensor(HALL_A, HALL_B, HALL_C, POLEPAIR);
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

float target = 0;
Commander command = Commander(Serial);
void doTarget(char* cmd){ command.scalar(&target, cmd); }
void onMotor(char* cmd){ command.motor(&motor,cmd); }


///////////////////////////  SETUP  /////////////////////

void setup() {
    // start serial
    Serial.begin(115200);
SimpleFOCDebug::enable(&Serial);
    // USE_EXTERN is default (1k - 5k recommended), change to USE_INTERN if needed
    sensor.pullup = Pullup::USE_EXTERN;
    // initialize sensor
    sensor.init();
    // enable Hall effect interrupts
    sensor.enableInterrupts(doA, doB, doC);
    // link sensor to motor
    motor.linkSensor(&sensor);
 // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12; // power supply voltage [V]
  driver.voltage_limit = 12; // Max DC voltage allowed - default voltage_power_supply
  driver.pwm_frequency = 22500; // pwm frequency to be used [Hz]
  driver.dead_zone = 0.01; // dead_zone [0,1] - default 0.02 - 2%

    // initialize driver
    driver.init();
    // link driver to motor
    motor.linkDriver(&driver);
// link driver to current sense
    currentsense.linkDriver(&driver);
  
  //motor.phase_resistance = 0.3; // [Ohm]
  //motor.current_limit = 1;      // [Amps] - if phase resistance defined
  motor.voltage_limit = 12; // [V] - if phase resistance not defined
  motor.voltage_sensor_align = 0.1f;
  motor.velocity_limit = 300; // [rad/s] 5 rad/s cca 50rpm

///////////////////////////////// CONTROL //////////////////////////////

    motor.controller = MotionControlType::torque; // set motion control type to torque (default)
    //motor.controller = MotionControlType::velocity; // set motion control type to velocity 
    //motor.controller = MotionControlType::angle; // set motion control type to angle / position
    //motor.controller = MotionControlType::velocity_openloop; // set motion control type to velocity openloop
    //motor.controller = MotionControlType::angle_openloop; // set motion control type to angle / postion openloop

  
///////////////////////////////// TORQUE //////////////////////////////

    motor.torque_controller = TorqueControlType::voltage; // set torque control type to voltage (default)
    //motor.torque_controller = TorqueControlType::dc_current; // set torque control type to DC current
    //motor.torque_controller = TorqueControlType::foc_current; // set torque control type to FOC current


///////////////////////////////// MODULATION //////////////////////////////

    //motor.foc_modulation = FOCModulationType::SinePWM; // set FOC modulation type to sinusoidal (default)
    motor.foc_modulation = FOCModulationType::Trapezoid_120; // set FOC modulation type to trapezoidal 120
    //motor.foc_modulation = FOCModulationType::SpaceVectorPWM; // set FOC modulation type to space vector modulation


// controller configuration based on the control type 
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
motor.PID_velocity.D = 0.001;

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

// angle loop controller
motor.P_angle.P = 20;


// Q axis
// PID parameters - default 
motor.PID_current_q.P = 1;                       // 3    - Arduino UNO/MEGA
motor.PID_current_q.I = 0;                    // 300  - Arduino UNO/MEGA
motor.PID_current_q.D = 0;
motor.PID_current_q.limit = motor.voltage_limit; 
//motor.PID_current_q.ramp = 1e6;                  // 1000 - Arduino UNO/MEGA
// Low pass filtering - default 
motor.LPF_current_q.Tf= 0.5;                         // 0.01 - Arduino UNO/MEGA

// D axis
// PID parameters - default 
motor.PID_current_d.P = 1;                       // 3    - Arduino UNO/MEGA
motor.PID_current_d.I = 0;                    // 300  - Arduino UNO/MEGA
motor.PID_current_d.D = 0;
motor.PID_current_d.limit = motor.voltage_limit; 
//motor.PID_current_d.ramp = 1e6;                  // 1000 - Arduino UNO/MEGA
// Low pass filtering - default 
motor.LPF_current_d.Tf= 0.5;                         // 0.01 - Arduino UNO/MEGA


    // use monitoring
    motor.useMonitoring(Serial);
    //display variables 
    motor.monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VOLT_D | _MON_CURR_Q | _MON_CURR_D | _MON_VEL | _MON_ANGLE; // default _MON_TARGET | _MON_VOLT_Q | _MON_VEL | _MON_ANGLE
    // downsampling
    motor.monitor_downsample = 10000; // default 10
    // initialize motor
    motor.init();
    currentsense.init();
    motor.linkCurrentSense(&currentsense);
    // for SimpleFOCShield v2.01/v2.0.2
  //currentsense.gain_a *= 0.1;
  //currentsense.gain_b *= 0.1;
    // add command to commander
    command.add('T', doTarget, "target");
   // command.add('P', onTarget, "target");
    command.add('M',onMotor,"motion");
    // align sensor and start FOC
    motor.initFOC();

    _delay(1000);
}

void loop() {
    // main FOC algorithm function, the higher the execution frequency, the better, don't put delays in the loop
    motor.loopFOC();

    // this function can be run at much lower frequency than loopFOC()
    motor.move(target);

    // significantly slowing the execution down
    motor.monitor();

command.run();
}

Its looks correct?? Motor hold by T0 command

And MOT: PP check: fail 99/100 trys

17:32:01.128 -> MOT: Align sensor.
17:32:03.292 -> MOT: sensor_direction==CW
17:32:03.324 -> MOT: PP check: fail - estimated pp: 3.60
17:32:04.052 -> MOT: Zero elec. angle: 0.00
17:32:04.237 -> MOT: Align current sense.
17:32:05.336 -> CS: Switch A-B
17:32:05.336 -> CS: Inv A
17:32:06.412 -> CS: Switch B-(C)NC
17:32:06.452 -> MOT: Success: 4
17:32:06.452 -> MOT: Ready.

After uploading the code I noticed that I am using voltage mode. So FOC does not check current sensors?
If I change to DC current mode the motor receives max negative voltage and turns off my power supply (I test at 12V 5A max). Could this be because ACS754 from precise voltage 5V. The sensor is bidirectional so 0A falls at 2.5V (Vcc/2). Is the driver trying to go down to 1.65V (3.3V/2) that is why my motor is spinning when it should be standing still? I tried to do:
currentsense.offset_ia = -0.85f;
currentsense.offset_ib = -0.85f;
but then it does not initialize:

19:25:33.385 → MOT: Align sensor.
19:25:35.590 → MOT: sensor_direction==CW
19:25:35.590 → MOT: PP check: fail - estimated pp: 3.60
19:25:36.272 → MOT: Zero elec. angle: 0.00
19:25:36.498 → MOT: Align current sense.
19:25:37.612 → CS: Switch A-(C)NC
19:25:38.673 → CS: Err B - all currents same magnitude!
19:25:38.711 → MOT: Align error!
19:25:38.711 → MOT: Init FOC failed.

Quick edit.

However, after changing the mode to DC current and reducing the voltage limit on the motor to 1V, it rotates in the same pulsating way as in every openloop and voltage test so far. After the T0 command, it rotates after T1, changes direction, and T0.8-T0.9 is close to stopping. So I need an offset?

It seems to me that I am not far from a satisfactory effect. I only need it to quickly and with the highest possible torque turn the gear to the position and change direction on demand. :wink:

The situation became clear. One transistor that protected the enable input in the driver was activated randomly and gave ground to the pin.
Currently, the system operates in voltage mode quite correctly. However, in current mode it is bad. Where to start? I admit that I mixed the parameters a lot to fix the previous problem and I got lost.

As I wrote, I power the current sensors with 5v.
I have them bidirectional and I thought to mount it inverted, use invert in code and measurement from 2.5V → 0 to get a higher resolution. the range 2.5V → 3.3v would be for reverse current if something measures it. Only 13.3mV/A seems imprecise with the ADC 12bit my ESP.

PS.
Howto check this:

18:14:22.298 -> MOT: Align sensor.
18:14:24.475 -> MOT: sensor_direction==CW
18:14:24.513 -> MOT: PP check: fail - estimated pp: 3.60

Why Inv C? I use A and B only.

18:39:34.110 -> CS: Inv A
18:39:35.249 -> CS: Switch B-(C)NC
18:39:35.249 -> CS: Inv C
18:39:35.249 -> MOT: Success: 4
18:39:35.249 -> MOT: Ready.