Velocity Closed loop does not work with alternative ESP32 MISO MOSI and CLK pins

Hi,
Thanks for making FOC accessible to people like me.
For dynamic pitch control I developed my own BLDC control PCB with ESP32Wroom32, DRV8305 and 3 MA732GQ magnetic angle sensors running 6PWM. I use only one of them for the BLDC motor angle.
For some stupid reason I did not use the standard ESP32 SPI pins but other GPIO’s (14,12,13).
In IDE 2.3.0 I use ESP32-WROOM-DA Module.
motor.initFOC() produces success in 50% of atemps.
At success, Velocity- and Angle open loop work well. Torque closed loop using FOC current works fine too.
BLDCMotor motor = BLDCMotor(14, 11.3, 11*1.2, 13.03)
I power with a12V/10A lab power supply.
In the setup I use SPI.begin(14,12,13); for setting the right pins resulting in angle sensor reading work well in serial monitor and also in the SimpleFOC Configuration Tool.
When I prooceed to Velocity closed loop in FOC Current torque mode, the rotor only once, at one increase from target=0, makes a short small displacement. Any further target increase does not do anything. I have to target=0 and then move in the opposite direction to get such small move in the other direction again. As good behaviour stops after needing the sensor angle for the close loop, my assumption was that in the void loop, motor.move() is using the default ESP32 SPI pins in stead of mine. So between motor.loopFOC and motor.move I repeated
SPI.begin(CLK, MISO, MOSI);
sensor.init();
to trick simpleFOC to use my odd SPI pins instead of the default ESP32 ones.
And it worked!
But not good enough to get closed loop Ange to work too.
I tried to dig deeper to search where the getAngle is called in the code in order to force SPI to use my pins, but couldn’t find it.
Si I guess I need your help.

This is the testing code I use:

#include <SimpleFOC.h>

#define OnOff12V 27 // Power 12V enable pin

#define CLK 14
#define MISO 12
#define MOSI 13
#define U6_CS 17
#define DRV_CS 26
#define DRV_EN 23 //Enable driver pin. Enable high.
#define phA_h 5
#define phA_l 4
#define phB_h 18
#define phB_l 21
#define phC_h 19
#define phC_l 22
#define phA_C 33
#define phB_C 32
#define phC_C 35

// magnetic sensor instance - SPI
// SPIClass SPI(HSPI); // Enable the HSPI SPI interface variant on the ESP32
MagneticSensorSPI sensor = MagneticSensorSPI(MA730_SPI, U6_CS);

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(14, 11.3, 11*1.2, 13.03); // BLDC motor inductance BLDCMotor(polepairs, (R), (KV), (Ph-Ph-Inductance))
// BLDCMotor motor = BLDCMotor(14);// , 13.03 BLDC motor inductance BLDCMotor(polepairs, (R), (KV), (Ph-Ph-Inductance))

// BLDCDriver3PWM driver = BLDCDriver3PWM(phA_h, phB_h, phC_h, DriverCS);
BLDCDriver6PWM driver = BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, DRV_EN);

// lowside current sense instance LowsideCurrentSense(R, gain, phA, phB, (phC))
LowsideCurrentSense current_sense = LowsideCurrentSense(0.005, 50, phA_C, phB_C, phC_C);

// commander interface
Commander command = Commander(Serial);
void doMotor(char* cmd){command.motor(&motor, cmd); }

void setup() {

// pinMode(U6_CS, OUTPUT);
// digitalWrite(U6_CS, HIGH);
// pinMode(CLK, OUTPUT);
// pinMode(MISO, INPUT);
// pinMode(MOSI, OUTPUT);

// initialise magnetic sensor hardware
SPI.begin(CLK, MISO, MOSI);
sensor.init();
// SPI_2.begin(CLK, MISO, MOSI);
// // initialise magnetic sensor hardware
// sensor.init(&SPI_2);
// SPI_3.begin(CLK, MISO, MOSI);
// sensor.init(&SPI_3);

// pinMode(OnOff12V, OUTPUT);
// digitalWrite(OnOff12V, LOW); // Disonnect 12V to the driver and the FET’s

// monitoring port
motor.useMonitoring(Serial);

// align voltage
// motor.voltage_sensor_align = 3;

// link the motor to the sensor
motor.linkSensor(&sensor);

// driver config

// power supply voltage [V]
driver.voltage_power_supply = 12;

// pwm frequency to be used [Hz]
driver.pwm_frequency = 20000;

// initialise driver
driver.init();

// set driver voltage limit, this phase voltage
driver.voltage_limit = 3;

// link motor to the driver
motor.linkDriver(&driver);

// link the driver with the current sense
current_sense.linkDriver(&driver);

// set torque mode to be used
motor.torque_controller = TorqueControlType::voltage; // ( default )
// motor.torque_controller = TorqueControlType::dc_current;
// motor.torque_controller = TorqueControlType::foc_current;

// set control loop type to be used
// motor.controller = MotionControlType::torque;
// motor.controller = MotionControlType::velocity;
// motor.controller = MotionControlType::angle;
motor.controller = MotionControlType::velocity_openloop; // - velocity open-loop control
// motor.controller = MotionControlType::angle_openloop; // - position open-loop control

// Velocity loop PID
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 20;
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 = 300;
// Velocity low pass filtering time constant
// default 5ms - try different values to see what is the best.
// the lower the less filtered and less smooth operation.
motor.LPF_velocity.Tf = 0.01;

// angle loop PID
motor.P_angle.P = 20.0;
motor.P_angle.I = 0;
motor.P_angle.D = 0;
// acceleration control using output ramp
// this variable is in rad/s^2 and sets the limit of acceleration
motor.P_angle.output_ramp = 10000; // default 1e6 rad/s^2
// Angle ow pass filtering time constant
// default 0 - disabled
// use only for very noisy position sensors - try to avoid and keep the values very small
motor.LPF_angle.Tf = 0.0;

// Q axis
// current q loop PID - default
motor.PID_current_q.P = 5; // 3 - Arduino UNO/MEGA
motor.PID_current_q.I = 1000; // 300 - Arduino UNO/MEGA
motor.PID_current_q.D = 0;
// motor.PID_current_q.limit = motor.voltage_limit;
// motor.PID_current_q.ramp = 1000000; // 1000 - Arduino UNO/MEGA
// Low pass filtering time constant
motor.LPF_current_q.Tf = 0.005; // 0.01 - Arduino UNO/MEGA

// D axis (the aim of the control is to keep this current zero)
// PID parameters - default
motor.PID_current_d.P = 5; // 3 - Arduino UNO/MEGA
motor.PID_current_d.I = 1000; // 300 - Arduino UNO/MEGA
motor.PID_current_d.D = 0;
// motor.PID_current_d.limit = motor.voltage_limit;
// motor.PID_current_d.ramp = 1000000; // 1000 - Arduino UNO/MEGA
// Low pass filtering - default
motor.LPF_current_d.Tf= 0.005; // 0.01 - Arduino UNO/MEGA

// setting the limits
// maximal velocity of the position control
motor.velocity_limit = 10; // rad/s - default 20
motor.voltage_limit = 4; // Deze waarde wordt door SimpleFOC Conficuration Tool gebruikt
motor.current_limit = 2.0;

// use monitoring with serial for motor init
// monitoring port
Serial.begin(115200);
// comment out if not needed
motor.useMonitoring(Serial);
motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
motor.monitor_downsample = 1000;
motor.motion_downsample = 5.0;

// invert phase b gain
// current_sense.gain_b *=-1;
// skip alignment
// current_sense.skip_align = true;

// initialise motor
motor.init();

// init current sense
current_sense.init();
// driver 8302 has inverted gains on all channels
// current_sense.gain_a *=-1;
// current_sense.gain_b *=-1;
// current_sense.gain_c *=-1;

// link the motor to current sense
motor.linkCurrentSense(&current_sense);

// motor.sensor_direction = CW; //-----------------------------

// To skip Pole Pair Check this line must be before initFOC
// motor.zero_electric_angle = 4.76;

// align encoder and start FOC
motor.initFOC();

// set the inital target value
motor.target = 0;

// define the motor id
command.add(‘M’, doMotor, “motor”);

Serial.println(F(“Motor commands sketch | Initial motion control > torque/voltage : target 0.”));

_delay(1000);
}

void loop() {

// SPI.begin(CLK, MISO, MOSI);
// sensor.init();

// iterative setting of the FOC phase voltage
motor.loopFOC();

SPI.begin(CLK, MISO, MOSI);
sensor.init();
// iterative function setting the outter loop target
// velocity, position or voltage
// if target not set in parameter uses motor.target variable
motor.move();

// monitoring function outputting motor variables to the serial terminal 

motor.monitor();

// user communication
command.run();
}

Actually non of the PID, ramp and LPF settings make any difference. Even when I put ALL to 0.0 it behaves the same. Also it stops working smooth beyond +/-4 rad/sec velocity.

Hi @ppvernhout .

In the past, I used the ESP32Wroom32 with SimpleFOC and non-default SPI pins on both HSPI and VSPI. It worked like a charm.

I believe sensor init should be done like this:

MagneticSensorSPI sensor(MA730_SPI, U6_CS);
SPIClass spiEnc(HSPI);
spiEnc.begin(CLK, MISO, MOSI);
sensor.init(&spiEnc);

SPI.begin() and sensor.init() should be removed from the loop function.

Hope this helps.

1 Like