try to fix submodule
This commit is contained in:
175
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/README.md
Normal file
175
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/README.md
Normal file
@@ -0,0 +1,175 @@
|
||||
|
||||
# DRV8316 SimpleFOC driver
|
||||
|
||||
The DRV8316 is a integrated FET, integrated current sensing 3-phase BLDC driver IC from Texas Instruments, including all protections and many cool configuration optons. See https://www.ti.com/product/DRV8316 for more information.
|
||||
|
||||
This driver includes a DRV8316 SPI driver, and specific subclasses for SimpleFOCs BLDCDriver3PWM and BLDCDriver6PWM generic drivers. The code is designed to be "Ardunio compatible" and should work with any of the hardware architectures supported by SimpleFOC.
|
||||
|
||||
## Hardware setup
|
||||
|
||||
To use the DRV8316 you will have to connect the following:
|
||||
|
||||
- GND
|
||||
- SPI MOSI
|
||||
- SPI MISO
|
||||
- SPI CLK
|
||||
- SPI nCS
|
||||
- INH_U - connect to motor PWM pin
|
||||
- INH_V - connect to motor PWM pin
|
||||
- INH_W - connect to motor PWM pin
|
||||
- INL_U - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
- INL_V - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
- INL_W - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
|
||||
Optionally, but probably useful:
|
||||
|
||||
- nFault - digital in, active low
|
||||
- DRVOFF - digital out
|
||||
|
||||
For current sensting:
|
||||
|
||||
- VREF - either connect to DAC output of the MCU or a fixed voltage reference.
|
||||
- ISENA - connect to analog in
|
||||
- ISENB - connect to analog in
|
||||
- ISENC - connect to analog in
|
||||
|
||||
For current limiting:
|
||||
|
||||
- ILIM (same as VREF) - connect it to a DAC output of the MCU if you want to control the current limit from the MCU
|
||||
|
||||
## Usage
|
||||
|
||||
Usage is quite easy, especially if you already know SimpleFOC. See also the [examples](https://github.com/simplefoc/Arduino-FOC-drivers/examples/drivers/drv8316/)
|
||||
|
||||
```c++
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include <SimpleFOC.h>
|
||||
#include <Math.h>
|
||||
#include "SimpleFOCDrivers.h"
|
||||
#include "drivers/drv8316/drv8316.h"
|
||||
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
DRV8316Driver6PWM driver = DRV8316Driver6PWM(A3,0,A4,1,2,6,7,false); // MKR1010 6-PWM
|
||||
|
||||
//... normal simpleFOC init code...
|
||||
```
|
||||
|
||||
Or, for 3-PWM:
|
||||
|
||||
```c++
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include <SimpleFOC.h>
|
||||
#include <Math.h>
|
||||
#include "SimpleFOCDrivers.h"
|
||||
#include "drivers/drv8316/drv8316.h"
|
||||
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
DRV8316Driver3PWM driver = DRV8316Driver3PWM(A3,A4,2,7,false); // MKR1010 3-PWM
|
||||
// these are examples, for 3-PWM you could use any output pins as the enable pins.
|
||||
#define ENABLE_A 0
|
||||
#define ENABLE_B 1
|
||||
#define ENABLE_C 6
|
||||
|
||||
void setup() {
|
||||
|
||||
|
||||
pinMode(ENABLE_A, OUTPUT);
|
||||
digitalWrite(ENABLE_A, 1); // enable
|
||||
pinMode(ENABLE_B, OUTPUT);
|
||||
digitalWrite(ENABLE_B, 1); // enable
|
||||
pinMode(ENABLE_C, OUTPUT);
|
||||
digitalWrite(ENABLE_C, 1); // enable
|
||||
|
||||
|
||||
//... normal simpleFOC init code...
|
||||
|
||||
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
You can use the driver's features. In general you can do this at any time, but certain features only make sense at setup-time (e.g. setting the PWM mode, which is handled automatically by the DRV8316Driver3PWM class, or setting the current limit, which you generally want to get done before applying power to the motor).
|
||||
|
||||
Driver usage, for example reading and printing the complete status:
|
||||
|
||||
```c++
|
||||
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);
|
||||
```
|
||||
|
||||
|
||||
Setting options can be conveniently done via the provided setter methods. All documented registers and options are available via the driver, and the option values can be accessed via enums.
|
||||
|
||||
Leave at least 400ns delay between reading and/or writing options to ensure you don't talk to the DRV8316 too quickly:
|
||||
|
||||
```c++
|
||||
driver.setPWM100Frequency(DRV8316_PWM100DUTY::FREQ_40KHz);
|
||||
delayMicroseconds(1); // ensure 400ns delay
|
||||
driver.setBuckVoltage(DRV8316_BuckVoltage::VB_5V7);
|
||||
```
|
||||
|
||||
|
||||
### Current sensing
|
||||
|
||||
TODO...
|
||||
|
||||
### Current limiting
|
||||
|
||||
TODO...
|
||||
|
||||
586
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/drv8316.cpp
Normal file
586
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/drv8316.cpp
Normal file
@@ -0,0 +1,586 @@
|
||||
|
||||
|
||||
#include "./drv8316.h"
|
||||
|
||||
|
||||
void DRV8316Driver3PWM::init(SPIClass* _spi) {
|
||||
DRV8316Driver::init(_spi);
|
||||
setRegistersLocked(false);
|
||||
delayMicroseconds(1);
|
||||
DRV8316Driver::setPWMMode(DRV8316_PWMMode::PWM3_Mode);
|
||||
BLDCDriver3PWM::init();
|
||||
};
|
||||
|
||||
|
||||
void DRV8316Driver6PWM::init(SPIClass* _spi) {
|
||||
DRV8316Driver::init(_spi);
|
||||
setRegistersLocked(false);
|
||||
delayMicroseconds(1);
|
||||
DRV8316Driver::setPWMMode(DRV8316_PWMMode::PWM6_Mode); // default mode is 6-PWM
|
||||
BLDCDriver6PWM::init();
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* SPI setup:
|
||||
*
|
||||
* capture on falling, propagate on rising =
|
||||
* MSB first
|
||||
*
|
||||
* 16 bit words
|
||||
* outgoing: R/W:1 addr:6 parity:1 data:8
|
||||
* incoming: status:8 data:8
|
||||
*
|
||||
* on reads, incoming data is content of register being read
|
||||
* on writes, incomnig data is content of register being written
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
void handleInterrupt() {
|
||||
|
||||
}
|
||||
|
||||
void DRV8316Driver::init(SPIClass* _spi) {
|
||||
// TODO make SPI speed configurable
|
||||
spi = _spi;
|
||||
settings = SPISettings(1000000, MSBFIRST, SPI_MODE1);
|
||||
|
||||
//setup pins
|
||||
pinMode(cs, OUTPUT);
|
||||
digitalWrite(cs, HIGH); // switch off
|
||||
|
||||
//SPI has an internal SPI-device counter, it is possible to call "begin()" from different devices
|
||||
spi->begin();
|
||||
|
||||
if (_isset(nFault)) {
|
||||
pinMode(nFault, INPUT);
|
||||
// TODO add interrupt handler on the nFault pin if configured
|
||||
// add configuration for how to handle faults... idea: interrupt handler calls a callback, depending on the type of fault
|
||||
// consider what would be a useful configuration in practice? What do we want to do on a fault, e.g. over-temperature for example?
|
||||
|
||||
//attachInterrupt(digitalPinToInterrupt(nFault), handleInterrupt, PinStatus::FALLING);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::getParity(uint16_t data) {
|
||||
//PARITY = XNOR(CMD, A5..A0, D7..D0)
|
||||
uint8_t par = 0;
|
||||
for (int i=0;i<16;i++) {
|
||||
if (((data)>>i) & 0x0001)
|
||||
par+=1;
|
||||
}
|
||||
return (par&0x01)==0x01; // even number of bits means true
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
uint16_t DRV8316Driver::readSPI(uint8_t addr) {
|
||||
digitalWrite(cs, 0);
|
||||
spi->beginTransaction(settings);
|
||||
uint16_t data = (((addr<<1) | 0x80)<<8)|0x0000;
|
||||
if (getParity(data))
|
||||
data |= 0x0100;
|
||||
uint16_t result = spi->transfer16(data);
|
||||
spi->endTransaction();
|
||||
digitalWrite(cs, 1);
|
||||
// Serial.print("SPI Read Result: ");
|
||||
// Serial.print(data, HEX);
|
||||
// Serial.print(" -> ");
|
||||
// Serial.println(result, HEX);
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
uint16_t DRV8316Driver::writeSPI(uint8_t addr, uint8_t value) {
|
||||
digitalWrite(cs, 0);
|
||||
spi->beginTransaction(settings);
|
||||
uint16_t data = ((addr<<1)<<8)|value;
|
||||
if (getParity(data))
|
||||
data |= 0x0100;
|
||||
uint16_t result = spi->transfer16(data);
|
||||
spi->endTransaction();
|
||||
digitalWrite(cs, 1);
|
||||
// Serial.print("SPI Write Result: ");
|
||||
// Serial.print(data, HEX);
|
||||
// Serial.print(" -> ");
|
||||
// Serial.println(result, HEX);
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
|
||||
DRV8316Status DRV8316Driver::getStatus() {
|
||||
IC_Status data;
|
||||
Status__1 data1;
|
||||
Status__2 data2;
|
||||
uint16_t result = readSPI(IC_Status_ADDR);
|
||||
data.reg = (result & 0x00FF);
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = readSPI(Status__1_ADDR);
|
||||
data1.reg = (result & 0x00FF);
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = readSPI(Status__2_ADDR);
|
||||
data2.reg = (result & 0x00FF);
|
||||
return DRV8316Status(data, data1, data2);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void DRV8316Driver::clearFault() {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.CLR_FLT |= 1;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__2_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isRegistersLocked(){
|
||||
uint16_t result = readSPI(Control__1_ADDR);
|
||||
Control__1 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.REG_LOCK==REG_LOCK_LOCK;
|
||||
}
|
||||
void DRV8316Driver::setRegistersLocked(bool lock){
|
||||
uint16_t result = readSPI(Control__1_ADDR);
|
||||
Control__1 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.REG_LOCK = lock?REG_LOCK_LOCK:REG_LOCK_UNLOCK;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__1_ADDR, data.reg);
|
||||
}
|
||||
|
||||
|
||||
|
||||
DRV8316_PWMMode DRV8316Driver::getPWMMode() {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_PWMMode)data.PWM_MODE;
|
||||
};
|
||||
void DRV8316Driver::setPWMMode(DRV8316_PWMMode pwmMode){
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.PWM_MODE = pwmMode;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__2_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_Slew DRV8316Driver::getSlew() {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_Slew)data.SLEW;
|
||||
};
|
||||
void DRV8316Driver::setSlew(DRV8316_Slew slewRate) {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.SLEW = slewRate;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__2_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_SDOMode DRV8316Driver::getSDOMode() {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_SDOMode)data.SDO_MODE;
|
||||
};
|
||||
void DRV8316Driver::setSDOMode(DRV8316_SDOMode sdoMode) {
|
||||
uint16_t result = readSPI(Control__2_ADDR);
|
||||
Control__2 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.SDO_MODE = sdoMode;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__2_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isOvertemperatureReporting(){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.OTW_REP==OTW_REP_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setOvertemperatureReporting(bool reportFault){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OTW_REP = reportFault?OTW_REP_ENABLE:OTW_REP_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__3_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isSPIFaultReporting(){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.SPI_FLT_REP==SPI_FLT_REP_ENABLE;
|
||||
}
|
||||
void DRV8316Driver::setSPIFaultReporting(bool reportFault){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.SPI_FLT_REP = reportFault?SPI_FLT_REP_ENABLE:SPI_FLT_REP_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__3_ADDR, data.reg);
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isOvervoltageProtection(){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.OVP_EN==OVP_EN_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setOvervoltageProtection(bool enabled){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OVP_EN = enabled?OVP_EN_ENABLE:OVP_EN_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__3_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_OVP DRV8316Driver::getOvervoltageLevel(){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_OVP)data.OVP_SEL;
|
||||
};
|
||||
void DRV8316Driver::setOvervoltageLevel(DRV8316_OVP voltage){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OVP_SEL = voltage;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__3_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_PWM100DUTY DRV8316Driver::getPWM100Frequency(){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_PWM100DUTY)data.PWM_100_DUTY_SEL;
|
||||
};
|
||||
void DRV8316Driver::setPWM100Frequency(DRV8316_PWM100DUTY freq){
|
||||
uint16_t result = readSPI(Control__3_ADDR);
|
||||
Control__3 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.PWM_100_DUTY_SEL = freq;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__3_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_OCPMode DRV8316Driver::getOCPMode(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_OCPMode)data.OCP_MODE;
|
||||
|
||||
};
|
||||
void DRV8316Driver::setOCPMode(DRV8316_OCPMode ocpMode){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OCP_MODE = ocpMode;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_OCPLevel DRV8316Driver::getOCPLevel(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_OCPLevel)data.OCP_LVL;
|
||||
};
|
||||
void DRV8316Driver::setOCPLevel(DRV8316_OCPLevel amps){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OCP_LVL = amps;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_OCPRetry DRV8316Driver::getOCPRetryTime(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_OCPRetry)data.OCP_RETRY;
|
||||
};
|
||||
void DRV8316Driver::setOCPRetryTime(DRV8316_OCPRetry ms){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OCP_RETRY = ms;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_OCPDeglitch DRV8316Driver::getOCPDeglitchTime(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_OCPDeglitch)data.OCP_DEG;
|
||||
};
|
||||
void DRV8316Driver::setOCPDeglitchTime(DRV8316_OCPDeglitch ms){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OCP_DEG = ms;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isOCPClearInPWMCycleChange(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.OCP_CBC==OCP_CBC_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setOCPClearInPWMCycleChange(bool enable){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.OCP_CBC = enable?OCP_CBC_ENABLE:OCP_CBC_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isDriverOffEnabled(){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.DRV_OFF==DRV_OFF_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setDriverOffEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__4_ADDR);
|
||||
Control__4 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.DRV_OFF = enabled?DRV_OFF_ENABLE:DRV_OFF_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__4_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_CSAGain DRV8316Driver::getCurrentSenseGain(){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_CSAGain)data.CSA_GAIN;
|
||||
};
|
||||
void DRV8316Driver::setCurrentSenseGain(DRV8316_CSAGain gain){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.CSA_GAIN = gain;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__5_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isActiveSynchronousRectificationEnabled(){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.EN_ASR==EN_ASR_ENABLE;
|
||||
|
||||
};
|
||||
void DRV8316Driver::setActiveSynchronousRectificationEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.EN_ASR = enabled?EN_ASR_ENABLE:EN_ASR_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__5_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isActiveAsynchronousRectificationEnabled(){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.EN_AAR==EN_AAR_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setActiveAsynchronousRectificationEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.EN_AAR = enabled?EN_AAR_ENABLE:EN_AAR_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__5_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_Recirculation DRV8316Driver::getRecirculationMode(){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_Recirculation)data.ILIM_RECIR;
|
||||
};
|
||||
void DRV8316Driver::setRecirculationMode(DRV8316_Recirculation recirculationMode){
|
||||
uint16_t result = readSPI(Control__5_ADDR);
|
||||
Control__5 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.ILIM_RECIR = recirculationMode;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__5_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isBuckEnabled(){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.BUCK_DIS==BUCK_DIS_BUCK_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setBuckEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.BUCK_DIS = enabled?BUCK_DIS_BUCK_ENABLE:BUCK_DIS_BUCK_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__6_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_BuckVoltage DRV8316Driver::getBuckVoltage(){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_BuckVoltage)data.BUCK_SEL;
|
||||
};
|
||||
void DRV8316Driver::setBuckVoltage(DRV8316_BuckVoltage volts){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.BUCK_SEL = volts;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__6_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_BuckCurrentLimit DRV8316Driver::getBuckCurrentLimit(){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_BuckCurrentLimit)data.BUCK_CL;
|
||||
};
|
||||
void DRV8316Driver::setBuckCurrentLimit(DRV8316_BuckCurrentLimit mamps){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.BUCK_CL = mamps;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__6_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isBuckPowerSequencingEnabled(){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.BUCK_PS_DIS==BUCK_PS_DIS_ENABLE;
|
||||
|
||||
};
|
||||
void DRV8316Driver::setBuckPowerSequencingEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__6_ADDR);
|
||||
Control__6 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.BUCK_PS_DIS = enabled?BUCK_PS_DIS_ENABLE:BUCK_PS_DIS_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__6_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
DRV8316_DelayTarget DRV8316Driver::getDelayTarget(){
|
||||
uint16_t result = readSPI(Control__10_ADDR);
|
||||
Control__10 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return (DRV8316_DelayTarget)data.DLY_TARGET;
|
||||
};
|
||||
void DRV8316Driver::setDelayTarget(DRV8316_DelayTarget us){
|
||||
uint16_t result = readSPI(Control__10_ADDR);
|
||||
Control__10 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.DLY_TARGET = us;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__10_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool DRV8316Driver::isDelayCompensationEnabled(){
|
||||
uint16_t result = readSPI(Control__10_ADDR);
|
||||
Control__10 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
return data.DLYCMP_EN==DLYCMP_EN_ENABLE;
|
||||
};
|
||||
void DRV8316Driver::setDelayCompensationEnabled(bool enabled){
|
||||
uint16_t result = readSPI(Control__10_ADDR);
|
||||
Control__10 data;
|
||||
data.reg = (result & 0x00FF);
|
||||
data.DLYCMP_EN = enabled?DLYCMP_EN_ENABLE:DLYCMP_EN_DISABLE;
|
||||
delayMicroseconds(1); // delay at least 400ns between operations
|
||||
result = writeSPI(Control__10_ADDR, data.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
316
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/drv8316.h
Normal file
316
firmware/lib/Arduino-FOC-drivers/src/drivers/drv8316/drv8316.h
Normal file
@@ -0,0 +1,316 @@
|
||||
|
||||
|
||||
#ifndef SIMPLEFOC_DRV8316
|
||||
#define SIMPLEFOC_DRV8316
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <SPI.h>
|
||||
#include <drivers/BLDCDriver3PWM.h>
|
||||
#include <drivers/BLDCDriver6PWM.h>
|
||||
|
||||
#include "./drv8316_registers.h"
|
||||
|
||||
|
||||
enum DRV8316_PWMMode {
|
||||
PWM6_Mode = 0b00,
|
||||
PWM6_CurrentLimit_Mode = 0b01,
|
||||
PWM3_Mode = 0b10,
|
||||
PWM3_CurrentLimit_Mode = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_SDOMode {
|
||||
SDOMode_OpenDrain = 0b0,
|
||||
SDOMode_PushPull = 0b1
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_Slew {
|
||||
Slew_25Vus = 0b00,
|
||||
Slew_50Vus = 0b01,
|
||||
Slew_150Vus = 0b10,
|
||||
Slew_200Vus = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_OVP {
|
||||
OVP_SEL_32V = 0b0,
|
||||
OVP_SEL_20V = 0b1
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_PWM100DUTY {
|
||||
FREQ_20KHz = 0b0,
|
||||
FREQ_40KHz = 0b1
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_OCPMode {
|
||||
Latched_Fault = 0b00,
|
||||
AutoRetry_Fault = 0b01,
|
||||
ReportOnly = 0b10,
|
||||
NoAction = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_OCPLevel {
|
||||
Curr_16A = 0b0,
|
||||
Curr_24A = 0b1
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_OCPRetry {
|
||||
Retry5ms = 0b0,
|
||||
Retry500ms = 0b1
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_OCPDeglitch {
|
||||
Deglitch_0us2 = 0b00,
|
||||
Deglitch_0us6 = 0b01,
|
||||
Deglitch_1us1 = 0b10,
|
||||
Deglitch_1us6 = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_CSAGain {
|
||||
Gain_0V15 = 0b00,
|
||||
Gain_0V1875 = 0b01,
|
||||
Gain_0V25 = 0b10,
|
||||
Gain_0V375 = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_Recirculation {
|
||||
BrakeMode = 0b00, // FETs
|
||||
CoastMode = 0b01 // Diodes
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_BuckVoltage {
|
||||
VB_3V3 = 0b00,
|
||||
VB_5V = 0b01,
|
||||
VB_4V = 0b10,
|
||||
VB_5V7 = 0b11
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_BuckCurrentLimit {
|
||||
Limit_600mA = 0b00,
|
||||
Limit_150mA = 0b01
|
||||
};
|
||||
|
||||
|
||||
enum DRV8316_DelayTarget {
|
||||
Delay_0us = 0x0,
|
||||
Delay_0us4 = 0x1,
|
||||
Delay_0us6 = 0x2,
|
||||
Delay_0us8 = 0x3,
|
||||
Delay_1us = 0x4,
|
||||
Delay_1us2 = 0x5,
|
||||
Delay_1us4 = 0x6,
|
||||
Delay_1us6 = 0x7,
|
||||
Delay_1us8 = 0x8,
|
||||
Delay_2us = 0x9,
|
||||
Delay_2us2 = 0xA,
|
||||
Delay_2us4 = 0xB,
|
||||
Delay_2us6 = 0xC,
|
||||
Delay_2us8 = 0xD,
|
||||
Delay_3us = 0xE,
|
||||
Delay_3us2 = 0xF
|
||||
};
|
||||
|
||||
|
||||
|
||||
class DRV8316ICStatus {
|
||||
public:
|
||||
DRV8316ICStatus(IC_Status status) : status(status) {};
|
||||
~DRV8316ICStatus() {};
|
||||
|
||||
bool isFault() { return status.FAULT==0b1; };
|
||||
bool isOverTemperature() { return status.OT==0b1; };
|
||||
bool isOverCurrent() { return status.OCP==0b1; };
|
||||
bool isOverVoltage() { return status.OVP==0b1; };
|
||||
bool isSPIError() { return status.SPI_FLT==0b1; };
|
||||
bool isBuckError() { return status.BK_FLT==0b1; };
|
||||
bool isPowerOnReset() { return status.NPOR==0b1; };
|
||||
|
||||
IC_Status status;
|
||||
};
|
||||
|
||||
|
||||
class DRV8316Status1 {
|
||||
public:
|
||||
DRV8316Status1(Status__1 status1) : status1(status1) {};
|
||||
~DRV8316Status1() {};
|
||||
|
||||
|
||||
bool isOverCurrent_Ah() { return status1.OCP_HA==0b1; };
|
||||
bool isOverCurrent_Al() { return status1.OCP_LA==0b1; };
|
||||
bool isOverCurrent_Bh() { return status1.OCP_HB==0b1; };
|
||||
bool isOverCurrent_Bl() { return status1.OCP_LB==0b1; };
|
||||
bool isOverCurrent_Ch() { return status1.OCP_HC==0b1; };
|
||||
bool isOverCurrent_Cl() { return status1.OCP_LC==0b1; };
|
||||
bool isOverTemperatureShutdown() { return status1.OTS==0b1; };
|
||||
bool isOverTemperatureWarning() { return status1.OTW==0b1; };
|
||||
|
||||
Status__1 status1;
|
||||
};
|
||||
|
||||
|
||||
class DRV8316Status2 {
|
||||
public:
|
||||
DRV8316Status2(Status__2 status2) : status2(status2) {};
|
||||
~DRV8316Status2() {};
|
||||
|
||||
|
||||
bool isOneTimeProgrammingError() { return status2.OTP_ERR==0b1; };
|
||||
bool isBuckOverCurrent() { return status2.BUCK_OCP==0b1; };
|
||||
bool isBuckUnderVoltage() { return status2.BUCK_UV==0b1; };
|
||||
bool isChargePumpUnderVoltage() { return status2.VCP_UV==0b1; };
|
||||
bool isSPIParityError() { return status2.SPI_PARITY==0b1; };
|
||||
bool isSPIClockFramingError() { return status2.SPI_SCLK_FLT==0b1; };
|
||||
bool isSPIAddressError() { return status2.SPI_ADDR_FLT==0b1; };
|
||||
|
||||
Status__2 status2;
|
||||
};
|
||||
|
||||
|
||||
|
||||
class DRV8316Status : public DRV8316ICStatus, public DRV8316Status1, public DRV8316Status2 {
|
||||
public:
|
||||
DRV8316Status(IC_Status status, Status__1 status1, Status__2 status2) : DRV8316ICStatus(status), DRV8316Status1(status1), DRV8316Status2(status2) {};
|
||||
~DRV8316Status() {};
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
class DRV8316Driver {
|
||||
|
||||
public:
|
||||
DRV8316Driver(int cs, bool currentLimit = false, int nFault = NOT_SET) : currentLimit(currentLimit), cs(cs), nFault(nFault), spi(&SPI), settings(1000000, MSBFIRST, SPI_MODE1) {};
|
||||
virtual ~DRV8316Driver() {};
|
||||
|
||||
virtual void init(SPIClass* _spi = &SPI);
|
||||
|
||||
void clearFault(); // TODO check for fault condition methods
|
||||
|
||||
DRV8316Status getStatus();
|
||||
|
||||
bool isRegistersLocked();
|
||||
void setRegistersLocked(bool lock);
|
||||
|
||||
DRV8316_PWMMode getPWMMode();
|
||||
void setPWMMode(DRV8316_PWMMode pwmMode);
|
||||
|
||||
DRV8316_Slew getSlew();
|
||||
void setSlew(DRV8316_Slew slewRate);
|
||||
|
||||
DRV8316_SDOMode getSDOMode();
|
||||
void setSDOMode(DRV8316_SDOMode sdoMode);
|
||||
|
||||
bool isOvertemperatureReporting();
|
||||
void setOvertemperatureReporting(bool reportFault);
|
||||
|
||||
bool isSPIFaultReporting();
|
||||
void setSPIFaultReporting(bool reportFault);
|
||||
|
||||
bool isOvervoltageProtection();
|
||||
void setOvervoltageProtection(bool enabled);
|
||||
|
||||
DRV8316_OVP getOvervoltageLevel();
|
||||
void setOvervoltageLevel(DRV8316_OVP voltage);
|
||||
|
||||
DRV8316_PWM100DUTY getPWM100Frequency();
|
||||
void setPWM100Frequency(DRV8316_PWM100DUTY freq);
|
||||
|
||||
DRV8316_OCPMode getOCPMode();
|
||||
void setOCPMode(DRV8316_OCPMode ocpMode);
|
||||
|
||||
DRV8316_OCPLevel getOCPLevel();
|
||||
void setOCPLevel(DRV8316_OCPLevel amps);
|
||||
|
||||
DRV8316_OCPRetry getOCPRetryTime();
|
||||
void setOCPRetryTime(DRV8316_OCPRetry ms);
|
||||
|
||||
DRV8316_OCPDeglitch getOCPDeglitchTime();
|
||||
void setOCPDeglitchTime(DRV8316_OCPDeglitch ms);
|
||||
|
||||
bool isOCPClearInPWMCycleChange();
|
||||
void setOCPClearInPWMCycleChange(bool enable);
|
||||
|
||||
bool isDriverOffEnabled();
|
||||
void setDriverOffEnabled(bool enabled);
|
||||
|
||||
DRV8316_CSAGain getCurrentSenseGain();
|
||||
void setCurrentSenseGain(DRV8316_CSAGain gain);
|
||||
|
||||
bool isActiveSynchronousRectificationEnabled();
|
||||
void setActiveSynchronousRectificationEnabled(bool enabled);
|
||||
|
||||
bool isActiveAsynchronousRectificationEnabled();
|
||||
void setActiveAsynchronousRectificationEnabled(bool enabled);
|
||||
|
||||
DRV8316_Recirculation getRecirculationMode();
|
||||
void setRecirculationMode(DRV8316_Recirculation recirculationMode);
|
||||
|
||||
bool isBuckEnabled();
|
||||
void setBuckEnabled(bool enabled);
|
||||
|
||||
DRV8316_BuckVoltage getBuckVoltage();
|
||||
void setBuckVoltage(DRV8316_BuckVoltage volts);
|
||||
|
||||
DRV8316_BuckCurrentLimit getBuckCurrentLimit();
|
||||
void setBuckCurrentLimit(DRV8316_BuckCurrentLimit mamps);
|
||||
|
||||
bool isBuckPowerSequencingEnabled();
|
||||
void setBuckPowerSequencingEnabled(bool enabled);
|
||||
|
||||
DRV8316_DelayTarget getDelayTarget();
|
||||
void setDelayTarget(DRV8316_DelayTarget us);
|
||||
|
||||
bool isDelayCompensationEnabled();
|
||||
void setDelayCompensationEnabled(bool enabled);
|
||||
|
||||
private:
|
||||
uint16_t readSPI(uint8_t addr);
|
||||
uint16_t writeSPI(uint8_t addr, uint8_t data);
|
||||
bool getParity(uint16_t data);
|
||||
|
||||
bool currentLimit;
|
||||
int cs;
|
||||
int nFault;
|
||||
SPIClass* spi;
|
||||
SPISettings settings;
|
||||
};
|
||||
|
||||
|
||||
|
||||
class DRV8316Driver3PWM : public DRV8316Driver, public BLDCDriver3PWM {
|
||||
|
||||
public:
|
||||
DRV8316Driver3PWM(int phA,int phB,int phC, int cs, bool currentLimit = false, int en = NOT_SET, int nFault = NOT_SET) :
|
||||
DRV8316Driver(cs, currentLimit, nFault), BLDCDriver3PWM(phA, phB, phC, en) { enable_active_high=false; };
|
||||
virtual ~DRV8316Driver3PWM() {};
|
||||
|
||||
virtual void init(SPIClass* _spi = &SPI) override;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
class DRV8316Driver6PWM : public DRV8316Driver, public BLDCDriver6PWM {
|
||||
|
||||
public:
|
||||
DRV8316Driver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int cs, bool currentLimit = false, int en = NOT_SET, int nFault = NOT_SET) :
|
||||
DRV8316Driver(cs, currentLimit, nFault), BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, en) { enable_active_high=false; };
|
||||
virtual ~DRV8316Driver6PWM() {};
|
||||
|
||||
virtual void init(SPIClass* _spi = &SPI) override;
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,184 @@
|
||||
|
||||
|
||||
#ifndef SIMPLEFOC_DRV8316_REGISTERS
|
||||
#define SIMPLEFOC_DRV8316_REGISTERS
|
||||
|
||||
|
||||
#define IC_Status_ADDR 0x0
|
||||
#define Status__1_ADDR 0x1
|
||||
#define Status__2_ADDR 0x2
|
||||
#define Control__1_ADDR 0x3
|
||||
#define Control__2_ADDR 0x4
|
||||
#define Control__3_ADDR 0x5
|
||||
#define Control__4_ADDR 0x6
|
||||
#define Control__5_ADDR 0x7
|
||||
#define Control__6_ADDR 0x8
|
||||
#define Control__10_ADDR 0xC
|
||||
|
||||
#define REG_LOCK_LOCK 0b110
|
||||
#define REG_LOCK_UNLOCK 0b011
|
||||
#define CLR_FAULT_CLR 0b1
|
||||
#define OTW_REP_ENABLE 0b1
|
||||
#define OTW_REP_DISABLE 0b0
|
||||
#define SPI_FLT_REP_ENABLE 0b0
|
||||
#define SPI_FLT_REP_DISABLE 0b1
|
||||
#define OVP_EN_ENABLE 0b1
|
||||
#define OVP_EN_DISABLE 0b0
|
||||
#define OCP_CBC_ENABLE 0b1
|
||||
#define OCP_CBC_DISABLE 0b0
|
||||
#define DRV_OFF_ENABLE 0b1
|
||||
#define DRV_OFF_DISABLE 0b0
|
||||
#define EN_ASR_ENABLE 0b1
|
||||
#define EN_ASR_DISABLE 0b0
|
||||
#define EN_AAR_ENABLE 0b1
|
||||
#define EN_AAR_DISABLE 0b0
|
||||
#define BUCK_DIS_BUCK_DISABLE 0b1
|
||||
#define BUCK_DIS_BUCK_ENABLE 0b0
|
||||
#define BUCK_PS_DIS_DISABLE 0b1
|
||||
#define BUCK_PS_DIS_ENABLE 0b0
|
||||
#define DLYCMP_EN_ENABLE 0b1
|
||||
#define DLYCMP_EN_DISABLE 0b0
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t REG_LOCK:3;
|
||||
uint8_t :5;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__1;
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t CLR_FLT:1;
|
||||
uint8_t PWM_MODE:2;
|
||||
uint8_t SLEW:2;
|
||||
uint8_t SDO_MODE:1;
|
||||
uint8_t :2;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__2;
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t OTW_REP:1;
|
||||
uint8_t SPI_FLT_REP:1;
|
||||
uint8_t OVP_EN:1;
|
||||
uint8_t OVP_SEL:1;
|
||||
uint8_t PWM_100_DUTY_SEL:1;
|
||||
uint8_t :3;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__3;
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t OCP_MODE:2;
|
||||
uint8_t OCP_LVL:1;
|
||||
uint8_t OCP_RETRY:1;
|
||||
uint8_t OCP_DEG:2;
|
||||
uint8_t OCP_CBC:1;
|
||||
uint8_t DRV_OFF:1;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__4;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t CSA_GAIN:2;
|
||||
uint8_t EN_ASR:1;
|
||||
uint8_t EN_AAR:1;
|
||||
uint8_t :2;
|
||||
uint8_t ILIM_RECIR:1;
|
||||
uint8_t :1;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__5;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t BUCK_DIS:1;
|
||||
uint8_t BUCK_SEL:2;
|
||||
uint8_t BUCK_CL:1;
|
||||
uint8_t BUCK_PS_DIS:1;
|
||||
uint8_t :2;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__6;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t DLY_TARGET:4;
|
||||
uint8_t DLYCMP_EN:1;
|
||||
uint8_t :3;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Control__10;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t FAULT:1;
|
||||
uint8_t OT:1;
|
||||
uint8_t OVP:1;
|
||||
uint8_t NPOR:1;
|
||||
uint8_t OCP:1;
|
||||
uint8_t SPI_FLT:1;
|
||||
uint8_t BK_FLT:1;
|
||||
uint8_t :1;
|
||||
};
|
||||
uint8_t reg;
|
||||
} IC_Status;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t OCP_LA:1;
|
||||
uint8_t OCP_HA:1;
|
||||
uint8_t OCP_LB:1;
|
||||
uint8_t OCP_HB:1;
|
||||
uint8_t OCP_LC:1;
|
||||
uint8_t OCP_HC:1;
|
||||
uint8_t OTS:1;
|
||||
uint8_t OTW:1;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Status__1;
|
||||
|
||||
|
||||
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint8_t SPI_ADDR_FLT:1;
|
||||
uint8_t SPI_SCLK_FLT:1;
|
||||
uint8_t SPI_PARITY:1;
|
||||
uint8_t VCP_UV:1;
|
||||
uint8_t BUCK_UV:1;
|
||||
uint8_t BUCK_OCP:1;
|
||||
uint8_t OTP_ERR:1;
|
||||
uint8_t :1;
|
||||
};
|
||||
uint8_t reg;
|
||||
} Status__2;
|
||||
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,42 @@
|
||||
|
||||
# SimpleFOC STSPIN32G4 Driver
|
||||
|
||||
This driver initializes the PWM stage of the STSPIN32G4, and provides access to its configuration via I2C.
|
||||
|
||||
:warning: in development!
|
||||
|
||||
## Setup
|
||||
|
||||
Since there are currently no standard boards for Arduino based on the STSPIN32G4 you will need a custom board definition, associated linker script and project setup to compile for your board. These topics are out of scope for this driver, but you can find a working example for the [FunQi STSPIN32G4 board](TODO link) [here](TODO link);
|
||||
|
||||
Once you can compile for your board, and flash it with a "blinky" test sketch, then you're ready to try SimpleFOC and more complex code.
|
||||
|
||||
## Usage
|
||||
|
||||
Basic usage, as you can see it is very simple. Since the pins are all pre-defined due to internal connections, setup
|
||||
is easier than with the standard drivers. Here is an example for open loop mode:
|
||||
|
||||
```c++
|
||||
#include <Arduino.h>
|
||||
#include "SimpleFOC.h"
|
||||
#include "SimpleFOCDrivers.h"
|
||||
#include "drivers/stspin32g4/STSPIN32G4.h"
|
||||
|
||||
|
||||
STSPIN32G4 driver = STSPIN32G4();
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
|
||||
void setup() {
|
||||
driver.voltage_power_supply = 12.0f;
|
||||
driver.init();
|
||||
motor.voltage_limit = driver.voltage_limit / 2.0f;
|
||||
motor.controller = MotionControlType::velocity_openloop;
|
||||
motor.linkDriver(&driver);
|
||||
motor.init();
|
||||
}
|
||||
|
||||
void loop(){
|
||||
motor.move(5.0f); // 5 rad/s open loop
|
||||
delayMicroseconds(100); // STM32G4 is very fast, add a delay in open loop if we do nothing else
|
||||
}
|
||||
```
|
||||
@@ -0,0 +1,182 @@
|
||||
|
||||
#include "./STSPIN32G4.h"
|
||||
|
||||
#ifdef ARDUINO_GENERIC_G431VBTX
|
||||
|
||||
|
||||
STSPIN32G4::STSPIN32G4() : BLDCDriver6PWM(STSPIN32G4_PIN_INUH, STSPIN32G4_PIN_INUL, STSPIN32G4_PIN_INVH,
|
||||
STSPIN32G4_PIN_INVL, STSPIN32G4_PIN_INWH, STSPIN32G4_PIN_INWL),
|
||||
_wire(STSPIN32G4_PIN_SDA, STSPIN32G4_PIN_SCL) {
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4::~STSPIN32G4(){
|
||||
_wire.end();
|
||||
};
|
||||
|
||||
|
||||
|
||||
int STSPIN32G4::init(){
|
||||
// init pins
|
||||
pinMode(STSPIN32G4_PIN_WAKE, OUTPUT);
|
||||
digitalWrite(STSPIN32G4_PIN_WAKE, LOW);
|
||||
pinMode(STSPIN32G4_PIN_READY, INPUT_PULLUP);
|
||||
pinMode(STSPIN32G4_PIN_FAULT, INPUT_PULLUP);
|
||||
|
||||
int result = this->BLDCDriver6PWM::init();
|
||||
if(result == 0) return result;
|
||||
setPwm(0,0,0); // set the phases to off
|
||||
|
||||
// init I2C
|
||||
_wire.begin();
|
||||
|
||||
delayMicroseconds(50); // give driver a moment to wake up
|
||||
clearFaults(); // clear the faults
|
||||
|
||||
// TODO init fault monitor
|
||||
|
||||
return isReady() ? 1 : 0;
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::wake() {
|
||||
digitalWrite(STSPIN32G4_PIN_WAKE, HIGH);
|
||||
delayMicroseconds(50); // 50ms high pulse to wake up
|
||||
digitalWrite(STSPIN32G4_PIN_WAKE, LOW);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::sleep() {
|
||||
digitalWrite(STSPIN32G4_PIN_WAKE, LOW);
|
||||
writeRegister(STSPIN32G4_REG_STBY, 0x01);
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool STSPIN32G4::isReady(){
|
||||
return digitalRead(STSPIN32G4_PIN_READY)==HIGH;
|
||||
};
|
||||
|
||||
|
||||
|
||||
bool STSPIN32G4::isFault(){
|
||||
return digitalRead(STSPIN32G4_PIN_FAULT)==LOW;
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4Status STSPIN32G4::status(){
|
||||
STSPIN32G4Status result;
|
||||
result.reg = readRegister(STSPIN32G4_REG_STATUS);
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::lock(){
|
||||
writeRegister(STSPIN32G4_REG_LOCK, 0x00);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::unlock(){
|
||||
writeRegister(STSPIN32G4_REG_LOCK, 0xF0);
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4NFault STSPIN32G4::getNFaultRegister(){
|
||||
STSPIN32G4NFault result;
|
||||
result.reg = readRegister(STSPIN32G4_REG_NFAULT);
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4Ready STSPIN32G4::getReadyRegister(){
|
||||
STSPIN32G4Ready result;
|
||||
result.reg = readRegister(STSPIN32G4_REG_READY);
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4Logic STSPIN32G4::getLogicRegister(){
|
||||
STSPIN32G4Logic result;
|
||||
result.reg = readRegister(STSPIN32G4_REG_LOGIC);
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
STSPIN32G4PowMng STSPIN32G4::getPowMngRegister(){
|
||||
STSPIN32G4PowMng result;
|
||||
result.reg = readRegister(STSPIN32G4_REG_POWMNG);
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::setNFaultRegister(STSPIN32G4NFault value){
|
||||
writeRegister(STSPIN32G4_REG_NFAULT, value.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::setReadyRegister(STSPIN32G4Ready value){
|
||||
writeRegister(STSPIN32G4_REG_READY, value.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::setLogicRegister(STSPIN32G4Logic value){
|
||||
writeRegister(STSPIN32G4_REG_LOGIC, value.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::setPowMngRegister(STSPIN32G4PowMng value){
|
||||
writeRegister(STSPIN32G4_REG_POWMNG, value.reg);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::resetRegisters(){
|
||||
// write 0xFF to reset register
|
||||
writeRegister(STSPIN32G4_REG_RESET, 0xFF);
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::clearFaults(){
|
||||
// write 0xFF to clear faults
|
||||
writeRegister(STSPIN32G4_REG_CLEAR, 0xFF);
|
||||
};
|
||||
|
||||
|
||||
|
||||
uint8_t STSPIN32G4::readRegister(uint8_t reg){
|
||||
uint8_t result = 0;
|
||||
_wire.beginTransmission(STSPIN32G4_I2C_ADDR);
|
||||
_wire.write(reg);
|
||||
_wire.endTransmission(false);
|
||||
_wire.requestFrom(STSPIN32G4_I2C_ADDR, 1);
|
||||
result = _wire.read();
|
||||
return result;
|
||||
};
|
||||
|
||||
|
||||
|
||||
void STSPIN32G4::writeRegister(uint8_t reg, uint8_t val){
|
||||
_wire.beginTransmission(STSPIN32G4_I2C_ADDR);
|
||||
_wire.write(reg);
|
||||
_wire.write(val);
|
||||
_wire.endTransmission();
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,148 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Arduino.h"
|
||||
|
||||
#ifdef ARDUINO_GENERIC_G431VBTX
|
||||
|
||||
#include "Wire.h"
|
||||
#include "drivers/BLDCDriver6PWM.h"
|
||||
|
||||
|
||||
#define STSPIN32G4_PIN_INUL PE8
|
||||
#define STSPIN32G4_PIN_INUH PE9
|
||||
#define STSPIN32G4_PIN_INVL PE10
|
||||
#define STSPIN32G4_PIN_INVH PE11
|
||||
#define STSPIN32G4_PIN_INWL PE12
|
||||
#define STSPIN32G4_PIN_INWH PE13
|
||||
|
||||
#define STSPIN32G4_PIN_WAKE PE7
|
||||
#define STSPIN32G4_PIN_READY PE14
|
||||
#define STSPIN32G4_PIN_FAULT PE15
|
||||
|
||||
#define STSPIN32G4_PIN_SDA PC9
|
||||
#define STSPIN32G4_PIN_SCL PC8
|
||||
|
||||
#define STSPIN32G4_I2C_ADDR 0b1000111
|
||||
|
||||
#define STSPIN32G4_REG_POWMNG 0x01
|
||||
#define STSPIN32G4_REG_LOGIC 0x02
|
||||
#define STSPIN32G4_REG_READY 0x07
|
||||
#define STSPIN32G4_REG_NFAULT 0x08
|
||||
#define STSPIN32G4_REG_CLEAR 0x09
|
||||
#define STSPIN32G4_REG_STBY 0x0A
|
||||
#define STSPIN32G4_REG_LOCK 0x0B
|
||||
#define STSPIN32G4_REG_RESET 0x0C
|
||||
#define STSPIN32G4_REG_STATUS 0x80
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
union STSPIN32G4Status {
|
||||
struct {
|
||||
uint8_t vcc_uvlo:1;
|
||||
uint8_t thsd:1;
|
||||
uint8_t vds_p:1;
|
||||
uint8_t reset:1;
|
||||
uint8_t unused:3;
|
||||
uint8_t lock:1;
|
||||
};
|
||||
uint8_t reg;
|
||||
};
|
||||
|
||||
|
||||
|
||||
union STSPIN32G4NFault {
|
||||
struct {
|
||||
uint8_t vcc_uvlo_flt:1;
|
||||
uint8_t thsd_flt:1;
|
||||
uint8_t vds_p_flt:1;
|
||||
uint8_t unused:5;
|
||||
};
|
||||
uint8_t reg;
|
||||
};
|
||||
|
||||
|
||||
union STSPIN32G4Ready {
|
||||
struct {
|
||||
uint8_t vcc_uvlo_rdy:1;
|
||||
uint8_t thsd_rdy:1;
|
||||
uint8_t unused:1;
|
||||
uint8_t stby_rdy:1;
|
||||
uint8_t unused2:4;
|
||||
};
|
||||
uint8_t reg;
|
||||
};
|
||||
|
||||
|
||||
|
||||
union STSPIN32G4Logic {
|
||||
struct {
|
||||
uint8_t ilock:1;
|
||||
uint8_t dtmin:1;
|
||||
uint8_t vds_p_deg:2;
|
||||
uint8_t unused:4;
|
||||
};
|
||||
uint8_t reg;
|
||||
};
|
||||
|
||||
|
||||
|
||||
union STSPIN32G4PowMng {
|
||||
struct {
|
||||
uint8_t vcc_val:2;
|
||||
uint8_t unused:2;
|
||||
uint8_t stby_reg_en:1;
|
||||
uint8_t vcc_dis:1;
|
||||
uint8_t reg3v3_dis:1;
|
||||
uint8_t unused2:1;
|
||||
};
|
||||
uint8_t reg;
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
class STSPIN32G4 : public BLDCDriver6PWM {
|
||||
public:
|
||||
STSPIN32G4();
|
||||
~STSPIN32G4();
|
||||
|
||||
int init() override;
|
||||
|
||||
void wake();
|
||||
void sleep();
|
||||
bool isReady();
|
||||
bool isFault();
|
||||
|
||||
STSPIN32G4Status status();
|
||||
void lock();
|
||||
void unlock();
|
||||
STSPIN32G4NFault getNFaultRegister();
|
||||
STSPIN32G4Ready getReadyRegister();
|
||||
STSPIN32G4Logic getLogicRegister();
|
||||
STSPIN32G4PowMng getPowMngRegister();
|
||||
void setNFaultRegister(STSPIN32G4NFault value);
|
||||
void setReadyRegister(STSPIN32G4Ready value);
|
||||
void setLogicRegister(STSPIN32G4Logic value);
|
||||
void setPowMngRegister(STSPIN32G4PowMng value);
|
||||
void resetRegisters();
|
||||
void clearFaults();
|
||||
|
||||
protected:
|
||||
uint8_t readRegister(uint8_t reg);
|
||||
void writeRegister(uint8_t reg, uint8_t val);
|
||||
|
||||
TwoWire _wire;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
147
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/README.md
Normal file
147
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/README.md
Normal file
@@ -0,0 +1,147 @@
|
||||
|
||||
# TMC6200 SimpleFOC Driver
|
||||
|
||||
by [@YaseenTwati](https://github.com/YaseenTwati)
|
||||
|
||||
The TMC6200 is a Universal high voltage BLDC/PMSM/Servo MOSFET 3-halfbridge gate-driver with in line motor current
|
||||
sensing. External MOSFETs for up to 100A motor current.
|
||||
|
||||
See https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC6200_datasheet_Rev1.05.pdf for more information.
|
||||
|
||||
## Hardware setup
|
||||
|
||||
To use the TMC6200 you will have to connect the following:
|
||||
|
||||
- GND
|
||||
- VCC_IO - 3.3V or 5V
|
||||
- SPE - pull up to VCC to enable SPI mode
|
||||
- SPI MOSI ( SDI )
|
||||
- SPI MISO ( SDO )
|
||||
- SPI CLK
|
||||
- SPI nCS
|
||||
- DRV_EN - connect to digital out (or pull up to VCC)
|
||||
- UH - connect to motor PWM pin
|
||||
- VH - connect to motor PWM pin
|
||||
- WH - connect to motor PWM pin
|
||||
- UL - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
- VL - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
- WL - connect to motor PWM pin for 6-PWM, or to digital out (or pull up to VCC) for 3-PWM operation
|
||||
|
||||
Optionally, but useful:
|
||||
|
||||
- FAULT - digital in, active high
|
||||
|
||||
For current sensing:
|
||||
|
||||
- CURU - connect to analog in
|
||||
- CURV - connect to analog in
|
||||
- CURW - connect to analog in
|
||||
|
||||
## Usage
|
||||
|
||||
Usage is quite easy, especially if you already know SimpleFOC. See also the [examples](https://github.com/simplefoc/Arduino-FOC-drivers/examples/drivers/drv8316/)
|
||||
|
||||
```c++
|
||||
#include "Arduino.h"
|
||||
#include <SimpleFOC.h>
|
||||
#include "SimpleFOCDrivers.h"
|
||||
#include "drivers/tmc6200/TMC6200.hpp"
|
||||
|
||||
BLDCMotor motor = BLDCMotor(15);
|
||||
TMC6200Driver6PWM driver = DRV8316Driver6PWM(UH, UL, VH, VL, WH, WL, nCS, DRV_EN);
|
||||
|
||||
//... normal simpleFOC init code...
|
||||
```
|
||||
|
||||
Or, for 3-PWM:
|
||||
|
||||
```c++
|
||||
#include "Arduino.h"
|
||||
#include <SimpleFOC.h>
|
||||
#include "SimpleFOCDrivers.h"
|
||||
#include "drivers/tmc6200/TMC6200.hpp"
|
||||
|
||||
BLDCMotor motor = BLDCMotor(15);
|
||||
TMC6200Driver3PWM driver = TMC6200Driver3PWM(UH, MOTOR_VH, MOTOR_WH, nCS, DRV_EN);
|
||||
|
||||
void setup() {
|
||||
|
||||
pinMode(UL, OUTPUT);
|
||||
pinMode(VL, OUTPUT);
|
||||
pinMode(WL, OUTPUT);
|
||||
|
||||
digitalWrite(WL, HIGH);
|
||||
digitalWrite(UL, HIGH);
|
||||
digitalWrite(VL, HIGH);
|
||||
|
||||
//... normal simpleFOC init code...
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
### Validating the SPI Connection
|
||||
You can validate the SPI connection by checking the value of VERSION field in IOIN register. The value should be 0x10.
|
||||
|
||||
```c++
|
||||
if(driver.getInputs().VERSION != TMC6200_VERSION){
|
||||
// something is wrong with the spi connection
|
||||
}
|
||||
```
|
||||
|
||||
### Current Sensing
|
||||
The gain of the internal current amplifiers can be set to 5, 10 or 20 through `setCurrentSenseGain()`
|
||||
|
||||
```c++
|
||||
driver.setCurrentSenseGain(TMC6200_AmplificationGain::_5);
|
||||
//driver.setCurrentSenseGain(TMC6200_AmplificationGain::_10);
|
||||
//driver.setCurrentSenseGain(TMC6200_AmplificationGain::_20);
|
||||
```
|
||||
The sense amplifiers can also be turned off ( they are on by default ), through `setCurrentSenseAmplifierState()`
|
||||
|
||||
```c++
|
||||
driver.setCurrentSenseAmplifierState(false);
|
||||
```
|
||||
### Driver Strength
|
||||
The strength of the mosfet drivers can be controlled through `setDriverStrength()`
|
||||
|
||||
```c++
|
||||
driver.setDriverStrength(TMC6200_DRVStrength::Weak);
|
||||
//driver.setDriverStrength(TMC6200_DRVStrength::WeakTC); // (medium above OTPW level)
|
||||
//driver.setDriverStrength(TMC6200_DRVStrength::Medium);
|
||||
//driver.setDriverStrength(TMC6200_DRVStrength::Strong);
|
||||
```
|
||||
|
||||
### Handling Faults
|
||||
The fault line will go high if a fault occurs such as a short, an interrupt can be used to handle it.
|
||||
Note that some faults will disable the driver and will require the DRV_EN to be cycled to clear the fault.
|
||||
|
||||
```c++
|
||||
// somewhere in setup
|
||||
attachInterrupt(digitalPinToInterrupt(FAULT), handleFault, RISING);
|
||||
```
|
||||
|
||||
```c++
|
||||
void handleFault()
|
||||
{
|
||||
// you can read the status register to see what happened
|
||||
TMC6200GStatus status = driver.getStatus();
|
||||
Serial.print("hasUShorted: "); Serial.println(status.hasUShorted());
|
||||
Serial.print("hasVShorted: "); Serial.println(status.hasVShorted());
|
||||
Serial.print("hasWShorted: "); Serial.println(status.hasWShorted());
|
||||
Serial.print("isUShortedToGround: "); Serial.println(status.isUShortedToGround());
|
||||
Serial.print("isUShortedToSupply: "); Serial.println(status.isUShortedToSupply());
|
||||
Serial.print("isVShortedToGround: "); Serial.println(status.isVShortedToGround());
|
||||
Serial.print("isVShortedToSupply: "); Serial.println(status.isVShortedToSupply());
|
||||
Serial.print("isWShortedToGround: "); Serial.println(status.isWShortedToGround());
|
||||
Serial.print("isWShortedToSupply: "); Serial.println(status.isWShortedToSupply());
|
||||
Serial.print("isOverTemperaturePreWarning: "); Serial.println(status.isOverTemperaturePreWarning());
|
||||
Serial.print("isChargePumpUnderVoltage: "); Serial.println(status.isChargePumpUnderVoltage());
|
||||
|
||||
// the driver must be cycled to clear the fault
|
||||
digitalWrite(DRV_EN, LOW);
|
||||
delayMicrosockets(someSmallDelay);
|
||||
digitalWrite(DRV_EN, HIGH);
|
||||
}
|
||||
```
|
||||
|
||||
The driver provides other features such as controlling the tolerences of short detection and the BBM cycle time and so on, setting the options can be conveniently done via the provided setter methods. All documented registers and options are available via the driver, and the option values can be accessed via enums.
|
||||
221
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/TMC6200.cpp
Normal file
221
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/TMC6200.cpp
Normal file
@@ -0,0 +1,221 @@
|
||||
#include "TMC6200.hpp"
|
||||
|
||||
void TMC6200Driver::init(SPIClass *_spi) {
|
||||
spi = _spi;
|
||||
settings = SPISettings(500000, MSBFIRST, SPI_MODE3);
|
||||
|
||||
pinMode(csPin, OUTPUT);
|
||||
digitalWrite(csPin, HIGH);
|
||||
}
|
||||
|
||||
// TMC6200_GCONF ------
|
||||
|
||||
void TMC6200Driver::setDriverState(bool state) {
|
||||
TMC6200_GCONF gConf;
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
|
||||
gConf.DISABLE = state ? 0 : 1;
|
||||
writeRegister(TMC6200_GCONF_REG, gConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setPWMMode(TMC6200_PWMMode pwmMode) {
|
||||
TMC6200_GCONF gConf;
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
|
||||
gConf.SINGLE_LINE = pwmMode;
|
||||
writeRegister(TMC6200_GCONF_REG, gConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setFaultDirect(TMC6200_FaultDirect faultDirect) {
|
||||
TMC6200_GCONF gConf;
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
|
||||
gConf.FAULT_DIRECT = faultDirect;
|
||||
writeRegister(TMC6200_GCONF_REG, gConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setCurrentSenseAmplifierState(bool state) {
|
||||
TMC6200_GCONF gConf;
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
|
||||
gConf.AMPLIFIER_OFF = state ? 0 : 1;
|
||||
writeRegister(TMC6200_GCONF_REG, gConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setCurrentSenseGain(TMC6200_AmplificationGain amplificationGain) {
|
||||
TMC6200_GCONF gConf;
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
|
||||
gConf.AMPLIFICATION = amplificationGain;
|
||||
writeRegister(TMC6200_GCONF_REG, gConf.reg);
|
||||
|
||||
gConf.reg = readRegister(TMC6200_GCONF_REG);
|
||||
}
|
||||
|
||||
// TMC6200_DRV_CONF ------
|
||||
|
||||
void TMC6200Driver::setOverTemperatureThreshold(TMC6200_OTSelect otLevel) {
|
||||
TMC6200_DRV_CONF drvConf;
|
||||
drvConf.reg = readRegister(TMC6200_DRV_CONF_REG);
|
||||
|
||||
drvConf.OT_SELECT = otLevel;
|
||||
writeRegister(TMC6200_DRV_CONF_REG, drvConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setDriverStrength(TMC6200_DRVStrength strength) {
|
||||
TMC6200_DRV_CONF drvConf;
|
||||
drvConf.reg = readRegister(TMC6200_DRV_CONF_REG);
|
||||
|
||||
drvConf.DRV_STRENGTH = strength;
|
||||
writeRegister(TMC6200_DRV_CONF_REG, drvConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setBBMCycles(uint8_t clockCycles) {
|
||||
TMC6200_DRV_CONF drvConf;
|
||||
drvConf.reg = readRegister(TMC6200_DRV_CONF_REG);
|
||||
|
||||
drvConf.BBMCLKS = clockCycles;
|
||||
writeRegister(TMC6200_DRV_CONF_REG, drvConf.reg);
|
||||
}
|
||||
|
||||
// TMC6200_SHORT_CONF ------
|
||||
|
||||
void TMC6200Driver::setShortDelay(TMC6200_ShortDelay shortDelay) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.SHORT_DELAY = shortDelay;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::shortFilter(TMC6200_ShortFilter shortFilter) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.SHORT_FILTER = shortFilter;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setShortToSupplySensitivityLevel(uint8_t level) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.S2VS_LEVEL = level;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setShortToGroundSensitivityLevel(uint8_t level) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.S2G_LEVEL = level;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setShortRetries(uint8_t retries) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.RETRY = retries;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setParallelProtect(TMC6200_ParallelProtect parallelProtect) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.PROTECT_PARALLEL = parallelProtect;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setShortToGroundDetectionState(bool state) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.DISABLE_S2G = state ? 0 : 1;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
void TMC6200Driver::setShortToSupplyDetectionState(bool state) {
|
||||
TMC6200_SHORT_CONF shortConf;
|
||||
shortConf.reg = readRegister(TMC6200_SHORT_CONF_REG);
|
||||
|
||||
shortConf.DISABLE_S2VS = state ? 0 : 1;
|
||||
writeRegister(TMC6200_SHORT_CONF_REG, shortConf.reg);
|
||||
}
|
||||
|
||||
// TMC6200_IOIN ------
|
||||
|
||||
TMC6200_IOIN TMC6200Driver::getInputs() {
|
||||
TMC6200_IOIN ioin;
|
||||
ioin.reg = readRegister(TMC6200_IOIN_REG);
|
||||
|
||||
return ioin;
|
||||
}
|
||||
|
||||
// TMC6200_GSTAT ------
|
||||
|
||||
TMC6200GStatus TMC6200Driver::getStatus() {
|
||||
TMC6200_GSTAT gstat;
|
||||
gstat.reg = readRegister(TMC6200_GSTAT_REG);
|
||||
|
||||
return {gstat};
|
||||
}
|
||||
|
||||
void TMC6200Driver::setStatus(TMC6200_GSTAT status) {
|
||||
writeRegister(TMC6200_GSTAT_REG, status.reg);
|
||||
}
|
||||
|
||||
uint32_t TMC6200Driver::readRegister(uint8_t addr) {
|
||||
digitalWrite(csPin, LOW);
|
||||
spi->beginTransaction(settings);
|
||||
|
||||
// Address
|
||||
spi->transfer(TMC_ADDRESS(addr));
|
||||
|
||||
// 32bit Data
|
||||
uint32_t value = 0;
|
||||
value |= (spi->transfer(0x00) << 24);
|
||||
value |= (spi->transfer(0x00) << 16);
|
||||
value |= (spi->transfer(0x00) << 8);
|
||||
value |= (spi->transfer(0x00) << 0);
|
||||
|
||||
spi->end();
|
||||
digitalWrite(csPin, HIGH);
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
void TMC6200Driver::writeRegister(uint8_t addr, uint32_t data) {
|
||||
digitalWrite(csPin, LOW);
|
||||
spi->beginTransaction(settings);
|
||||
|
||||
// Address
|
||||
spi->transfer(addr | TMC_WRITE_BIT);
|
||||
|
||||
// 32bit Data
|
||||
spi->transfer(0xFF & (data >> 24));
|
||||
spi->transfer(0xFF & (data >> 16));
|
||||
spi->transfer(0xFF & (data >> 8));
|
||||
spi->transfer(0xFF & (data >> 0));
|
||||
|
||||
spi->end();
|
||||
digitalWrite(csPin, HIGH);
|
||||
}
|
||||
|
||||
// --------------------
|
||||
|
||||
void TMC6200Driver3PWM::init(SPIClass *_spi) {
|
||||
TMC6200Driver::init(_spi);
|
||||
delayMicroseconds(1);
|
||||
TMC6200Driver::setPWMMode(TMC6200_PWMMode::SingleLine);
|
||||
BLDCDriver3PWM::init();
|
||||
};
|
||||
|
||||
|
||||
void TMC6200Driver6PWM::init(SPIClass *_spi) {
|
||||
TMC6200Driver::init(_spi);
|
||||
delayMicroseconds(1);
|
||||
TMC6200Driver::setPWMMode(TMC6200_PWMMode::Individual);
|
||||
BLDCDriver6PWM::init();
|
||||
};
|
||||
171
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/TMC6200.hpp
Normal file
171
firmware/lib/Arduino-FOC-drivers/src/drivers/tmc6200/TMC6200.hpp
Normal file
@@ -0,0 +1,171 @@
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
#include <drivers/BLDCDriver3PWM.h>
|
||||
#include <drivers/BLDCDriver6PWM.h>
|
||||
#include "TMC6200_Registers.hpp"
|
||||
|
||||
#define TMC6200_VERSION 0x10
|
||||
|
||||
enum TMC6200_PWMMode {
|
||||
Individual = 0, // 6PWM
|
||||
SingleLine = 1, // 3PWM
|
||||
};
|
||||
|
||||
enum TMC6200_AmplificationGain {
|
||||
_5 = 0,
|
||||
_10 = 1,
|
||||
_Also_10 = 2, // maybe just remove this
|
||||
_20 = 3,
|
||||
};
|
||||
|
||||
enum TMC6200_ShortDelay {
|
||||
_750nS = 0,
|
||||
_1500nS = 1,
|
||||
};
|
||||
|
||||
enum TMC6200_ShortFilter {
|
||||
_100nS = 0,
|
||||
_1uS = 1,
|
||||
_2uS = 2,
|
||||
_3uS = 3,
|
||||
};
|
||||
|
||||
enum TMC6200_ParallelProtect {
|
||||
Detected = 0,
|
||||
All = 1,
|
||||
};
|
||||
|
||||
enum TMC6200_FaultDirect {
|
||||
AtLeastOneBridgeDown = 0,
|
||||
EachProtectiveAction = 1,
|
||||
};
|
||||
|
||||
enum TMC6200_OTSelect {
|
||||
_150 = 0b00,
|
||||
_143 = 0b01,
|
||||
_136 = 0b10,
|
||||
_120 = 0b11,
|
||||
};
|
||||
|
||||
enum TMC6200_DRVStrength {
|
||||
Weak = 0b00,
|
||||
WeakTC = 0b01, // (medium above OTPW level)
|
||||
Medium = 0b10,
|
||||
Strong = 0b11,
|
||||
};
|
||||
|
||||
class TMC6200GStatus {
|
||||
public:
|
||||
TMC6200GStatus(TMC6200_GSTAT status) : status(status) {};
|
||||
|
||||
bool isReset() const { return status.RESET == 0b1; };
|
||||
|
||||
bool isOverTemperaturePreWarning() const { return status.DRV_OTPW == 0b1; };
|
||||
|
||||
bool isOverTemperature() const { return status.DRV_OT == 0b1; };
|
||||
|
||||
bool isChargePumpUnderVoltage() const { return status.UV_CP == 0b1; };
|
||||
|
||||
bool hasUShorted() const { return status.SHORT_DET_U == 0b1; };
|
||||
|
||||
bool hasVShorted() const { return status.SHORT_DET_V == 0b1; };
|
||||
|
||||
bool hasWShorted() const { return status.SHORT_DET_W == 0b1; };
|
||||
|
||||
bool isUShortedToGround() const { return status.S2GU == 0b1; };
|
||||
|
||||
bool isUShortedToSupply() const { return status.S2VSU == 0b1; };
|
||||
|
||||
bool isVShortedToGround() const { return status.S2GV == 0b1; };
|
||||
|
||||
bool isVShortedToSupply() const { return status.S2VSV == 0b1; };
|
||||
|
||||
bool isWShortedToGround() const { return status.S2GW == 0b1; };
|
||||
|
||||
bool isWShortedToSupply() const { return status.S2VSW == 0b1; };
|
||||
|
||||
TMC6200_GSTAT status;
|
||||
};
|
||||
|
||||
class TMC6200Driver {
|
||||
|
||||
public:
|
||||
TMC6200Driver(int csPin) : csPin(csPin), spi(&SPI), settings(1000000, MSBFIRST, SPI_MODE3) {};
|
||||
|
||||
virtual ~TMC6200Driver() {};
|
||||
|
||||
virtual void init(SPIClass *_spi);
|
||||
|
||||
void setDriverState(bool state);
|
||||
|
||||
void setPWMMode(TMC6200_PWMMode pwmMode);
|
||||
|
||||
void setFaultDirect(TMC6200_FaultDirect faultDirect);
|
||||
|
||||
void setCurrentSenseGain(TMC6200_AmplificationGain amplificationGain);
|
||||
|
||||
void setOverTemperatureThreshold(TMC6200_OTSelect otLevel);
|
||||
|
||||
void setDriverStrength(TMC6200_DRVStrength strength);
|
||||
|
||||
void setCurrentSenseAmplifierState(bool state);
|
||||
|
||||
void setShortDelay(TMC6200_ShortDelay shortDelay);
|
||||
|
||||
void shortFilter(TMC6200_ShortFilter shortFilter);
|
||||
|
||||
void setShortToSupplySensitivityLevel(uint8_t level);
|
||||
|
||||
void setShortToGroundSensitivityLevel(uint8_t level);
|
||||
|
||||
void setShortRetries(uint8_t retries);
|
||||
|
||||
void setParallelProtect(TMC6200_ParallelProtect parallelProtect);
|
||||
|
||||
void setShortToGroundDetectionState(bool state);
|
||||
|
||||
void setShortToSupplyDetectionState(bool state);
|
||||
|
||||
void setBBMCycles(uint8_t clockCycles);
|
||||
|
||||
void setStatus(TMC6200_GSTAT status);
|
||||
|
||||
TMC6200GStatus getStatus();
|
||||
|
||||
TMC6200_IOIN getInputs();
|
||||
|
||||
private:
|
||||
uint32_t readRegister(uint8_t addr);
|
||||
|
||||
void writeRegister(uint8_t addr, uint32_t data);
|
||||
|
||||
int csPin;
|
||||
SPIClass *spi;
|
||||
SPISettings settings;
|
||||
};
|
||||
|
||||
|
||||
class TMC6200Driver3PWM : public TMC6200Driver, public BLDCDriver3PWM {
|
||||
|
||||
public:
|
||||
TMC6200Driver3PWM(int phA, int phB, int phC, int cs, int en = NOT_SET) :
|
||||
TMC6200Driver(cs), BLDCDriver3PWM(phA, phB, phC, en) {};
|
||||
|
||||
~TMC6200Driver3PWM() override = default;
|
||||
|
||||
virtual void init(SPIClass *_spi = &SPI) override;
|
||||
};
|
||||
|
||||
|
||||
class TMC6200Driver6PWM : public TMC6200Driver, public BLDCDriver6PWM {
|
||||
|
||||
public:
|
||||
TMC6200Driver6PWM(int phA_h, int phA_l, int phB_h, int phB_l, int phC_h, int phC_l, int cs, int en = NOT_SET) :
|
||||
TMC6200Driver(cs), BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, en) {};
|
||||
|
||||
~TMC6200Driver6PWM() override = default;
|
||||
|
||||
virtual void init(SPIClass *_spi = &SPI) override;
|
||||
};
|
||||
@@ -0,0 +1,111 @@
|
||||
#pragma once
|
||||
|
||||
// ------
|
||||
|
||||
#define TMC_WRITE_BIT 0x80
|
||||
#define TMC_ADDRESS_MASK 0x7F
|
||||
#define TMC_ADDRESS(x) ((x) & (TMC_ADDRESS_MASK))
|
||||
|
||||
// ------
|
||||
|
||||
#define TMC6200_GCONF_REG 0x00 // RW
|
||||
#define TMC6200_GSTAT_REG 0x01 // RW + WC
|
||||
#define TMC6200_IOIN_REG 0x04 // R
|
||||
|
||||
#define TMC6200_OTP_PROG_REG 0x06 // not used
|
||||
#define TMC6200_OTP_READ_REG 0x07 // not used
|
||||
#define TMC6200_FACTORY_CONF_REG 0x08 // not used
|
||||
|
||||
#define TMC6200_SHORT_CONF_REG 0x09 // RW
|
||||
#define TMC6200_DRV_CONF_REG 0x0A // RW
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint32_t DISABLE: 1;
|
||||
uint32_t SINGLE_LINE: 1;
|
||||
uint32_t FAULT_DIRECT: 1;
|
||||
uint32_t : 1;
|
||||
uint32_t AMPLIFICATION: 2;
|
||||
uint32_t AMPLIFIER_OFF: 1;
|
||||
uint32_t TMC6200_TEST_MODE: 1;
|
||||
uint32_t : 24;
|
||||
};
|
||||
uint32_t reg;
|
||||
} TMC6200_GCONF;
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint32_t RESET: 1;
|
||||
uint32_t DRV_OTPW: 1;
|
||||
uint32_t DRV_OT: 1;
|
||||
uint32_t UV_CP: 1;
|
||||
|
||||
uint32_t SHORT_DET_U: 1;
|
||||
uint32_t S2GU: 1;
|
||||
uint32_t S2VSU: 1;
|
||||
uint32_t : 1;
|
||||
|
||||
uint32_t SHORT_DET_V: 1;
|
||||
uint32_t S2GV: 1;
|
||||
uint32_t S2VSV: 1;
|
||||
uint32_t : 1;
|
||||
|
||||
uint32_t SHORT_DET_W: 1;
|
||||
uint32_t S2GW: 1;
|
||||
uint32_t S2VSW: 1;
|
||||
uint32_t : 1;
|
||||
};
|
||||
uint32_t reg;
|
||||
} TMC6200_GSTAT;
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
unsigned UL: 1;
|
||||
uint32_t UH: 1;
|
||||
uint32_t VL: 1;
|
||||
uint32_t VH: 1;
|
||||
uint32_t WL: 1;
|
||||
uint32_t WH: 1;
|
||||
uint32_t DRV_EN: 1;
|
||||
uint32_t _reserved1: 1;
|
||||
uint32_t OTPW: 1;
|
||||
uint32_t OT136C: 1;
|
||||
uint32_t OT143C: 1;
|
||||
uint32_t OT150C: 1;
|
||||
uint32_t _reserved2: 12;
|
||||
uint32_t VERSION: 8;
|
||||
};
|
||||
|
||||
uint32_t reg;
|
||||
} TMC6200_IOIN;
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint32_t S2VS_LEVEL: 4;
|
||||
uint32_t : 4;
|
||||
uint32_t S2G_LEVEL: 4;
|
||||
uint32_t : 4;
|
||||
uint32_t SHORT_FILTER: 2;
|
||||
uint32_t : 2;
|
||||
uint32_t SHORT_DELAY: 1;
|
||||
uint32_t : 4;
|
||||
uint32_t RETRY: 2;
|
||||
uint32_t : 2;
|
||||
uint32_t PROTECT_PARALLEL: 1;
|
||||
uint32_t DISABLE_S2G: 1;
|
||||
uint32_t DISABLE_S2VS: 1;
|
||||
uint32_t : 2;
|
||||
};
|
||||
uint32_t reg;
|
||||
} TMC6200_SHORT_CONF;
|
||||
|
||||
typedef union {
|
||||
struct {
|
||||
uint32_t BBMCLKS: 5;
|
||||
uint32_t : 11;
|
||||
uint32_t OT_SELECT: 2;
|
||||
uint32_t DRV_STRENGTH: 2;
|
||||
uint32_t : 12;
|
||||
};
|
||||
uint32_t reg;
|
||||
} TMC6200_DRV_CONF;
|
||||
Reference in New Issue
Block a user