-
Notifications
You must be signed in to change notification settings - Fork 70
/
Copy pathdrv8316.h
316 lines (216 loc) · 7.2 KB
/
drv8316.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
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