DRV8316 + STM32G431 design request for comments

Here’s the schematic:

The board will be used to control this A2212 motor. We use these type of motors in our 3D printed RC vehicles. (trucks, cars, excavators…)

Interfaces:

  • CANBUS
  • UART
  • I2C
  • PWM
    I will mostly use PWM for now. The rest are just for testing purpose.

Notes:

  • DRV8316 motor driver wired with 6PWM. Used a 5V zener as vref to provide pullup for NSLEEP
  • VIO of IF1044VD CAN transceiver connected to PC13 to hopefully prevent conflict of RXD pin with PB8-BOOT0
  • 10k pull-up for NRST, don’t want capacitative touch for reset :joy: @dekutree64
  • Planning to go with a 1.2mm 6-layer board and economic assembly

This will be my first PCB using a STM32 MCU. My previous PCBs were limited to ESP32 series and RP2040
I used the CubeMX to determine the pins - PWM, I2C, UART, FDCAN


I would like to program this directly from USB with Arduino IDE. Do I need to use STM32Cube IDE or ST-Link to configure this MCU for the first time? Or can we directly start using this board from the Arduino IDE.

Thank you everyone

Hey @rambros, I think it would be a better idea to make a separate forum post for your driver board schematic, that way it’s really clear which board people are commenting on.

1 Like

You’re right.
@runger thanks for taking care of this issue

Hey, I have split it off to its own topic, as per @nanoparticle’s request

Regarding your questions:

Not if you don’t need a special BOOT0 configuration. It has a built-in boot loader so it is good to go.

I don’t think so. You need to select a board definition in ArduinoIDE before you can use a board, and I am not sure the generic board definition for G431 will work:

  • you seem to have a different clock configuration to the generic variant, using an external oscillator
  • you probably want FDCAN and CORDIC support
  • you’re using USART4 and none of the others which will lead to strange serial port object naming

So working with this board will require a little bit of work on the part of the user. You can make it easier for them by providing a board definition, but they will still have to install that from wherever you provide it.

1 Like

Taking a quick look at your schematic, here is my feedback:

  1. Would recommend adding a limiting resistor to your crystal oscillator, even if you just use a zero ohm resistor.
  2. Would recommend exposing the remaining IO as a pin header or connector, though maybe these are on a different page because I don’t see your SWD connector here either
  3. DRV8316 buck starts in 3.3V mode by default, and the diode forward voltage plus LDO dropout voltage might be too low for the mcu in this initial condition.

Other than that, looks pretty good!

1 Like

You sure 8316 is big enough for that motor? That’s a tiny driver. You’ll be tripping like the finale on a Burning Man festival.

Cheers,
Valentine

PS Please read very carefully page 70, table 9-1, line #2 of the design document.

1 Like

@Valentine you have a good point.

In our tests the peak consumption was only 6-7A and the average is 2-3A. It is borderline near the safety margin, I usually like to have atleast 2x.

Beyond 6A at 11.1V (3S), The 3D printed gears started melting. So the model is not compatible more than 60W. That’s why I stuck with DRV8316, since board size should also be small - I will have to rethink my choices.

Thank you, I totally missed that part. I was just looking through the board variants

I will have to make it compatible with the generic board def.
And enable FDCAN and CORDIC in code.

If I get rid of the crystal (to save some board space), the MCU will use the High Speed Internal clock. This might have enough accuracy for PWM and ADC. And make the Clock Recovery System work with the USB connection. Thanks again

Thank you - Thats something I never thought of. I will look into that :+1:

I usually add the connectors at last after the schematic is finalized.

You’re right I should fix this too
Thanks again

Users who want this will have to set appropriate build flags in the environment. Unfortunately you can’t enable them just with code if they are not in the board definition.

It will work fine with the internal oscillator, but it does affect performance if you’re into very high performance use cases…
Someone here in the forum compared the velocity stability of a turntable with and without external oscillator and there was a difference.

1 Like

Thank you, I looked into the thread you were referring to.
https://community.simplefoc.com/t/arduino-mini-r4-poor-performance/3945/42

And you have also convinced me to create a new board def - that looks like the best way forward.
I thought of using B_G431_ESC1 variant but it cant use USB DFU since the (PA11) D- is used by CAN_RX.

I will fix all the issues and concerns everyone mentioned. Thanks a ton guys :+1:

If you do decide to create a board definition, I can offer to host it here if you like: GitHub - simplefoc/simplefoc_arduino_boards: Arduino board vendor files for SimpleFOC boards - just send us a pull request :slight_smile:

Also, as an alternative, working with new boards is far easier in PlatformIO. For PlatformIO you could provide a GitHub project including all the needed files to get your board working with custom clock and all, which people could just git clone and use with a standard PlatformIO install.

1 Like

@runger That’s awesome, I will create a pull request when the board is tested.

@nanoparticle I have used a power ORing with PMOS to address the voltage drop issue you mentioned

Here’s the link to the full schematic:
https://pro.easyeda.com/editor#id=9ac00872234849bb980a836700ccab2e,tab=*c797a62a637c408481f37c2b62597a91

2 Likes

Good news fellas, Boards have finally arrived

Here’s the pinout graphics

PCB photos


My Testing setup with a A2212 Motor


This is powered by a 2S 7.4V battery

Good thing is; the board didn’t release the magic smoke! The blink code works.
I still need to make the DRV8316 & MT6701 work. Still a long way to go I guess.

@runger As per your suggestion I am now working with Platformio. I am getting used to it. After the testing is done, I think I should create Arduino board def too.

I will keep you guys updated on this :handshake:

4 Likes

The MT6701 is working great

It has to use the SPI_2 bus since the default bus is used by the DRV8316
The ENC_NC is a dummy pin for the SPI_2 MOSI

// MicroSpora-MT6701_Serial

#include "Arduino.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/mt6701/MagneticSensorMT6701SSI.h"

// MT6701 pin mapping
// ENC_NC - PA7
// ENC_SDO - PA6
// ENC_CLK - PA5
// ENC_CS - PA4

//  Use SPI_2 for sensor since default SPI will be used by DRV8316C
SPIClass SPI_2(ENC_NC, ENC_SDO, ENC_CLK);
MagneticSensorMT6701SSI sensor = MagneticSensorMT6701SSI(ENC_CS);

void setup() {

  Serial.begin(250000);
  Serial.println("MT6701 Sensor ready");

  sensor.init(&SPI_2);  //  Initialize sensor on SPI_2 bus

  _delay(1000);
}


void loop() {
  sensor.update();

  float radians = sensor.getAngle();
  float degrees = radians * (180.0 / PI);

  Serial.print("Angle: rad = ");
  Serial.print(radians, 4);

  Serial.print("\tdeg = ");
  Serial.print(degrees, 2);

  float velocity = sensor.getVelocity();
  float rpm = velocity * (60.0 / (2.0 * PI));

  Serial.print("\t  Velocity: rad/s = ");
  Serial.print(velocity);

  Serial.print("\t  RPM = ");
  Serial.println(rpm);

  _delay(100);
}

Serial Monitor output

So far so good

all code is available on this repo

I will now check the DRV8316

Hey, that’s looking really great!

1 Like

If you’d like to implement the CRC you can try the following code:

#include <SPI.h>

const int csPin = PB6; //SPI chip select pin

// CRC-6 lookup table for polynomial X^6 + X^1 + 1
const uint8_t crcTable[64] = {
 0x00, 0x03, 0x06, 0x05, 0x0C, 0x0F, 0x0A, 0x09,
 0x18, 0x1B, 0x1E, 0x1D, 0x14, 0x17, 0x12, 0x11,
 0x30, 0x33, 0x36, 0x35, 0x3C, 0x3F, 0x3A, 0x39,
 0x28, 0x2B, 0x2E, 0x2D, 0x24, 0x27, 0x22, 0x21,
 0x23, 0x20, 0x25, 0x26, 0x2F, 0x2C, 0x29, 0x2A,
 0x3B, 0x38, 0x3D, 0x3E, 0x37, 0x34, 0x31, 0x32,
 0x13, 0x10, 0x15, 0x16, 0x1F, 0x1C, 0x19, 0x1A,
 0x0B, 0x08, 0x0D, 0x0E, 0x07, 0x04, 0x01, 0x02
};

void setup() {
  SPI.begin();
  SPI.setClockDivider(SPI_CLOCK_DIV32); // Adjust the clock speed if needed
  SPI.setDataMode(SPI_MODE1);           // MT6701 Mode 1
  SPI.setBitOrder(MSBFIRST);

  pinMode(csPin, OUTPUT);
  digitalWrite(csPin, HIGH);            // Keep CS high (inactive)
  
  Serial.begin(115200);                
}

uint32_t readDataMT6701() {
  digitalWrite(csPin, LOW);

  // Read 24 bits from the MT6701
  uint8_t byte1 = SPI.transfer(0x00);
  uint8_t byte2 = SPI.transfer(0x00);
  uint8_t byte3 = SPI.transfer(0x00);

  digitalWrite(csPin, HIGH);

  // Combine the 3 bytes into a 24-bit unsigned integer
  uint32_t data = ((uint32_t)byte1 << 16) | ((uint32_t)byte2 << 8) | byte3;

  return data;
}

uint16_t extractAngleData(uint32_t data) {
  // Extract the 14-bit angle data (bits 0 to 13)
  return (data >> 10) & 0x3FFF;  // Shift right by 10 bits and mask 14 bits (0x3FFF)
}

uint8_t extractCRC(uint32_t data) {
  // Extract the 6-bit CRC data (bits 18 to 23)
  return data & 0x3F;  // Mask the lower 6 bits
}

uint8_t calculateCRC(uint32_t data) {
  // Combine the 14-bit angle data and 4-bit status into 18 bits
  uint32_t combinedData = data >> 6;  // Shift out the 6-bit CRC
  
  uint8_t crc = 0;
  
  // Process the data 6 bits at a time (from MSB to LSB)
  crc = crcTable[(crc ^ (combinedData >> 12)) & 0x3F];  // First 6 bits
  crc = crcTable[(crc ^ (combinedData >> 6)) & 0x3F];   // Second 6 bits
  crc = crcTable[(crc ^ combinedData) & 0x3F];          // Last 6 bits
  
  return crc;
}
1 Like

Thank you @Daan87423
Your code looks like it should be implemented in the driver library.

The CRC would increase the reliability and safety factor. I will look into it after I get the DRV8316 SPI working.
But if you want me to test something specific, let me know.

I am just getting started with this STM32 stuff, It took a lot of time to just get this MT6701 example working. (the new SPI_2 definitons were over my head first)

And now the DRV8316 SPI connection is messing with me.

DRV8316 SPI error

I initially started with A2212 motor, but it also had errors.
Assuming the errors were triggered due to the low resistance of the motor.

I made this setup with a 2204 gimbal motor and 7.4V battery. But the errors prevail.

This is my testing setup for open loop

I am using this code from the Arduino-FOC-drivers example

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

//BLDCMotor motor = BLDCMotor(11);
//DRV8316Driver6PWM driver = DRV8316Driver6PWM(0,1,2,3,4,6,7,false); // use the right pins for your setup!

BLDCMotor motor = BLDCMotor(11);
DRV8316Driver6PWM driver = DRV8316Driver6PWM(PHA_H, PHA_L, PHB_H, PHB_L, PHC_H, PHC_L, DRV_CS, false);


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);
  while (!Serial);
  delay(1);
  Serial.println("Initializing...");

  driver.voltage_power_supply = 12;
  driver.init();
  motor.linkDriver(&driver);
  motor.controller = MotionControlType::velocity_openloop;
  motor.voltage_limit = 3;
  motor.velocity_limit = 20;
  motor.init();
  Serial.println("Init complete...");

  delay(100);
  printDRV8316Status();
}


// velocity set point variable
float target_velocity = 7.0;


void loop() {
  motor.move(target_velocity);
}

And here’s the platform.ini


[env:SIMPLEFOC_MICROSPORA]
platform = ststm32
board = genericSTM32G431CB
framework = arduino

lib_archive = false
monitor_speed = 250000

upload_protocol = dfu

lib_deps = 
	askuric/Simple FOC@^2.3.4
	simplefoc/SimpleFOCDrivers@^1.0.8
	SPI
	Wire

build_flags = 

  	-D PIO_FRAMEWORK_ARDUINO_ENABLE_CDC	; Enable Serial Output
    -D CORE_DEBUG_LEVEL=3  ; Set debug level to verbose (optional)

    -D HSE_VALUE=16000000UL ; External crystal value 16 MHz
    -D HAL_CORDIC_MODULE_ENABLED    ; Enables the CORDIC module
    -D HAL_FDCAN_MODULE_ENABLED     ; Enables the FDCAN module

	-D LED_BUILTIN=PC6   ; On-board LED

    ; Motor driver drv8316 - 6PWM
    -D PHA_H=PA10      ; High-side PWM for phase A
    -D PHA_L=PB15      ; Low-side PWM for phase A
    -D PHB_H=PA9      ; High-side PWM for phase B
    -D PHB_L=PB14      ; Low-side PWM for phase B
    -D PHC_H=PA8      ; High-side PWM for phase C
    -D PHC_L=PB13      ; Low-side PWM for phase C

	-D PIN_ISENSA=PA0	; Phase A current sense
	-D PIN_ISENSB=PA1	; Phase B current sense
	-D PIN_ISENSC=PA2	; Phase C current sense

    -D SPI_MOSI=PB5   ; SPI MOSI
    -D SPI_MISO=PB4   ; SPI MISO
    -D SPI_SCK=PB3    ; SPI Clock
    -D SPI_SS=PC4    ; SPI Chip Select (SS)
    -D DRV_CS=SPI_SS  
    
	; MT6701 14bit Magnetic encoder
	-D ENC_SDO=PA6  ; configured as MISO
    -D ENC_NC=PA7   ; Not connected (dummy MOSI)
	-D ENC_CLK=PA5
	-D ENC_CS=PA4

	; 1044 CAN Transceiver
    -D CAN_RX=PB8      ; CAN Receive Pin
    -D CAN_TX=PB9      ; CAN Transmit Pin
    -D CAN_ENABLE=PC13      ; CAN Transmit Pin

	; Voltage Divider
	-D VSENS=PB11 ; Voltage sense pin
    -D VSCALE=11.0 ; Scaling factor

I have no experience with SPI drivers in SimpleFOC, Is anything off here? Anything specific to look for

The way you’re initializing the driver it is using the default SPI object with the default pins… does that in fact correspond to your setup?

1 Like

Thanks you very much @runger , Your instinct was correct, thats exactly the issue.

I had this in the platform.ini build flags. But don’t know why it doesn’t work.
image

So instead I manually set the pins in the SPI_1 class

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, false);

I can confirm that this setup works, I checked the voltage output from the inbuilt buck converter.
Previously it was only 3.3V (default). Now it is set to 5V with SPI.

  driver.init(&SPI_1);
  driver.setBuckVoltage(VB_5V);
  driver.setOCPLevel(Curr_16A);
  driver.setOCPMode(AutoRetry_Fault);
  driver.setOCPRetryTime(Retry500ms);
  driver.setSlew(Slew_50Vus);

That’s a relief to know that the driver is communication correctly.

Full driver test code

MicroSpora-SimpleFOC/firmware/Driver-DRV8316_diagnostics/src/main.cpp at main · rambrosteam/MicroSpora-SimpleFOC · GitHub


#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, false);


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);
  while (!Serial);
  delay(1);
  Serial.println("Initializing...");

  driver.voltage_power_supply = 12;
  driver.init(&SPI_1);
  driver.setBuckVoltage(VB_5V);
  driver.setOCPLevel(Curr_24A);
  driver.setOCPMode(AutoRetry_Fault);
  driver.setOCPRetryTime(Retry500ms);
  driver.setSlew(Slew_25Vus);

  motor.linkDriver(&driver);
  motor.controller = MotionControlType::velocity_openloop;
  motor.voltage_limit = 4;
  motor.velocity_limit = 20;
  motor.init();
  Serial.println("Init complete...");

  delay(100);
  printDRV8316Status();
}


// velocity set point variable
float target_velocity = 7.0;


void loop() {
  motor.move(target_velocity);
}

The serial monitor shows no errors now

However, The motor is still not running. No vibrations or any movements.
motor.move(target_velocity);
I can move it freely without any resistance.

Let’s see if I missed something. I will check again and update you tomorrow.