Current Sensing using DRV8302

Hi @thewrongbutton -

Below is sample code to use the DRV8302 with a Nucelo F401RE board in 3 PWM mode, with full current sensing. I m using an AS5048A SPI angle sensor. Note the gains I used, along with the inversion of them in the code.

Note - some of the code is specific to my project, and also, the current PID gains are specific for a large AC servo motor. It works great!

#include <Arduino.h>
#include <SimpleFOC.h>

// DRV8302 pins connections
#define INH_A PA8
#define INH_B PA9
#define INH_C PA10

#define EN_GATE PB7
#define M_PWM PB4
#define M_OC PB3
#define OC_ADJ PB6
#define OC_GAIN PB5

#define IOUTA A0
#define IOUTB A1
#define IOUTC A2

// Motor instance
BLDCMotor motor = BLDCMotor(4);
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);

// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);

// encoder instance
MagneticSensorSPI encoder = MagneticSensorSPI(AS5048_SPI, 14);

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

long time_ms = 0;
double iq_sp_A = 0;
double iq_max_A = 0.8;

double initial_position_rads = 0;
double position_rads = 0;
double delta_position_rads = 0;

float angle_rads = 0;

void setup() {

  //pinMode(PA5, OUTPUT);
  // initialize encoder sensor hardware
  encoder.init();
  
  // link the motor to the sensor
  motor.linkSensor(&encoder);

  // DRV8302 specific code
  // M_OC  - enable overcurrent 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 overcurrent limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  pinMode(OC_GAIN,OUTPUT);
  digitalWrite(OC_GAIN,LOW);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.pwm_frequency = 20000; // suggested under 18khz

  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  cs.linkDriver(&driver);

  // align voltage
  motor.voltage_sensor_align = 2.0;
  
  // control loop type and torque mode 
  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller = MotionControlType::velocity;
  motor.motion_downsample = 1.0;

  // velocity loop PID
  motor.PID_velocity.P = 0.18;
  motor.PID_velocity.I = 7.0;
  motor.LPF_velocity.Tf = 0.007;
  
  // angle loop PID
  motor.P_angle.P = 25.0;
  motor.LPF_angle.Tf = 0.005;

  // current q loop PID 
  motor.PID_current_q.P = 5.0;
  motor.PID_current_q.I = 500.0;
  motor.LPF_current_q.Tf = 0.005;

  // current d loop PID
  motor.PID_current_d.P = 5.0;
  motor.PID_current_d.I = 500.0;
  motor.LPF_current_d.Tf = 0.005;

  // Limits 
  motor.velocity_limit = 20.0; 
  motor.voltage_limit = 7.0;   // 12 Volt limit 
  motor.current_limit = 2.0;    // 2 Amp current limit

  // use monitoring with serial for motor init
  // monitoring port
  Serial.begin(115200);
  motor.useMonitoring(Serial);
  motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
  motor.monitor_downsample = 0;

  // initialise motor
  motor.init();

  cs.init();
  cs.skip_align = true;
  // driver 8302 has inverted gains on all channels
  cs.gain_a *= -1;
  cs.gain_b *= -1;
  cs.gain_c *= -1;
  motor.linkCurrentSense(&cs);

  // align encoder and start FOC
  motor.initFOC(1.94, Direction::CW);
  
  // set the inital target value
  motor.target = 0.0;

  // define the motor id
  command.add('M', onMotor, "motor");

  Serial.println(F("Full control example: "));
  Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
  Serial.println(F("Initial motion control loop is voltage loop."));
  Serial.println(F("Initial target voltage 2V."));

  _delay(1000);
  
  initial_position_rads = encoder.getAngle();
  time_ms = millis();
  
}

void loop() {

  // iterative setting FOC phase voltage
  motor.loopFOC();
  
  float val = 12.0*sin(millis()/1000.0);
  motor.move(val);

  // monitoring the state variables
  motor.monitor();

  // user communication
  command.run(); 
  
  // if (millis() - time_ms > 5){
  //   PhaseCurrent_s current = cs.getPhaseCurrents();
  //   Serial.print(current.a);
  //   Serial.print("\t");
  //   Serial.print(current.b);
  //   Serial.print("\t");
  //   Serial.print(current.c);
  //   Serial.println("");
  //   time_ms = millis();
  // }

}
1 Like