diff --git a/src/drivers/drv832x/drv832x.cpp b/src/drivers/drv832x/drv832x.cpp index 62fd625..ac77555 100644 --- a/src/drivers/drv832x/drv832x.cpp +++ b/src/drivers/drv832x/drv832x.cpp @@ -23,9 +23,7 @@ void DRV832xDriver6PWM::init(SPIClass* _spi) { }; void DRV832xDriver::init(SPIClass* _spi) { - // TODO make SPI speed configurable spi = _spi; - settings = SPISettings(1000000, MSBFIRST, SPI_MODE1); //setup pins pinMode(cs, OUTPUT); @@ -50,8 +48,6 @@ void DRV832xDriver::init(SPIClass* _spi) { }; - - uint16_t DRV832xDriver::readSPI(uint8_t addr) { digitalWrite(cs, 0); spi->beginTransaction(settings); @@ -119,7 +115,6 @@ DRV832xStatus DRV832xDriver::getStatus() { return DRV832xStatus(data0, data1); } - void DRV832xDriver::clearFault() { uint16_t result = readSPI(Driver_Control_ADDR); Driver_Control data; @@ -172,6 +167,24 @@ def_getset(CurrentSenseOvercurrentSensitivity, DRV832x_CS_VSEN_LVL, CSA_Control_ def_isset(CurrentSenseCalibrateA, CSA_Control_ADDR, CSA_Control, CSA_CAL_A); def_isset(CurrentSenseCalibrateB, CSA_Control_ADDR, CSA_Control, CSA_CAL_B); def_isset(CurrentSenseCalibrateC, CSA_Control_ADDR, CSA_Control, CSA_CAL_C); + + +void DRV832xDriver::calibrate_current_sense() +{ + CSA_Control csa_control_before, csa_control_cal; + csa_control_before.reg = readSPI(CSA_Control_ADDR); + csa_control_cal.reg = csa_control_before.reg; + csa_control_cal.CSA_CAL_A = 1; + csa_control_cal.CSA_CAL_B = 1; + csa_control_cal.CSA_CAL_C = 1; + writeSPI(CSA_Control_ADDR, csa_control_cal.reg); + delay(1); //Calibration routine requires 100us, we're waiting for 1ms to be safe + csa_control_before.CSA_CAL_A = 0; + csa_control_before.CSA_CAL_B = 0; + csa_control_before.CSA_CAL_C = 0; + writeSPI(CSA_Control_ADDR, csa_control_before.reg); //restore settings, as the calibration may have changed the sensitivity to 40V/V +} + def_isset(CurrentSenseOvercurrentDisable, CSA_Control_ADDR, CSA_Control, DIS_SEN); def_getset(CurrentSenseGain, DRV832x_CSAGain, CSA_Control_ADDR, CSA_Control, CSA_GAIN) def_isset(CurrentSenseOvercurrentResistor, CSA_Control_ADDR, CSA_Control, LS_REF); diff --git a/src/drivers/drv832x/drv832x.h b/src/drivers/drv832x/drv832x.h index e6a46b1..e287f94 100644 --- a/src/drivers/drv832x/drv832x.h +++ b/src/drivers/drv832x/drv832x.h @@ -187,7 +187,7 @@ class DRV832xStatus : public DRV832xFault, public DRV832xVGS { class DRV832xDriver { public: - DRV832xDriver(int cs, bool currentLimit = false, int nFault = NOT_SET) : currentLimit(currentLimit), cs(cs), nFault(nFault), spi(&SPI), settings(1000000, MSBFIRST, SPI_MODE1) {}; + DRV832xDriver(int cs, int nFault = NOT_SET, uint32_t spi_clock = 1000000) : cs(cs), nFault(nFault), spi(&SPI), settings(spi_clock, MSBFIRST, SPI_MODE1) {}; virtual ~DRV832xDriver() {}; virtual void init(SPIClass* _spi = &SPI); @@ -230,6 +230,8 @@ class DRV832xDriver { decl_isset(CurrentSenseCalibrateA); decl_isset(CurrentSenseCalibrateB); decl_isset(CurrentSenseCalibrateC); + void calibrate_current_sense(); + decl_isset(CurrentSenseOvercurrentDisable); decl_getset(CurrentSenseGain, DRV832x_CSAGain); decl_isset(CurrentSenseOvercurrentResistor); @@ -240,7 +242,6 @@ class DRV832xDriver { uint16_t readSPI(uint8_t addr); uint16_t writeSPI(uint8_t addr, uint16_t value); - bool currentLimit; int cs; int nFault; SPIClass* spi; @@ -253,8 +254,8 @@ class DRV832xDriver { class DRV832xDriver3PWM : public DRV832xDriver, public BLDCDriver3PWM { public: - DRV832xDriver3PWM(int phA,int phB,int phC, int cs, bool currentLimit = false, int en = NOT_SET, int nFault = NOT_SET) : - DRV832xDriver(cs, currentLimit, nFault), BLDCDriver3PWM(phA, phB, phC, en) { enable_active_high=false; }; + DRV832xDriver3PWM(int phA,int phB,int phC, int cs, int en = NOT_SET, int nFault = NOT_SET, uint32_t spi_clock = 1000000) : + DRV832xDriver(cs, nFault, spi_clock), BLDCDriver3PWM(phA, phB, phC, en) { enable_active_high=false; }; virtual ~DRV832xDriver3PWM() {}; virtual void init(SPIClass* _spi = &SPI) override; @@ -266,8 +267,8 @@ class DRV832xDriver3PWM : public DRV832xDriver, public BLDCDriver3PWM { class DRV832xDriver6PWM : public DRV832xDriver, public BLDCDriver6PWM { public: - DRV832xDriver6PWM(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) : - DRV832xDriver(cs, currentLimit, nFault), BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, en) { enable_active_high=false; }; + DRV832xDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h,int phC_l, int cs, int en = NOT_SET, int nFault = NOT_SET, uint32_t spi_clock = 1000000) : + DRV832xDriver(cs, nFault, spi_clock), BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, en) { enable_active_high=false; }; virtual ~DRV832xDriver6PWM() {}; virtual void init(SPIClass* _spi = &SPI) override;