DRV8316 + STM32G431 design request for comments

Ok I still didn’t get the motor running.
But I did find something interesting with the config behaviour.

DRV8316Driver6PWM driver = DRV8316Driver6PWM(PHA_H, PHA_L, PHB_H, PHB_L, PHC_H, PHC_L, DRV_CS, true);
I assumed this would setPWMMode to PWM6_CurrentLimit_Mode. Setting current limit to true does not affect PWMMode.

driver.setPWMMode(PWM6_CurrentLimit_Mode);
But it does change when I set call this function in setup. The weird thing is, this even works when I use the DRV8316Driver3PWM CLASS.


That said, I’m not sure why the motor doesn’t move. I tried changing these

driver.enable();
driver.voltage_power_supply = 12;
driver.voltage_limit = 4;
motor.voltage_limit = 4;
motor.velocity_limit = 20;

There is no voltage in the motor phases. I checked the connections again, the hardware looks okay.
Anything else I should check for?

This is probably a kind of bug. We should probably align these different modes and setter functions so the resulting settings always make sense.

But as long as you can configure the mode you need (even if you need multiple calls that don’t seem logical) this isn’t a problem per se, just a useability issue.

When you set the 3-PWM vs. the 6-PWM mode, does it reflect in the status you print via printDRV8316Status()? I.e. have you seen any output that isn’t all-zero?

1 Like

Yes, the PWM mode changes according to 3pwm, 6pwm and currentlimit

serial output for this - driver.setPWMMode(PWM6_CurrentLimit_Mode);

So I think the SPI communication is going well. I don’t know why there is no voltage in the motor phases

Hmmm, it should not be needed according to the examples, but does it help if you add a motor.enable()?

Is the DRVOFF pin of the driver tied low, or are you controlling it from the MCU?

1 Like

:face_holding_back_tears: what have I done.

I simple left it NC

As per the datasheet, it has internal pulldown, so default low when unconnected.

However I don’t measure any voltage on that pin. So not sure whats the issue

But you’re right, the mosfets don’t seem to be enabled.

I will check with another board and confirm.

Edit:

I was measuring the voltage between the phases, between phase and ground. So the voltage was 0.

There is full voltage when I measure between a phase and Vin. So the low side mosfets are infact enabled. That’s relief, DRVOFF is infact internal pulldown.

To confim this, I soldered a wire to the DRVOFF. When I connected it to 5V, voltage between phase and Vin dropped. Indicating that the mosfets are disabled by DRVOFF.

I also checked the pwm outputs from the MCU. It is working well, So that means only the driver is the issue. I will see if there is any other way to debug this stuff.

Another day another update

I can confirm the driver mosfets are working but not with simplefoc.

Brute forced a commutation with analogwrite. Since all the Low side mosfet were enabled, I simply toggle pha_h, pha_b, pha_c one by one.

#include "Arduino.h"
#include <Wire.h>
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include "drivers/drv8316/drv8316.h"

SPIClass SPI_1(SPI_MOSI, SPI_MISO, SPI_SCK);
BLDCMotor motor = BLDCMotor(11);

DRV8316Driver6PWM driver = DRV8316Driver6PWM(PHA_H, PHA_L, PHB_H, PHB_L, PHC_H, PHC_L, DRV_CS, true);

// velocity set point variable
float target_velocity = 20.0;

void setup() {
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(LED_BUILTIN, HIGH);
  delay(100);
  Serial.begin(250000);
  Serial.println("Initializing...");

  driver.voltage_power_supply = 12.0;
  driver.voltage_limit = 12.0;
  driver.init(&SPI_1);
  driver.setSlew(Slew_25Vus);
  driver.setPWM100Frequency(FREQ_40KHz);
  driver.setBuckVoltage(VB_5V);
  driver.setOCPRetryTime(Retry5ms);
  //driver.enable();
  Serial.println("Init complete...");

  delay(100);
  printDRV8316Status();

  digitalWrite(LED_BUILTIN, LOW);
  Serial.println("Done");
}

void loop() {

  for (int i = 0; i < 6; i++) {
    int pins[3] = { PHA_H, PHB_H, PHC_H };
    for (int j = 0; j < 3; j++) {
      if (i == j) {
        for (int k = 0; k <= 40; k++) {
          analogWrite(pins[j], k);
          delay(10);
        }
      } else {
        analogWrite(pins[j], 0);
      }
    }
  }
}

Good news is the PCB is working well, no hardware errors found so far. I will look into the simplefoc code and check if anything is missed.

So far I have tested and confirmed these:

  • MT6701 is working
  • Driver SPI communication is good
  • Driver Mosfets are working

So the only thing left to check is the simplefoc code. On the hardware side I still have to check the CAN transceiver.

PS: The lights you’re seeing in the video visualizes BLDC commutation. It is made with 6 leds in delta configuration along with diodes and resistors for protection.

But you already mentioned that you could see the PWM output on the MCU? So that means SimpleFOC is working if that’s the case?

To me that would indicate there is still some kind of setup/initialization/enable problem that means SimpleFOC is producing output but the driver isn’t passing it on to the phases?

PS: I love your commutation visualizer :slight_smile: would you mind sharing its design in the forum here? I think many people would like it!

2 Likes

Yeah sure. Here’s the schematic.

Step file and stls are available here: GitHub - rambrosteam/BLDC-LED-Visualizer

  • Use diodes rated for your voltage. I use a maximum 12V, so this works fine.
  • Use a different colour for odd leds ( LED1, LED3, LED5 ) and even leds ( LED2, LED4, LED6 ).

The working principle is very simple:
The diodes make sure the odd and even light up according to the current direction. For low voltages (below 5V) you can get away without diodes since LED are also diodes.
This setup is connected to a 3 phase driver output. It allows us to visualize the active phase and current direction.

2 Likes

I once bought leds with 2 colors

Could also work with Low voltage

Finally got it working

Platformio was the issue, Arduino IDE works

I am using the generic G431 config without cordic and fdcan enabled. I assume it is using the internal clock now. So I will create a board def next
image

The past few days have been rough with this thing, Only last night I suspected that there might be some issue with platformio core since it is usually a bit outdated than the arduino cores.

Anyway It is finally working!


Look at that mesmerizing pwm.


My bad friend, I was getting pwm from the MCU but all pins were giving the same voltage. That’s how suspected it might actually have to do something with the platformio core. Now with this Arduino core I can confirm that the pwm is actually changing voltage according to commutation.

I still have to do the following:

  • create a board def for Arduino IDE
  • test the closed loop modes
  • test the CAN transceiver

@runger Huge thanks to you man

What a week fellas :facepunch:

Hey, I’m really glad you got it working!

But I’m not sure its really an issue with platformIO - I use it all the time for my development on SimpleFOC, and the G431 is one of the more used chips I test with.

So its definitely possible to get it working with platformIO and a “generic” G431 board.

If you’re happy to use ArduinoIDE we can drop this topic, but if you’d like to make PlatformIO work we can compare versions and try to find the issue for you…

1 Like

Yeah sure, I would like to find out what went wrong with the platformio setup. It would be nice to have both working.
I was just getting started with platformio, so I might have messed up something. This is my platform.ini file https://github.com/rambrosteam/MicroSpora-SimpleFOC/blob/main/firmware/Driver-DRV8316_diagnostics/platformio.ini


I am also getting an error with simplefoc arduino board defs. I tried to compile a blink example for lepton board. same error with the new board also.

.arduino15/packages/STMicroelectronics/hardware/stm32/2.8.1/system/STM32G0xx/system_stm32g0xx.c:201:39: note: in expansion of macro 'VECT_TAB_OFFSET'
  201 |   SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET;

I have also added this board to the fork (still need to configure clock settings), I will create a pull request once its ready.

Now I know whats wrong, I left out the PIN_ prefix
It is supposed to be like this:

    -D PIN_SPI_MOSI=PB5   ; SPI MOSI
    -D PIN_SPI_MISO=PB4   ; SPI MISO
    -D PIN_SPI_SCK=PB3    ; SPI Clock
    -D PIN_SPI_SS=PC4    ; SPI Chip Select (SS)
    -D DRV_CS=PIN_SPI_SS

With this I can now use the default SPI. No need to manually define a new SPI class.

1 Like

.arduino15/packages/STMicroelectronics/hardware/stm32/2.8.1/system/STM32G4xx/system_stm32g4xx.c: In function 'SystemInit':
<command-line>: error: expected expression before '{' token
.arduino15/packages/STMicroelectronics/hardware/stm32/2.8.1/system/STM32G4xx/system_stm32g4xx.c:199:39: note: in expansion of macro 'VECT_TAB_OFFSET'
  199 |   SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET;

I can’t get the arduino_simplefoc_boards working. This error shows with both boards, lepton and microspora.
The generic board defs compile well, but not the simplefoc defs
@runger can you please give some advice, I’m totally lost here.

I will look into this later this week, and try to add your board and the quadrans also… I’m a bit busy today…

1 Like

Thanks a ton man. I don’t think I could have got this working without your help :handshake:

Position mode example


Found a minor error:
I mislabelled PA15 as PA5. It is an exposed gpio at the bottom of the PCB.
That will be corrected in V2.

image

Some more photos of the board



3 Likes

I’m currently testing a similar setup with the DRV8316EVM and an STM32G431 Nucleo. Have you been able to get the low-side current sense to work?

Closed-loop torque control using voltage works, and currently trying to monitor the d and q currents using step 4 from the getting started. But getting an nFAULT (not sure which one) on the EVM and serial monitor gets stuck at:

STM32-DRV: Syncronising timers! Timer no. 1
STM32-DRV: Restarting �

I’ll try switching the default SPI DRV8316 to the non-SPI DRV8316C and see if it has anything to do with the DRV8316Driver6PWM.

#include "Arduino.h"
#include <Wire.h>
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include "drivers/drv8316/drv8316.h"

BLDCMotor motor = BLDCMotor(1);
DRV8316Driver6PWM driver = DRV8316Driver6PWM(PA8,PB13,PA9,PB14,PA10,PB15,PB6,false,PB10,PB12); // use the right pins for your setup!

// hall sensor instance
HallSensor sensor = HallSensor(PB4, PC11, PC10, 1);
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

//current sense
LowsideCurrentSense current_sense  = LowsideCurrentSense(2700, PA2, PA1, PA0);

//target variable
float target_voltage = 2;

// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }

void printDRV8316Status() {
	DRV8316Status status = driver.getStatus();
	Serial.println("DRV8316 Status:");
	Serial.print("Fault: ");
	Serial.println(status.isFault());
	Serial.print("Buck Error: ");
	Serial.print(status.isBuckError());
	Serial.print("  Undervoltage: ");
	Serial.print(status.isBuckUnderVoltage());
	Serial.print("  OverCurrent: ");
	Serial.println(status.isBuckOverCurrent());
	Serial.print("Charge Pump UnderVoltage: ");
	Serial.println(status.isChargePumpUnderVoltage());
	Serial.print("OTP Error: ");
	Serial.println(status.isOneTimeProgrammingError());
	Serial.print("OverCurrent: ");
	Serial.print(status.isOverCurrent());
	Serial.print("  Ah: ");
	Serial.print(status.isOverCurrent_Ah());
	Serial.print("  Al: ");
	Serial.print(status.isOverCurrent_Al());
	Serial.print("  Bh: ");
	Serial.print(status.isOverCurrent_Bh());
	Serial.print("  Bl: ");
	Serial.print(status.isOverCurrent_Bl());
	Serial.print("  Ch: ");
	Serial.print(status.isOverCurrent_Ch());
	Serial.print("  Cl: ");
	Serial.println(status.isOverCurrent_Cl());
	Serial.print("OverTemperature: ");
	Serial.print(status.isOverTemperature());
	Serial.print("  Shutdown: ");
	Serial.print(status.isOverTemperatureShutdown());
	Serial.print("  Warning: ");
	Serial.println(status.isOverTemperatureWarning());
	Serial.print("OverVoltage: ");
	Serial.println(status.isOverVoltage());
	Serial.print("PowerOnReset: ");
	Serial.println(status.isPowerOnReset());
	Serial.print("SPI Error: ");
	Serial.print(status.isSPIError());
	Serial.print("  Address: ");
	Serial.print(status.isSPIAddressError());
	Serial.print("  Clock: ");
	Serial.print(status.isSPIClockFramingError());
	Serial.print("  Parity: ");
	Serial.println(status.isSPIParityError());
	if (status.isFault())
		driver.clearFault();
	delayMicroseconds(1); // ensure 400ns delay
	DRV8316_PWMMode val = driver.getPWMMode();
	Serial.print("PWM Mode: ");
	Serial.println(val);
	delayMicroseconds(1); // ensure 400ns delay
	bool lock = driver.isRegistersLocked();
	Serial.print("Lock: ");
	Serial.println(lock);
}

void setup() {
	Serial.begin(115200);
  SimpleFOCDebug::enable(&Serial);

  sensor.pullup = Pullup::USE_EXTERN;
  sensor.init();
  sensor.enableInterrupts(doA, doB, doC);
  motor.linkSensor(&sensor);

	driver.voltage_power_supply = 24;
  driver.init();

	motor.linkDriver(&driver);
  current_sense.linkDriver(&driver);
  // current sense init hardware
  if(!current_sense.init()){
    Serial.println("Current sense init failed!");
    return;
  }
    // link the current sense to the motor
  motor.linkCurrentSense(&current_sense);
  motor.voltage_sensor_align = 6;
  // set motion control loop to be used
  motor.torque_controller = TorqueControlType::voltage;
  motor.controller = MotionControlType::torque;
  motor.useMonitoring(Serial);
  motor.monitor_downsample = 100; // set downsampling can be even more > 100
  motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // set monitoring of d and q currents

  // initialize motor
  if(!motor.init()){
    Serial.println("Motor init failed!");
    return;
  }
  //motor.zero_electric_angle = 0;
  //motor.sensor_direction = CW;
  // align sensor and start FOC
  if(!motor.initFOC()){
    Serial.println("FOC init failed!");
    return;
  }
	Serial.println("Init complete...");

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

	delay(100);
	printDRV8316Status();
}

void loop() {
  // main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  motor.move(target_voltage);

  // display the currents
  motor.monitor();
  // user communication
  command.run();
}

I also didn’t get the current sense to work, I got the error that current sense was not initialized, but not the timer error. I tried different gain settings in 8316.

Currently I am occupied with another project.
I will look into it again next week. I am determined to get this fully working.


edit: here’s the code I tried
Torque control MicroSpora-SimpleFOC/firmware/MicroSpora-FOC_Control/SimpleFOC_Torque/SimpleFOC_Torque.ino at main · rambros3d/MicroSpora-SimpleFOC · GitHub
ADC test - MicroSpora-SimpleFOC/firmware/MicroSpora-Test_Utils/Current_sensor-adc_test/Current_sensor-adc_test.ino at main · rambros3d/MicroSpora-SimpleFOC · GitHub
Even the adc test was problematic, I absolutely have no idea what’s up with stm32 and drv8316.