Skip to content

Commit

Permalink
add parsing for voltage, fill more of the structure
Browse files Browse the repository at this point in the history
  • Loading branch information
hendjoshsr71 committed Mar 22, 2024
1 parent 247fc6d commit bceb26a
Showing 1 changed file with 93 additions and 52 deletions.
145 changes: 93 additions & 52 deletions libraries/AP_Scripting/drivers/BattMon_EMUS_G1_CAN.lua
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,13 @@
Protocol Version: 2.0.13
Protocol Last Revision Date: October 15, 2021
Autopilot Parameters
CAN_D1_PROTOCOL 10 (Scripting Driver 1)
CAN_P1_DRIVER 1 (First driver)
BATT_MONITOR (Scripting)
BATT_EMUS_INDEX (must match battery monitor attached to scripting)
--]]

-- Check Script uses a miniumum firmware version
Expand All @@ -16,6 +23,38 @@ assert(VERSION >= SCRIPT_AP_VERSION, string.format('%s Requires: %s:%.1f. Found

local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

-- Script defines


-- Global Parameters
local now_s = get_time_sec()


-- Broadcast rate

-- pg 5
-- Most of the CAN messages that contain various information can be periodically broadcasted by EMUS BMS Control Unit using the display
-- messages period. This period is configurable for active and idle states.

local EMUS_EXTENDED_BASE = 0x19B50000

local EMUS_FRM_PARAMETERS = uint32_t(0x000)
local EMUS_FRM_DIAGNOSTIC_CODES = uint32_t(0x007)
local EMUS_FRM_VOLTAGE = uint32_t(0x001)
-- local EMUS_FRM_CELL_MODULE_TEMPERATURE = uint32_t(0x002)
-- local EMUS_FRM_CELL_TEMPERATURE_OVERALL = uint32_t(0x008)
local EMUS_FRM_STATE_OF_CHARGE = uint32_t(0x0500) -- Current pg 29, can be periodically broadcasted


-- System Functions
local EMUS_FRM_CONTACTOR_CONTROL = uint32_t(0x0401)



-- local ESC1_CAN_ADDR_OFFSET = bind_add_param(ESC_PARAM_TABLE, '1_CAN_OFFSET', 1, 0)

-- Register Parameters

local PARAM_TABLE_KEY = 46
local PARAM_TABLE_PREFIX = "BATT_EMUS_"

Expand All @@ -30,6 +69,11 @@ function get_uint16(frame, ofs)
return frame:data(ofs) + (frame:data(ofs + 1) << 8)
end

-- [{DATA0 (2nd Byte)}, {DATA1 (LSB)}, {DATA2 (MSB)}, {DATA3 (3rd Byte)}]
function get_uint32_central(frame, ofs)
return uint32_t(frame:data(ofs + 1) + (frame:data(ofs)<<8) + (frame:data(ofs+3)<<16) + (frame:data(ofs+4)<<32))
end

-- Setup EFI Parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 15), 'could not add param table')

Expand Down Expand Up @@ -95,54 +139,6 @@ local assembly = {}
assembly.num_frames = 0
assembly.frames = {}

--[[
xmodem CRC implementation thanks to https://github.com/cloudwu/skynet
under MIT license
--]]
local XMODEMCRC16Lookup = {
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
}

local function crc_ANX(bytes)
-- ANX CRC uses xmodem with a seed of 0xa635
local crc = 0xa635
for i=1,#bytes do
local b = string.byte(bytes,i,i)
crc = ((crc<<8) & 0xffff) ~ XMODEMCRC16Lookup[(((crc>>8)~b) & 0xff) + 1]
end
return crc
end

local frame_count = 0

Expand All @@ -158,10 +154,17 @@ end


local function parse_volt_frame(payload)
if #payload < 12 then
if #payload < 8 then
-- invalid length
return
end

min_cell_volt = frame:data(0) * 0.01 + 2.0 -- Minimum Cell Voltage: encoded as 0.01V offset by 2.0V
max_cell_volt = frame:data(1) * 0.01 + 2.0 -- Maximum Cell Voltage: encoded as 0.01V offset by 2.0V
avg_cell_volt = frame:data(2) * 0.01 + 2.0 -- Average Cell Voltage: encoded as 0.01V offset by 2.0V
total_volt = get_uint32_central(frame, 3) * 0.01 -- Encoded in 0.01V


local total_volt, current, rem_cap, temperature, _ = string.unpack("<HhHhH", string.sub(payload, 1, 10))
total_volt = total_volt * 0.01
-- it is a discharge, so use minus current
Expand All @@ -181,7 +184,7 @@ local function parse_volt_frame(payload)

local state = BattMonitorScript_State()
state:healthy(true)
state:voltage(total_volt)
state:voltage(total_volt))
state:cell_count(num_cells)
state:capacity_remaining_pct(math.floor(rem_cap))
for i = 1, num_cells do
Expand Down Expand Up @@ -232,6 +235,9 @@ local function read_can()
-- only want extended frames
break
end



local id = frame:id_signed()
-- local sender_id = id&0x7
local last_pkt_id = (id>>3) & 1
Expand All @@ -255,11 +261,46 @@ local function read_can()
end
end


local battery1 = battery_control(driver1)

function update()
now_s = get_time_sec()

local battery_state = BattMonitorScript_State()

--- THIS MAY BE A USELESS STEP SINCE BATTERY BACKEND IS DIFFERENT THAN EFI
if not battery_state then
battery_state = BattMonitorScript_State()
if not battery_state then
return
end
end

battery1.update_telemetry()
battery1.update_charge_state()
battery1.update_balance_state()
battery1.update_telem_out()
battery1.update_logging()

read_can()
return update,10

end

-- wrapper around update(). This calls update() and if update faults
-- then an error is displayed, but the script is not stopped
function protected_wrapper()
local success, err = pcall(update)
if not success then
gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err)
-- when we fault we run the update function again after 1s, slowing it
-- down a bit so we don't flood the console with errors
return protected_wrapper, 1000
end
return protected_wrapper, 100 -- TO DO: add param for update speed 10-25 Hz should do ( 1000/ EFI_SP_UPDATE_HZ:get()
end

gcs:send_text(MAV_SEVERITY.INFO, "BATT_EMUS: Started")

return update()
-- start running update loop
return protected_wrapper()

0 comments on commit bceb26a

Please sign in to comment.