Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/scripts/battery_fit.py
9534 views
1
#!/usr/bin/env python3
2
3
# flake8: noqa
4
5
'''
6
fit coefficients for battery percentate from resting voltage
7
8
See AP_Scripting/applets/BattEstimate.lua
9
'''
10
11
from argparse import ArgumentParser
12
parser = ArgumentParser(description=__doc__)
13
parser.add_argument("--no-graph", action='store_true', default=False, help='disable graph display')
14
parser.add_argument("--num-cells", type=int, default=0, help='cell count, zero for auto-detection')
15
parser.add_argument("--batidx", type=int, default=1, help='battery index')
16
parser.add_argument("--condition", default=None, help='match condition')
17
parser.add_argument("--final-pct", type=float, default=100.0, help='set final percentage in log')
18
parser.add_argument("--comparison", type=str, default=None, help='comparison coefficients')
19
parser.add_argument("log", metavar="LOG")
20
21
args = parser.parse_args()
22
23
import sys
24
import math
25
from pymavlink import mavutil
26
import numpy as np
27
import matplotlib.pyplot as pyplot
28
29
def constrain(value, minv, maxv):
30
"""Constrain a value to a range."""
31
return max(min(value,maxv),minv)
32
33
def SOC_model(cell_volt, c):
34
'''simple model of state of charge versus resting voltage.
35
With thanks to Roho for the form of the equation
36
https://electronics.stackexchange.com/questions/435837/calculate-battery-percentage-on-lipo-battery
37
38
Adjusted to also fit other battery chemistries such as Li-ion.
39
'''
40
p0 = c[3]
41
p1 = c[2]
42
43
return constrain(c[0] * (1.0 - 1.0 / math.pow(1 + math.pow(cell_volt / c[1], p0), p1)), 0, 100)
44
45
def fit_batt(data):
46
'''fit a set of battery data to the SOC model'''
47
from scipy import optimize
48
49
def fit_error(p):
50
p = list(p)
51
ret = 0
52
for (voltR,pct) in data:
53
error = pct - SOC_model(voltR, p)
54
ret += abs(error)
55
56
ret /= len(data)
57
return ret
58
59
p = [123.0, 3.7, 0.165, 80.0]
60
bounds = [(100.0, 10000.0), (3.0, 3.9), (0.001, 0.4), (5.0, 100.0)]
61
62
(p,err,iterations,imode,smode) = optimize.fmin_slsqp(fit_error, p, bounds=bounds, iter=10000, full_output=True)
63
if imode != 0:
64
print("Fit failed: %s" % smode)
65
sys.exit(1)
66
return p
67
68
def ExtractDataLog(logfile):
69
'''find battery fit parameters from a log file'''
70
print("Processing log %s" % logfile)
71
mlog = mavutil.mavlink_connection(logfile)
72
73
Wh_total = 0.0
74
last_t = None
75
data = []
76
last_voltR = None
77
78
while True:
79
msg = mlog.recv_match(type=['BAT'], condition=args.condition)
80
if msg is None:
81
break
82
83
if (
84
msg.get_type() == 'BAT'
85
and (getattr(msg, 'Inst', None) == args.batidx - 1
86
or getattr(msg, 'Instance', None) == args.batidx - 1)
87
and msg.VoltR > 1
88
):
89
current = msg.Curr
90
voltR = msg.VoltR
91
if last_voltR is not None and voltR > last_voltR:
92
continue
93
last_voltR = voltR
94
power = current*voltR
95
t = msg.TimeUS*1.0e-6
96
97
if last_t is None:
98
last_t = t
99
continue
100
101
dt = t - last_t
102
if dt < 0.5:
103
# 2Hz data is plenty
104
continue
105
last_t = t
106
Wh_total += (power*dt)/3600.0
107
108
data.append((voltR,Wh_total))
109
110
if len(data) == 0:
111
print("No data found")
112
sys.exit(1)
113
114
# calculate total pack capacity based on final percentage
115
Wh_max = data[-1][1]/(args.final_pct*0.01)
116
117
fit_data = []
118
119
for i in range(len(data)):
120
(voltR,Wh) = data[i]
121
SOC = 100-100*Wh/Wh_max
122
fit_data.append((voltR, SOC))
123
124
print("Loaded %u samples" % len(data))
125
return fit_data
126
127
def ExtractDataCSV(logfile):
128
'''find battery fit parameters from a CSV file'''
129
print("Processing CSV %s" % logfile)
130
lines = open(logfile,'r').readlines()
131
fit_data = []
132
for line in lines:
133
line = line.strip()
134
if line.startswith("#"):
135
continue
136
v = line.split(',')
137
if len(v) != 2:
138
continue
139
if not v[0][0].isnumeric() or not v[1][0].isnumeric():
140
continue
141
fit_data.append((float(v[1]),float(v[0])))
142
return fit_data
143
144
def BattFit(fit_data, num_cells):
145
146
fit_data = [ (v/num_cells,p) for (v,p) in fit_data ]
147
148
c = fit_batt(fit_data)
149
print("Coefficients C1=%.4f C2=%.4f C3=%.4f C4=%.4f" % (c[0], c[1], c[2], c[3]))
150
151
if args.no_graph:
152
return
153
154
fig, axs = pyplot.subplots()
155
156
np_volt = np.array([v for (v,p) in fit_data])
157
np_pct = np.array([p for (v,p) in fit_data])
158
axs.invert_xaxis()
159
axs.plot(np_volt, np_pct, label='SOC')
160
np_rem = np.zeros(0,dtype=float)
161
162
# pad down to 3.2V to make it easier to visualise for logs that don't go to a low voltage
163
low_volt = np_volt[-1]
164
while low_volt > 3.2:
165
low_volt -= 0.1
166
np_volt = np.append(np_volt, low_volt)
167
168
for i in range(np_volt.size):
169
voltR = np_volt[i]
170
np_rem = np.append(np_rem, SOC_model(voltR, c))
171
172
axs.plot(np_volt, np_rem, label='SOC Fit')
173
174
if args.comparison:
175
c2 = args.comparison.split(',')
176
c2 = [ float(x) for x in c2 ]
177
np_rem2 = np.zeros(0,dtype=float)
178
for i in range(np_volt.size):
179
voltR = np_volt[i]
180
np_rem2 = np.append(np_rem2, SOC_model(voltR, c2))
181
axs.plot(np_volt, np_rem2, label='SOC Fit2')
182
183
axs.legend(loc='upper left')
184
axs.set_title('Battery Fit')
185
186
pyplot.show()
187
188
def get_cell_count(data):
189
if args.num_cells != 0:
190
return args.num_cells
191
volts = [ v[0] for v in data ]
192
volts = sorted(volts)
193
num_cells = round(volts[-1]/4.2)
194
print("Max voltags %.1f num_cells %u" % (volts[-1], num_cells))
195
return num_cells
196
197
if args.log.upper().endswith(".CSV"):
198
fit_data = ExtractDataCSV(args.log)
199
else:
200
fit_data = ExtractDataLog(args.log)
201
202
num_cells = get_cell_count(fit_data)
203
BattFit(fit_data, num_cells)
204
205