DRV8323S wip
This commit is contained in:
parent
9de2e98a6e
commit
53d773b169
73
fw/src/DRV8323S.hpp
Normal file
73
fw/src/DRV8323S.hpp
Normal file
@ -0,0 +1,73 @@
|
|||||||
|
#ifndef _DRV8323S_H
|
||||||
|
#define _DRV8323S_H
|
||||||
|
|
||||||
|
enum {
|
||||||
|
DRV8323S_FAULT_STATUS1_REG = 0x00,
|
||||||
|
DRV8323S_FAULT_STATUS2_REG = 0x01,
|
||||||
|
DRV8323S_DRIVER_CONTROL_REG = 0x02,
|
||||||
|
DRV8323S_GATE_DRIVE_HS_REG = 0x03,
|
||||||
|
DRV8323S_GATE_DRIVE_LS_REG = 0x04,
|
||||||
|
DRV8323S_OCP_CONTROL_REG = 0x05,
|
||||||
|
DRV8323S_CSA_CONTROL_REG = 0x06,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x00 */ {
|
||||||
|
DRV8323S_FAULT_STATUS1_FAULT_MASK = 1 << 10, /* logic or of all faults */
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_OCP_MASK = 1 << 9, /* vds monitor overcurrent */
|
||||||
|
DRV8323S_FAULT_STATUS1_GDF_MASK = 1 << 8, /* gate drive fault */
|
||||||
|
DRV8323S_FAULT_STATUS1_UVLO_MASK = 1 << 7, /* undervoltage lockout fault */
|
||||||
|
DRV8323S_FAULT_STATUS1_OTSD_MASK = 1 << 6, /* over temperature shutdown */
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_HA_MASK = 1 << 5, /* overcurrent on FET */
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_LA_MASK = 1 << 4,
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_HB_MASK = 1 << 3,
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_LB_MASK = 1 << 2,
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_HC_MASK = 1 << 1,
|
||||||
|
DRV8323S_FAULT_STATUS1_VDS_LC_MASK = 1 << 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x01 */ {
|
||||||
|
DRV8323S_FAULT_STATUS1_SA_OC_MASK = 1 << 10, /* Sense amp OC */
|
||||||
|
DRV8323S_FAULT_STATUS1_SB_OC_MASK = 1 << 9,
|
||||||
|
DRV8323S_FAULT_STATUS1_SC_OC_MASK = 1 << 8,
|
||||||
|
DRV8323S_FAULT_STATUS1_OTW_MASK = 1 << 7, /* over temp warning */
|
||||||
|
DRV8323S_FAULT_STATUS1_CPUV_MASK = 1 << 6, /* charge pump fault */
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_HA_MASK = 1 << 5, /* FET gate drive failt */
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_LA_MASK = 1 << 4,
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_HB_MASK = 1 << 3,
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_LB_MASK = 1 << 2,
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_HC_MASK = 1 << 1,
|
||||||
|
DRV8323S_FAULT_STATUS1_VGS_LC_MASK = 1 << 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x02 */ {
|
||||||
|
DRV8323S_DRIVER_CONTROL_DIS_CPUV_MASK =
|
||||||
|
1 << 9, /* chrg pump uvlo fault disable */
|
||||||
|
DRV8323S_DRIVER_CONTROL_DIS_GDF_MASK = 1 << 8, /* gate drive fault disable */
|
||||||
|
DRV8323S_DRIVER_CONTROL_OTW_REP_MASK = 1
|
||||||
|
<< 7, /* over temp wariing reported */
|
||||||
|
DRV8323S_DRIVER_CONTROL_PWM_MODE_MASK = 0b11 << 5, /* PWM mode */
|
||||||
|
DRV8323S_DRIVER_CONTROL_1PWM_COM_MASK = 1 << 4, /* 1PWM mode diode freewheel*/
|
||||||
|
DRV8323S_DRIVER_CONTROL_1PWM_DIR_MASK = 1 << 3, /* 1PWM mode direction */
|
||||||
|
DRV8323S_DRIVER_CONTROL_COAST_MASK = 1 << 2, /* all FETs in Hi-Z */
|
||||||
|
DRV8323S_DRIVER_CONTROL_BRAKE_MASK = 1 << 1, /* all low FETs on */
|
||||||
|
DRV8323S_DRIVER_CONTROL_CLR_FLT_MASK = 1 << 1, /* clear latched fault bits */
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x03 */ {
|
||||||
|
DRV8323S_GATE_DRIVE_HS_LOCK_MASK = 0b111 << 8, /* lock register */
|
||||||
|
DRV8323S_GATE_DRIVE_HS_IDRIVEP_HS_MASK = 0b1111 << 4, /* HS positiv current */
|
||||||
|
DRV8323S_GATE_DRIVE_HS_IDRIVEN_HS_MASK = 0b1111 << 0, /* HS negativ current */
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x04 */ {
|
||||||
|
DRV8323S_GATE_DRIVE_LS_CBC_MASK = 1 << 10, /* cycle-by cycle operation */
|
||||||
|
DRV8323S_GATE_DRIVE_LS_TDRIVE_MASK = 0b11 << 8, /* peak gate curr drive t*/
|
||||||
|
DRV8323S_GATE_DRIVE_LS_IDRIVEP_LS_MASK = 0b1111 << 4, /* LS positiv current */
|
||||||
|
DRV8323S_GATE_DRIVE_LS_IDRIVEN_LS_MASK = 0b1111 << 0, /* LS negativ current */
|
||||||
|
};
|
||||||
|
|
||||||
|
enum /* 0x05 */ {
|
||||||
|
DRV8323S_OCP_CONTROL_TRETRY_MASK = 1 << 10, /* 0=4ms, 1=50us */
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* _DRV8323S_H */
|
122
fw/src/main.cpp
122
fw/src/main.cpp
@ -24,36 +24,33 @@
|
|||||||
// #include "esp32-hal.h"
|
// #include "esp32-hal.h"
|
||||||
// #include "simplesync.hpp"
|
// #include "simplesync.hpp"
|
||||||
|
|
||||||
#define ENC_A 17
|
#define ENC_A 11
|
||||||
#define ENC_B 8
|
#define ENC_B 8
|
||||||
|
|
||||||
#define I2C_SDA 18
|
#define I2C_SDA 18
|
||||||
#define I2C_SCL 0
|
#define I2C_SCL 0
|
||||||
|
|
||||||
#define DRVOFF 46
|
#define DRVEN 15
|
||||||
#define TERP_PCB 2
|
#define TERMISTOR_PCB 3
|
||||||
#define TERP_EXT 1
|
#define TERMISTOR_EXT 9
|
||||||
|
|
||||||
#define SOA 3
|
#define SOA 1
|
||||||
#define SOB 9
|
#define SOB 2
|
||||||
#define SOC 10
|
#define SOC 10
|
||||||
|
|
||||||
#define INLA 21
|
#define INHA 14
|
||||||
#define INHA 47
|
#define INHB 13
|
||||||
#define INLB 13
|
|
||||||
#define INHB 14
|
|
||||||
#define INLC 11
|
|
||||||
#define INHC 12
|
#define INHC 12
|
||||||
|
|
||||||
#define CAN_TX 45
|
#define CAN_TX 6
|
||||||
#define CAN_RX 48
|
#define CAN_RX 7
|
||||||
|
|
||||||
#define SPI_MISO 6
|
#define SPI_MISO 45
|
||||||
#define SPI_MOSI 7
|
#define SPI_MOSI 48
|
||||||
#define SPI_CLK 15
|
#define SPI_CLK 47
|
||||||
#define SPI_DRV_SC 16
|
#define SPI_DRV_SC 21
|
||||||
|
|
||||||
#define MOTOR
|
// #define MOTOR
|
||||||
#define SSIF_USBSERIAL
|
#define SSIF_USBSERIAL
|
||||||
#define FW_NO_WATCHDOG
|
#define FW_NO_WATCHDOG
|
||||||
|
|
||||||
@ -94,21 +91,11 @@ void read_i2c(uint8_t addr, uint8_t reg, uint8_t *buf, uint8_t len) {
|
|||||||
Wire.write(reg); // MAN:0x2E
|
Wire.write(reg); // MAN:0x2E
|
||||||
int error = Wire.endTransmission();
|
int error = Wire.endTransmission();
|
||||||
if (error != 0) {
|
if (error != 0) {
|
||||||
// Serial.println("read error!");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
delayMicroseconds(50);
|
delayMicroseconds(50);
|
||||||
int ret = Wire.requestFrom(addr, len);
|
int ret = Wire.requestFrom(addr, len);
|
||||||
// Serial.print("0x");
|
|
||||||
// Serial.print(reg, HEX);
|
|
||||||
// Serial.print(": ");
|
|
||||||
Wire.readBytes(buf, ret);
|
Wire.readBytes(buf, ret);
|
||||||
// for (int i = 0; i < ret; ++i) {
|
|
||||||
// Serial.print("0x");
|
|
||||||
// Serial.print(Wire.read(), HEX);
|
|
||||||
// Serial.print(" ");
|
|
||||||
// }
|
|
||||||
// Serial.println();
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -118,7 +105,6 @@ void write_i2c(uint8_t addr, uint8_t reg_lsb, uint8_t val) {
|
|||||||
Wire.write(data, sizeof data);
|
Wire.write(data, sizeof data);
|
||||||
int error = Wire.endTransmission();
|
int error = Wire.endTransmission();
|
||||||
if (error != 0) {
|
if (error != 0) {
|
||||||
// Serial.println("write error!");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -128,67 +114,10 @@ void write_dual_i2c(uint8_t addr, uint8_t reg_lsb, uint8_t val1, uint8_t val2) {
|
|||||||
Wire.write(data, sizeof data);
|
Wire.write(data, sizeof data);
|
||||||
int error = Wire.endTransmission();
|
int error = Wire.endTransmission();
|
||||||
if (error != 0) {
|
if (error != 0) {
|
||||||
// Serial.println("write error!");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void status() {
|
|
||||||
|
|
||||||
DRV8316Status status = driver.getStatus();
|
|
||||||
SSYNCIF.println("DRV8316 Status:");
|
|
||||||
SSYNCIF.print("Fault: ");
|
|
||||||
SSYNCIF.println(status.isFault());
|
|
||||||
SSYNCIF.print("Buck Error: ");
|
|
||||||
SSYNCIF.print(status.isBuckError());
|
|
||||||
SSYNCIF.print(" Undervoltage: ");
|
|
||||||
SSYNCIF.print(status.isBuckUnderVoltage());
|
|
||||||
SSYNCIF.print(" OverCurrent: ");
|
|
||||||
SSYNCIF.println(status.isBuckOverCurrent());
|
|
||||||
SSYNCIF.print("Charge Pump UnderVoltage: ");
|
|
||||||
SSYNCIF.println(status.isChargePumpUnderVoltage());
|
|
||||||
SSYNCIF.print("OTP Error: ");
|
|
||||||
SSYNCIF.println(status.isOneTimeProgrammingError());
|
|
||||||
SSYNCIF.print("OverCurrent: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent());
|
|
||||||
SSYNCIF.print(" Ah: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent_Ah());
|
|
||||||
SSYNCIF.print(" Al: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent_Al());
|
|
||||||
SSYNCIF.print(" Bh: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent_Bh());
|
|
||||||
SSYNCIF.print(" Bl: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent_Bl());
|
|
||||||
SSYNCIF.print(" Ch: ");
|
|
||||||
SSYNCIF.print(status.isOverCurrent_Ch());
|
|
||||||
SSYNCIF.print(" Cl: ");
|
|
||||||
SSYNCIF.println(status.isOverCurrent_Cl());
|
|
||||||
SSYNCIF.print("OverTemperature: ");
|
|
||||||
SSYNCIF.print(status.isOverTemperature());
|
|
||||||
SSYNCIF.print(" Shutdown: ");
|
|
||||||
SSYNCIF.print(status.isOverTemperatureShutdown());
|
|
||||||
SSYNCIF.print(" Warning: ");
|
|
||||||
SSYNCIF.println(status.isOverTemperatureWarning());
|
|
||||||
SSYNCIF.print("OverVoltage: ");
|
|
||||||
SSYNCIF.println(status.isOverVoltage());
|
|
||||||
SSYNCIF.print("PowerOnReset: ");
|
|
||||||
SSYNCIF.println(status.isPowerOnReset());
|
|
||||||
SSYNCIF.print("SPI Error: ");
|
|
||||||
SSYNCIF.print(status.isSPIError());
|
|
||||||
SSYNCIF.print(" Address: ");
|
|
||||||
SSYNCIF.print(status.isSPIAddressError());
|
|
||||||
SSYNCIF.print(" Clock: ");
|
|
||||||
SSYNCIF.print(status.isSPIClockFramingError());
|
|
||||||
SSYNCIF.print(" Parity: ");
|
|
||||||
SSYNCIF.println(status.isSPIParityError());
|
|
||||||
DRV8316_PWMMode val = driver.getPWMMode();
|
|
||||||
SSYNCIF.print("PWM Mode: ");
|
|
||||||
SSYNCIF.println(val);
|
|
||||||
SSYNCIF.print("Recirculation: ");
|
|
||||||
SSYNCIF.println(driver.getRecirculationMode());
|
|
||||||
}
|
|
||||||
// Preferences prefs;
|
|
||||||
|
|
||||||
SemaphoreHandle_t mutex;
|
SemaphoreHandle_t mutex;
|
||||||
struct sync_params {};
|
struct sync_params {};
|
||||||
|
|
||||||
@ -235,14 +164,14 @@ void setup() {
|
|||||||
// Wire.setTimeOut(10);
|
// Wire.setTimeOut(10);
|
||||||
Wire.begin(I2C_SDA, I2C_SCL, 400000);
|
Wire.begin(I2C_SDA, I2C_SCL, 400000);
|
||||||
|
|
||||||
pinMode(DRVOFF, OUTPUT);
|
// pinMode(DRVOFF, OUTPUT);
|
||||||
digitalWrite(DRVOFF, 0); // enable
|
// digitalWrite(DRVOFF, 0); // enable
|
||||||
pinMode(INLA, OUTPUT);
|
// pinMode(INLA, OUTPUT);
|
||||||
digitalWrite(INLA, 1); // enable
|
// digitalWrite(INLA, 1); // enable
|
||||||
pinMode(INLB, OUTPUT);
|
// pinMode(INLB, OUTPUT);
|
||||||
digitalWrite(INLB, 1); // enable
|
// digitalWrite(INLB, 1); // enable
|
||||||
pinMode(INLC, OUTPUT);
|
// pinMode(INLC, OUTPUT);
|
||||||
digitalWrite(INLC, 1); // enable
|
// digitalWrite(INLC, 1); // enable
|
||||||
|
|
||||||
// write_i2c(0x36,0x07, 0b00000011);
|
// write_i2c(0x36,0x07, 0b00000011);
|
||||||
write_i2c(0x36, 0x09, 0xFF);
|
write_i2c(0x36, 0x09, 0xFF);
|
||||||
@ -253,7 +182,6 @@ void setup() {
|
|||||||
driver.voltage_power_supply = 15;
|
driver.voltage_power_supply = 15;
|
||||||
SPI.begin(SPI_CLK, SPI_MISO, SPI_MOSI, SPI_DRV_SC);
|
SPI.begin(SPI_CLK, SPI_MISO, SPI_MOSI, SPI_DRV_SC);
|
||||||
driver.init(&SPI);
|
driver.init(&SPI);
|
||||||
driver.setSlew(DRV8316_Slew::Slew_200Vus);
|
|
||||||
status();
|
status();
|
||||||
motor.linkDriver(&driver);
|
motor.linkDriver(&driver);
|
||||||
// motor.linkSensor(&encoder);
|
// motor.linkSensor(&encoder);
|
||||||
@ -384,7 +312,9 @@ void loop() {
|
|||||||
|
|
||||||
motor.move(3);
|
motor.move(3);
|
||||||
#endif
|
#endif
|
||||||
// delay(100);
|
encoder.update(); // optional: Update manually if not using loopfoc()
|
||||||
|
SSYNCIF.println(encoder.getAngle());
|
||||||
|
delay(100);
|
||||||
// static int i = 0;
|
// static int i = 0;
|
||||||
// if (i++ % 100 == 0)
|
// if (i++ % 100 == 0)
|
||||||
// status();
|
// status();
|
||||||
|
Loading…
x
Reference in New Issue
Block a user