Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/scripts/battery_fit.py
Views: 1798
#!/usr/bin/env python1'''2fit coefficients for battery percentate from resting voltage34See AP_Scripting/applets/BattEstimate.lua5'''67from argparse import ArgumentParser8parser = ArgumentParser(description=__doc__)9parser.add_argument("--no-graph", action='store_true', default=False, help='disable graph display')10parser.add_argument("--num-cells", type=int, default=0, help='cell count, zero for auto-detection')11parser.add_argument("--batidx", type=int, default=1, help='battery index')12parser.add_argument("--condition", default=None, help='match condition')13parser.add_argument("--final-pct", type=float, default=100.0, help='set final percentage in log')14parser.add_argument("--comparison", type=str, default=None, help='comparison coefficients')15parser.add_argument("log", metavar="LOG")1617args = parser.parse_args()1819import sys20import math21from pymavlink import mavutil22import numpy as np23import matplotlib.pyplot as pyplot2425def constrain(value, minv, maxv):26"""Constrain a value to a range."""27return max(min(value,maxv),minv)2829def SOC_model(cell_volt, c):30'''simple model of state of charge versus resting voltage.31With thanks to Roho for the form of the equation32https://electronics.stackexchange.com/questions/435837/calculate-battery-percentage-on-lipo-battery33'''34p0 = 80.035p1 = c[2]36return constrain(c[0]*(1.0-1.0/math.pow(1+math.pow(cell_volt/c[1],p0),p1)),0,100)3738def fit_batt(data):39'''fit a set of battery data to the SOC model'''40from scipy import optimize4142def fit_error(p):43p = list(p)44ret = 045for (voltR,pct) in data:46error = pct - SOC_model(voltR, p)47ret += abs(error)4849ret /= len(data)50return ret5152p = [123.0, 3.7, 0.165]53bounds = [(100.0, 10000.0), (3.0,3.9), (0.001, 0.4)]5455(p,err,iterations,imode,smode) = optimize.fmin_slsqp(fit_error, p, bounds=bounds, iter=10000, full_output=True)56if imode != 0:57print("Fit failed: %s" % smode)58sys.exit(1)59return p6061def ExtractDataLog(logfile):62'''find battery fit parameters from a log file'''63print("Processing log %s" % logfile)64mlog = mavutil.mavlink_connection(logfile)6566Wh_total = 0.067last_t = None68data = []69last_voltR = None7071while True:72msg = mlog.recv_match(type=['BAT'], condition=args.condition)73if msg is None:74break7576if msg.get_type() == 'BAT' and msg.Instance == args.batidx-1 and msg.VoltR > 1:77current = msg.Curr78voltR = msg.VoltR79if last_voltR is not None and voltR > last_voltR:80continue81last_voltR = voltR82power = current*voltR83t = msg.TimeUS*1.0e-68485if last_t is None:86last_t = t87continue8889dt = t - last_t90if dt < 0.5:91# 2Hz data is plenty92continue93last_t = t94Wh_total += (power*dt)/3600.09596data.append((voltR,Wh_total))9798if len(data) == 0:99print("No data found")100sys.exit(1)101102# calculate total pack capacity based on final percentage103Wh_max = data[-1][1]/(args.final_pct*0.01)104105fit_data = []106107for i in range(len(data)):108(voltR,Wh) = data[i]109SOC = 100-100*Wh/Wh_max110fit_data.append((voltR, SOC))111112print("Loaded %u samples" % len(data))113return fit_data114115def ExtractDataCSV(logfile):116'''find battery fit parameters from a CSV file'''117print("Processing CSV %s" % logfile)118lines = open(logfile,'r').readlines()119fit_data = []120for line in lines:121line = line.strip()122if line.startswith("#"):123continue124v = line.split(',')125if len(v) != 2:126continue127if not v[0][0].isnumeric() or not v[1][0].isnumeric():128continue129fit_data.append((float(v[1]),float(v[0])))130return fit_data131132def BattFit(fit_data, num_cells):133134fit_data = [ (v/num_cells,p) for (v,p) in fit_data ]135136c = fit_batt(fit_data)137print("Coefficients C1=%.4f C2=%.4f C3=%.4f" % (c[0], c[1], c[2]))138139if args.no_graph:140return141142fig, axs = pyplot.subplots()143144np_volt = np.array([v for (v,p) in fit_data])145np_pct = np.array([p for (v,p) in fit_data])146axs.invert_xaxis()147axs.plot(np_volt, np_pct, label='SOC')148np_rem = np.zeros(0,dtype=float)149150# pad down to 3.2V to make it easier to visualise for logs that don't go to a low voltage151low_volt = np_volt[-1]152while low_volt > 3.2:153low_volt -= 0.1154np_volt = np.append(np_volt, low_volt)155156for i in range(np_volt.size):157voltR = np_volt[i]158np_rem = np.append(np_rem, SOC_model(voltR, c))159160axs.plot(np_volt, np_rem, label='SOC Fit')161162if args.comparison:163c2 = args.comparison.split(',')164c2 = [ float(x) for x in c2 ]165np_rem2 = np.zeros(0,dtype=float)166for i in range(np_volt.size):167voltR = np_volt[i]168np_rem2 = np.append(np_rem2, SOC_model(voltR, c2))169axs.plot(np_volt, np_rem2, label='SOC Fit2')170171axs.legend(loc='upper left')172axs.set_title('Battery Fit')173174pyplot.show()175176def get_cell_count(data):177if args.num_cells != 0:178return args.num_cells179volts = [ v[0] for v in data ]180volts = sorted(volts)181num_cells = round(volts[-1]/4.2)182print("Max voltags %.1f num_cells %u" % (volts[-1], num_cells))183return num_cells184185if args.log.upper().endswith(".CSV"):186fit_data = ExtractDataCSV(args.log)187else:188fit_data = ExtractDataLog(args.log)189190num_cells = get_cell_count(fit_data)191BattFit(fit_data, num_cells)192193194