blackpill+DRV8302+CAN Bus project

HI everyone;
I am working on a project to do a closed loop angle control a BLCD through CAN bus. My intended set up is a blackpill (stm32f411ceu6 ) a DRV8302 driver board, mpc2515 for the can interface and a AS5600.

Before I got the blackpill I tried this set up with an Arduino2560 and it work just fine: I am able to give position commands to the motor through the CAN bus, and am able to get the motor “answers” while running through CAN as well. But when I switch to the blackpill it doesn’t work: when calibrating it is not able to estimate the pole pairs (wit the atmega250 the result is always right), and then got stuck and doesn’t turn.
Things that I checked:

  • I am able to read the rotor position with the blackpill , and it seems accurate when I turn it by and.
  • I am able to send this position through CAN, these two components work right together and the blackpill and there is no weird SPI interaction.
  • The motor spins just right with the blackpill in open loop speed mode.

What could be happening? Some incompatibility with blackpill and the AS5600 sensor?

Hi @Mansan

To try to solve the problem, it would be interesting to post the code you are using, the development environment, as well as information about your configuration (motor, sensor, etc.)

I had a problem like this several times and can only vaguely remember how I solved it. Aha, I remember, it was the direction pin on the sensor board. Also depending on your board you may require pull up resistors. Post a picture of your board. If it’s the little white boards with rounded edges, I can guarantee you the the problem is your direction pin. Ground it. Bon voyage!

Hi @JorgeMaker;

The motor is “handmade” with a 3d printed rotor and a 10010 stator. The motor has 21 pole pairs. The sensor is an AS5048, not an AS5600.

I am able to move the motor at a constant speed with this code:


#include <SimpleFOC.h>


// DRV8302 pins connections
// don't forget to connect the common ground pin
#define   INH_A PB_3
#define   INH_B PB_4
#define   INH_C PB_5
#define   EN_GATE PA_2
#define   M_PWM PB_7 
#define   M_OC PC_15
#define   OC_ADJ PC_14


// motor instance
BLDCMotor motor = BLDCMotor(21);

// driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);

// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6,  8);
int x=3;
// angle set point variable
float target_angle = 20;
// instantiate the commander
//Commander command = Commander(Serial);
//void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }

void setup() {
  // M_OC  - enable over-current protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);
  // M_PWM  - enable 3pwm mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,HIGH);
  // OD_ADJ - set the maximum over-current limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  // initialise magnetic sensor hardware
  

  // link the motor to the sensor

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


  // set motion control loop to be used
  motor.controller = MotionControlType::velocity_openloop;

  // contoller configuration
  // default parameters in defaults.h

  
  motor.voltage_limit = 10;

  // velocity low pass filtering time constant
  // the lower the less filtered
  motor.LPF_velocity.Tf = 0.1f;
motor.LPF_angle.Tf = 0.1f;
  // angle P controller
  motor.P_angle.P =12;
  // maximal velocity of the position control
  motor.velocity_limit = 20;
  // use monitoring with serial
  Serial.begin(115200);
  // comment out if not needed
  motor.useMonitoring(Serial);


  // initialize motor
  motor.init();
  // align sensor and start FOC
  //float offset = float(PI / 100.0) * 816;  //where guess = somewhere between 0 to 200.
//Direction direction = Direction::CW; // or Direction::CCW!
motor.initFOC();

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

  Serial.println(F("Motor ready."));
  //Serial.println(F("Set the target angle using serial terminal:"));
  _delay(1000);
}


void loop() {


  // main FOC algorithm function
  // the faster you run this function the better
  // Arduino UNO loop  ~1kHz
  // Bluepill loop ~10kHz
  motor.loopFOC();

  // Motion control function
  // velocity, position or voltage (defined in motor.controller)
  // this function can be run at much lower frequency than loopFOC() function
  // You can also use motor.move() and set the motor.target in the code
  motor.move(5);


  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
   motor.monitor();

  // user communication
  //command.run();
}

But the when I try to do a closed loop position control it doesn’t work. Either it “Fail to notice movement” or estimate a much lower number of pole pairs during calibration (the rotor does move). This is what I tried:

#include <SimpleFOC.h>


#define   INH_A PB_3
#define   INH_B PB_4
#define   INH_C PB_5
#define   EN_GATE PA_2
#define   M_PWM PB_7 
#define   M_OC PC_15
#define   OC_ADJ PC_14


const byte  Cs_pin_sensor=PB_8;

// motor instance
int nPolePairs=21;
BLDCMotor motor = BLDCMotor(nPolePairs);

// driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);



void setup() {
 
  Serial.begin(115200);
  SPI.begin();
  pinMode(PB_8, OUTPUT); //Pin CS - salida

  // M_OC  - enable over-current protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);

  // M_PWM  - enable 3pwm mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,HIGH);

MagneticSensorSPI sensor = MagneticSensorSPI(AS5048_SPI, Cs_pin_sensor);

  // OD_ADJ - set the maximum over-current limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  // initialise magnetic sensor hardware
  sensor.init();

  motor.linkSensor(&sensor);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 7;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // choose FOC modulation (optional)
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // set motion control loop to be used
  motor.controller = MotionControlType::angle;

  // contoller configuration
  // default parameters in defaults.h

  // velocity PI controller parameters
  motor.PID_velocity.P = 10.0f;
  motor.PID_velocity.I = 0.02f;
  motor.PID_velocity.D = 0.0f;
  // maximal voltage to be set to the motor
  motor.voltage_limit = 10;


  // angle P controller
  motor.P_angle.P = 10.0; 
  motor.P_angle.I = 0.1;  // usually only P controller is enough 
  motor.P_angle.D = 0.0;  // usually only P controller is enough   // maximal velocity of the position control
  motor.velocity_limit = 20;
  motor.voltage_sensor_align = 2;
  motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE |_MON_VOLT_Q|_MON_VOLT_D|_MON_CURR_Q|_MON_CURR_D;
 motor.useMonitoring(Serial);
motor.init();

  motor.initFOC();
  //initiate state machines
  Serial.println("Motor ready."); 

}

void loop() {

  motor.loopFOC();
  motor.move(1);

}

And as I said, it works in a Atmega2560.
@Anthony_Douglas
Sorry I got the sensor wrong, it is a AS5048_SPI.

Hi,

Please declare the sensor variable outside of the setup() function, like driver and motor:

MagneticSensorSPI sensor = MagneticSensorSPI(AS5048_SPI, Cs_pin_sensor);

void setup(){
...
}

otherwise it gets deallocated when the setup() function exits, which is not what we want :wink:

If you have access to an oscilloscope could you check if there is a PWM signal on pins corresponding to INH_A, INH_B, INH_C ?

I will try to check the PWM signals with an osciloscope.
What I tried is to replace the SPI interface of the sensor with the PWM, and run the following code:

#include <SimpleFOC.h>


#define   INH_A PB_3
#define   INH_B PB_4
#define   INH_C PB_5
#define   EN_GATE PA_2
#define   M_PWM PB_7 
#define   M_OC PC_15
#define   OC_ADJ PC_14


const byte  Cs_pin_sensor=PB_8;
byte PWM_PIN = PB_0;

// motor instance
int nPolePairs=21;
BLDCMotor motor = BLDCMotor(nPolePairs);

// driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);

MagneticSensorPWM sensor = MagneticSensorPWM(PWM_PIN, 4, 932);


void setup() {
 _delay(10000);
  Serial.begin(9600);
  SPI.begin();
  pinMode(PB_8, OUTPUT); //Pin CS - salida

  // M_OC  - enable over-current protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);

  // M_PWM  - enable 3pwm mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,HIGH);


  // OD_ADJ - set the maximum over-current limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  // initialise magnetic sensor hardware
  sensor.init();

  motor.linkSensor(&sensor);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 7;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // choose FOC modulation (optional)
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // set motion control loop to be used
  motor.controller = MotionControlType::angle;

  // contoller configuration
  // default parameters in defaults.h

  // velocity PI controller parameters
  motor.PID_velocity.P = 1.0f;
  motor.PID_velocity.I = 0.02f;
  motor.PID_velocity.D = 0.0f;
  // maximal voltage to be set to the motor
  motor.voltage_limit = 7;


  // angle P controller
  motor.P_angle.P = 1.0; 
  motor.P_angle.I = 0.0;  // usually only P controller is enough 
  motor.P_angle.D = 0.0;  // usually only P controller is enough   // maximal velocity of the position control
  motor.velocity_limit = 20;
  motor.voltage_sensor_align = 2;
  motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE |_MON_VOLT_Q|_MON_VOLT_D|_MON_CURR_Q|_MON_CURR_D;
 motor.useMonitoring(Serial);
motor.init();

  motor.initFOC();
  //initiate state machines
  Serial.println("Motor ready."); 

}

void loop() {

  motor.loopFOC();
  motor.move(1);
       motor.monitor();


}

And the motor is able to calibrate correctly ("PP check: OK!
") but is vibrates a lot (I got a similar behaviour with the atmega2560 and the sensor in PWM mode), so definitely there is something with the SPI interface.