-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy path3drPilotReadBMS.ino
More file actions
288 lines (234 loc) · 11.3 KB
/
3drPilotReadBMS.ino
File metadata and controls
288 lines (234 loc) · 11.3 KB
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
/**********************************
* SMBus FOR 3DR SOLO with Arduino UNO R3
* STAVROPOULOS
* Code Version 0.02 beta
*
* MUCH OF THIS CODE WAS COPIED FROM
* https://github.com/PowerCartel/PackProbe/blob/master/PackProbe/PackProbe.ino
* https://github.com/ArduPilot/PX4Firmware/blob/master/src/drivers/batt_smbus/batt_smbus.cpp
*
**********************************/
/**********************************
* Configured for Arduino UNO R3
* you will need to use external pull up resistors of
* 4.7k-ohm to pull the SDA and SCL lines up to 3.3v
**********************************/
/**********************************
* CONFIGURE I2C/SERIAL ON ARDUINO
**********************************/
//DEFINE SDA AND SCL PINS
#define SCL_PIN 5 //COMMUNICATION PIN 5 ON MEGA
#define SCL_PORT PORTC
#define SDA_PIN 4 //COMMUNICATION PIN 6 ON MEGA
#define SDA_PORT PORTC
//CONFIGURE I2C MODES
#define I2C_TIMEOUT 100 //PREVENT SLAVE DEVICES FROM STRETCHING LOW PERIOD OF THE CLOCK INDEFINITELY AND LOCKING UP MCU BY DEFINING TIMEOUT
//#define I2C_NOINTERRUPT 1 //SET TO 1 IF SMBus DEVICE CAN TIMEOUT
//#define I2C_FASTMODE 1 //THE STANDARD I2C FREQ IS 100kHz. USE THIS TO PERMIT FASTER UP TO 400kHz.
//#define I2C_SLOWMODE 1 //THE STANDARD I2C FREQ IS 100kHz. USE THIS TO PERMIT SLOWER, DOWN TO 25kHz.
#define BAUD_RATE 115200
#include <SoftI2CMaster.h>
/**********************************
* CONFIGURE SERIAL LIBRARY
**********************************/
//#include <SoftwareSerial.h>
//#include <Serial.h>
#include <Wire.h>
/**********************************
* DEFINE VARIABLES AND SMBus MAPPINGS
**********************************/
#define BATT_SMBUS_ADDR 0x0B ///< I2C address
#define BATT_SMBUS_ADDR_MIN 0x08 ///< lowest possible address
#define BATT_SMBUS_ADDR_MAX 0x7F ///< highest possible address
//BUS MAPPINGS FROM DEV.3DR
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
#define BATT_SMBUS_REMAINING_CAPACITY 0x0f ///< predicted remaining battery capacity as a percentage
#define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
#define BATT_SMBUS_SERIALNUM 0x1c ///< serial number register
#define BATT_SMBUS_MANUFACTURE_NAME 0x20 ///< manufacturer name
#define BATT_SMBUS_MANUFACTURE_DATA 0x23 ///< manufacturer data
#define BATT_SMBUS_MANUFACTURE_INFO 0x25 ///< cell voltage register
#define BATT_SMBUS_CURRENT 0x2a ///< current register
#define BATT_SMBUS_MEASUREMENT_INTERVAL_US (1000000 / 10) ///< time in microseconds, measure at 10hz
#define BATT_SMBUS_TIMEOUT_US 10000000 ///< timeout looking for battery 10seconds after startup
#define BATT_SMBUS_BUTTON_DEBOUNCE_MS 300 ///< button holds longer than this time will cause a power off event
#define BATT_SMBUS_PEC_POLYNOMIAL 0x07 ///< Polynomial for calculating PEC
#define BATT_SMBUS_I2C_BUS PX4_I2C_BUS_EXPANSION
//BUS MAPPINGS FROM SMBus PROTOCOL DOCUMENTATION
#define BATTERY_MODE 0x03
#define CURRENT 0x0A
#define RELATIVE_SOC 0x0D
#define ABSOLUTE_SOC 0x0E
#define TIME_TO_FULL 0x13
#define CHARGING_CURRENT 0x14
#define CHARGING_VOLTAGE 0x15
#define BATTERY_STATUS 0x16
#define CYCLE_COUNT 0x17
#define SPEC_INFO 0x1A
#define MFG_DATE 0x1B
#define DEV_NAME 0x21 // String
#define CELL_CHEM 0x22 // String
#define CELL4_VOLTAGE 0x3C // Indidual cell voltages don't work on Lenovo and Dell Packs
#define CELL3_VOLTAGE 0x3D
#define CELL2_VOLTAGE 0x3E
#define CELL1_VOLTAGE 0x3F
#define STATE_OF_HEALTH 0x4F
//END BUS MAPPINGS
#define bufferLen 32
uint8_t i2cBuffer[bufferLen];
// standard I2C address for Smart Battery packs
byte deviceAddress = BATT_SMBUS_ADDR;
void setup()
{
//INITIATE SERIAL CONSOLE
Serial.begin(BAUD_RATE);
Serial.println(i2c_init());
//SETUP I2C INPUT PINS
//pinMode(27,INPUT_PULLUP); //use external pull up resistor instead
//pinMode(28,INPUT_PULLUP); //use external pull up resistor instead
Serial.flush();
while (!Serial) {
; //wait for Console port to connect.
}
Serial.println("Console Initialized");
i2c_init(); //i2c_start initialized the I2C system. will return false if bus is locked.
Serial.println("I2C Inialized");
scan();
}
int fetchWord(byte func)
{
i2c_start(deviceAddress<<1 | I2C_WRITE); //Initiates a transfer to the slave device with the (8-bit) I2C address addr.
//Alternatively, use i2c_start_wait which tries repeatedly to start transfer until acknowledgment received
//i2c_start_wait(deviceAddress<<1 | I2C_WRITE);
i2c_write(func); //Sends a byte to the previously addressed device. Returns true if the device replies with an ACK.
i2c_rep_start(deviceAddress<<1 | I2C_READ); //Sends a repeated start condition, i.e., it starts a new transfer without sending first a stop condition.
byte b1 = i2c_read(false); //i2c_read Requests to receive a byte from the slave device. If last is true,
//then a NAK is sent after receiving the byte finishing the read transfer sequence.
byte b2 = i2c_read(true);
i2c_stop(); //Sends a stop condition and thereby releases the bus.
return (int)b1|((( int)b2)<<8);
}
uint8_t i2c_smbus_read_block ( uint8_t command, uint8_t* blockBuffer, uint8_t blockBufferLen )
{
uint8_t x, num_bytes;
i2c_start((deviceAddress<<1) + I2C_WRITE);
i2c_write(command);
i2c_rep_start((deviceAddress<<1) + I2C_READ);
num_bytes = i2c_read(false); //num of bytes; 1 byte will be index 0
num_bytes = constrain(num_bytes,0,blockBufferLen-2); //room for null at the end
for (x=0; x<num_bytes-1; x++) { //-1 because x=num_bytes-1 if x<y; last byte needs to be "nack"'d, x<y-1
blockBuffer[x] = i2c_read(false);
}
blockBuffer[x++] = i2c_read(true); //this will nack the last byte and store it in x's num_bytes-1 address.
blockBuffer[x] = 0; // and null it at last_byte+1
i2c_stop();
return num_bytes;
}
void scan()
{
byte i = 0;
for ( i= 0; i < 127; i++ )
{
Serial.print("Address: 0x");
Serial.print(i,HEX);
bool ack = i2c_start(i<<1 | I2C_WRITE);
if ( ack ) {
Serial.println(": OK");
Serial.flush();
}
else {
Serial.println(": -");
Serial.flush();
}
i2c_stop();
}
}
void loop()
{
uint8_t length_read = 0;
Serial.print("Manufacturer Name: ");
length_read = i2c_smbus_read_block(BATT_SMBUS_MANUFACTURE_NAME, i2cBuffer, bufferLen);
Serial.write(i2cBuffer, length_read);
Serial.println("");
Serial.print("Manufacturer Data: ");
length_read = i2c_smbus_read_block(BATT_SMBUS_MANUFACTURE_DATA, i2cBuffer, bufferLen);
Serial.write(i2cBuffer, length_read);
Serial.println("");
Serial.print("Manufacturer Info: ");
length_read = i2c_smbus_read_block(BATT_SMBUS_MANUFACTURE_INFO, i2cBuffer, bufferLen);
Serial.write(i2cBuffer, length_read);
Serial.println("");
Serial.print("Design Capacity: " );
Serial.println(fetchWord(BATT_SMBUS_DESIGN_CAPACITY));
Serial.print("Design Voltage: " );
Serial.println(fetchWord(BATT_SMBUS_DESIGN_VOLTAGE));
Serial.print("Serial Number: ");
Serial.println(fetchWord(BATT_SMBUS_SERIALNUM));
Serial.print("Voltage: ");
Serial.println((float)fetchWord(BATT_SMBUS_VOLTAGE)/1000);
Serial.print("Full Charge Capacity: " );
Serial.println(fetchWord(BATT_SMBUS_FULL_CHARGE_CAPACITY));
Serial.print("Remaining Capacity: " );
Serial.println(fetchWord(BATT_SMBUS_REMAINING_CAPACITY));
Serial.print("Temp: ");
unsigned int tempk = fetchWord(BATT_SMBUS_TEMP);
Serial.println((float)tempk/10.0-273.15);
Serial.print("Current (mA): " );
Serial.println(fetchWord(BATT_SMBUS_CURRENT));
Serial.print("Device Name: ");
length_read = i2c_smbus_read_block(DEV_NAME, i2cBuffer, bufferLen);
Serial.write(i2cBuffer, length_read);
Serial.println("");
Serial.print("Chemistry ");
length_read = i2c_smbus_read_block(CELL_CHEM, i2cBuffer, bufferLen);
Serial.write(i2cBuffer, length_read);
Serial.println("");
String formatted_date = "Manufacture Date (Y-M-D): ";
int mdate = fetchWord(MFG_DATE);
int mday = B00011111 & mdate;
int mmonth = mdate>>5 & B00001111;
int myear = 1980 + (mdate>>9 & B01111111);
formatted_date += myear;
formatted_date += "-";
formatted_date += mmonth;
formatted_date += "-";
formatted_date += mday;
Serial.println(formatted_date);
Serial.print("Specification Info: ");
Serial.println(fetchWord(SPEC_INFO));
Serial.print("Cycle Count: " );
Serial.println(fetchWord(CYCLE_COUNT));
Serial.print("Relative Charge(%): ");
Serial.println(fetchWord(RELATIVE_SOC));
Serial.print("Absolute Charge(%): ");
Serial.println(fetchWord(ABSOLUTE_SOC));
Serial.print("Minutes remaining for full charge: ");
Serial.println(fetchWord(TIME_TO_FULL));
// These aren't part of the standard, but work with some packs.
// They don't work with the Lenovo and Dell packs we've tested
Serial.print("Cell 1 Voltage: ");
Serial.println(fetchWord(CELL1_VOLTAGE));
Serial.print("Cell 2 Voltage: ");
Serial.println(fetchWord(CELL2_VOLTAGE));
Serial.print("Cell 3 Voltage: ");
Serial.println(fetchWord(CELL3_VOLTAGE));
Serial.print("Cell 4 Voltage: ");
Serial.println(fetchWord(CELL4_VOLTAGE));
Serial.print("State of Health: ");
Serial.println(fetchWord(STATE_OF_HEALTH));
Serial.print("Battery Mode (BIN): 0b");
Serial.println(fetchWord(BATTERY_MODE),BIN);
Serial.print("Battery Status (BIN): 0b");
Serial.println(fetchWord(BATTERY_STATUS),BIN);
Serial.print("Charging Current: ");
Serial.println(fetchWord(CHARGING_CURRENT));
Serial.print("Charging Voltage: ");
Serial.println(fetchWord(CHARGING_VOLTAGE));
Serial.print("Current (mA): " );
Serial.println(fetchWord(CURRENT));
Serial.println(".");
delay(5000);
}