AP_MSP:Tools: use BATTERY_STATE.voltage_cv for cell voltage calculation to replicate actual DJI Goggles behaviour

This becomes apparent when pack voltage is above DJI's hard limit of 25.5v
with this fix the cell voltage is correct even for 12s packs just like on real hardware
This commit is contained in:
yaapu 2021-01-11 18:36:21 +01:00 committed by Andrew Tridgell
parent b84baf06d3
commit 89802ed6fc
2 changed files with 19 additions and 20 deletions

View File

@ -170,7 +170,7 @@ def display_cell_voltage():
(X,Y) = XY
px = X * FontWidth
py = Y * FontHeight
display_text(msp.OSD_AVG_CELL_VOLTAGE, "%.02fv" % (0 if msp.get('BATTERY_STATE.cellCount')==0 else msp.get('BATTERY_STATE.voltage')/msp.get('BATTERY_STATE.cellCount')*0.1), 12)
display_text(msp.OSD_AVG_CELL_VOLTAGE, "%.02fv" % (0 if msp.get('BATTERY_STATE.cellCount')==0 else msp.get('BATTERY_STATE.voltage_cv')/msp.get('BATTERY_STATE.cellCount')*0.01), 12)
draw_batt_icon(px,py-6)
def display_all():
@ -274,4 +274,3 @@ try:
run()
except KeyboardInterrupt:
pass

View File

@ -218,7 +218,7 @@ class PyMSP:
MSP_ATTITUDE: MSPItem('ATTITUDE', "hhh", "roll,pitch,yaw"),
MSP_ALTITUDE: MSPItem('ALTITUDE', "ih", "alt,vspeed"),
MSP_RC_TUNING: MSPItem('RC_TUNING', "BBBBBBB", "RC_Rate,RC_Expo,RollPitchRate,YawRate,DynThrPID,ThrottleMID,ThrottleExpo"),
MSP_BATTERY_STATE: MSPItem('BATTERY_STATE', "BHBHh", "cellCount,capacity,voltage,mah,current"),
MSP_BATTERY_STATE: MSPItem('BATTERY_STATE', "BHBHhBh", "cellCount,capacity,voltage,mah,current,state,voltage_cv"),
MSP_RTC: MSPItem('RTC', "HBBBBBH", "year,mon,mday,hour,min,sec,millis"),
MSP_OSD_CONFIG: MSPItem("OSD_CONFIG",
["BBBBHBBH",