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

@ -49,23 +49,23 @@ last_read_s = time.time()
msp = pymsp.PyMSP()
pygame.init()
# define the RGB value for white,
# green, blue colour .
white = (255, 255, 255)
green = (0, 255, 0)
blue = (0, 0, 128)
# define the RGB value for white,
# green, blue colour .
white = (255, 255, 255)
green = (0, 255, 0)
blue = (0, 0, 128)
black = (0, 0 ,0)
# window size
FontWidth = 25
FontHeight = 25
WindowWidth = 27 * FontWidth
WindowHeight = 16 * FontHeight
# create the display surface object
# of specific dimension..e(X, Y).
# create the display surface object
# of specific dimension..e(X, Y).
display_surface = pygame.display.set_mode((WindowWidth,WindowHeight))
# set the pygame window name
@ -107,7 +107,7 @@ def draw_batt_icon(x, y):
pygame.draw.rect(display_surface, (255, 255, 255), (x, y+3, 8, 14))
def draw_triangle(x, y, r, angle):
a = angle -90
a = angle -90
ra = math.radians(a)
x1 = int(x + r * math.cos(ra))
y1 = int(y + r * math.sin(ra))
@ -170,12 +170,12 @@ 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():
'''display all items'''
'''
_osd_item_settings[OSD_RSSI_VALUE] = &osd->screen[0].rssi;
_osd_item_settings[OSD_MAIN_BATT_VOLTAGE] = &osd->screen[0].bat_volt;
@ -264,7 +264,7 @@ def run():
display_all()
pygame.display.update()
time.sleep(0.01)
for event in pygame.event.get():
if event.type == pygame.QUIT:
pygame.quit()
@ -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",
@ -241,7 +241,7 @@ class PyMSP:
def __init__(self):
self.msp_name = {
'name':None
'name':None
}
self.msp_osd_config = {}
@ -293,7 +293,7 @@ class PyMSP:
value, = struct.unpack("<I", self.inBuf[self.p:self.p+4])
self.p += 4
return value
def read16(self):
'''signed 16 bit number'''
value, = struct.unpack("<h", self.inBuf[self.p:self.p+2])
@ -305,7 +305,7 @@ class PyMSP:
value, = struct.unpack("<H", self.inBuf[self.p:self.p+2])
self.p += 2
return value
def read8(self):
'''unsigned 8 bit number'''
value, = struct.unpack("<B", self.inBuf[self.p:self.p+1])
@ -396,7 +396,7 @@ class PyMSP:
self.c_state = self.HEADER_ERR
else:
self.c_state = self.IDLE
elif self.c_state == self.HEADER_ARROW or self.c_state == self.HEADER_ERR:
self.err_rcvd = (self.c_state == self.HEADER_ERR)
#print (struct.unpack('<B',c)[0])