Went ahead with your suggestion.
With your valuable inputs and inputs from discord which asked me to refer this file now in position to decode critical piece of information required to be reported to FC. Voltage, Current being of paramount importance.
Still seeing some inconsistencies with individual cell voltage decoding. Not able to identify temperature and also error bit flags
Here is a rough snapshot of what has been decoded and re-directed to serial console for debugging.
Now my queries are more focused on battery status to be reported over mavlink. the DDL for battery status at max supports only 14 cells so can’t report 18 cells. Limitation
Also how to calculate current_consumed and energy_consumed?
Is it
current_consumed is average_current_flow as reported by battery times duration(in sec)
energy_consumed is average_battery_voltage(over a period of time) times average_current(as reported by battery) over the same period of time? are units hJ and Wh one and the same?
Should these calculations be done in STM32 board?
Arduino Sketch here
#include "stm32f1xx_hal.h"
#include "stm32f1xx_hal_can.h"
#include <STM32_CAN.h>
#include <MAVLink.h>
STM32_CAN Can(CAN1, ALT); // or ALT if using PB8/PB9
#define LED_PIN PC13
#define TARGET_ID 0x1109216 //FIXME:
#define CAN_BAUD 1000000 // 1000 Kbps
#define MAV_BAUD 57600 // FIXME: very less but was working
#define CELL_INDEX_1 0
#define CELL_INDEX_2 1
#define CELL_INDEX_3 2
#define CELL_INDEX_4 3
#define CELL_INDEX_5 4
#define CELL_INDEX_6 5
#define CELL_INDEX_7 6
#define CELL_INDEX_8 7
#define CELL_INDEX_9 8
#define CELL_INDEX_10 9
#define CELL_INDEX_11 10
#define CELL_INDEX_12 11
#define CELL_INDEX_13 12
#define CELL_INDEX_14 13
#define CELL_INDEX_15 14
#define CELL_INDEX_16 15
#define CELL_INDEX_17 16
#define CELL_INDEX_18 17
HardwareSerial &mavSerial = Serial1; // UART to ArduPilot. PA9 is TX1, PA10 is RX1 and GND.
// ======================= BATTERY STRUCT =======================
struct __attribute__((packed)) Tattu18SBatteryMessage {
int16_t manufacturer;
uint16_t sku;
uint16_t voltage;
int16_t current;
uint16_t remaining_percent;
uint16_t cycle_life;
int16_t health_status;
uint16_t remaining_capacity_mah;
int16_t temperature;
uint16_t status_of_charge;
uint16_t cell_voltage[18];
uint16_t standard_capacity;
uint32_t error_info;
char serial_number[9];
};
Tattu18SBatteryMessage batteryData = {0};
Tattu18SBatteryMessage tempFrame = {0};
CAN_message_t CAN_RX_msg;
bool frameCollecting = false;
uint32_t lastHeaderTime = 0;
uint8_t cellIndex = 0;
// flags for sub-payload tracking
bool got_0x80=false, got_0x21=false, got_0x02=false, got_0x0A=false;
bool got_0x23 = false, got_0x4 = false, got_0x25 = false, got_0x6 = false, got_0x27 = false;
unsigned long previousMillis = 0;
const long interval = 5000;
bool ledState = false;
unsigned long lastMavSend = 0;
// ======================= SETUP =======================
void setup() {
unsigned long currentMillis = millis();
pinMode(LED_PIN, OUTPUT);
// --- Initialize Serial ports ---
Serial.begin(57600); //FIXME:
delay(200);
Serial.println();
Serial.println("=== STM32 CAN → MAVLink Battery Bridge ===");
mavSerial.begin(MAV_BAUD);
Serial.println("MAVLink serial ready...");
// --- Initialize CAN bus ---
Serial.print("Initializing CAN at ");
Serial.print(CAN_BAUD);
Serial.println(" bps...");
Can.begin();
Can.setBaudRate(CAN_BAUD); //1000KBPS
delay(100);
// Optional: apply filter (accept all frames)
//Can.setFilter(0, 0);
// --- Basic CAN status check ---
#ifdef STM32_CAN_VERSION
Serial.print("CAN driver version: ");
Serial.println(STM32_CAN_VERSION);
#endif
// Optional quick test: wait for activity
unsigned long start = millis();
bool seenFrame = false;
while (millis() - start < 2000) {
CAN_message_t msg;
if (Can.read(msg)) {
Serial.println("CAN frame detected — bus active.");
seenFrame = true;
break;
}
}
if (!seenFrame) {
Serial.println("No CAN traffic detected (check wiring, transceiver, or termination).");
}
Serial.println("STM32 CAN→MAVLink Battery Bridge Ready.");
Serial.println("==========================================");
digitalWrite(LED_PIN, LOW);
}
// ======================= UTILITY =======================
void copyIfReceived() {
if (got_0x80) {
batteryData.manufacturer = tempFrame.manufacturer;
batteryData.sku = tempFrame.sku;
}
if (got_0x21) {
batteryData.voltage = tempFrame.voltage;
batteryData.current = tempFrame.current;
batteryData.remaining_percent = tempFrame.remaining_percent;
batteryData.cycle_life = (tempFrame.cycle_life != 0) ? tempFrame.cycle_life : batteryData.cycle_life;
}
if (got_0x02) {
batteryData.cycle_life = tempFrame.cycle_life;
batteryData.health_status = tempFrame.health_status;
batteryData.remaining_capacity_mah = tempFrame.remaining_capacity_mah;
batteryData.cell_voltage[CELL_INDEX_1] = tempFrame.cell_voltage[CELL_INDEX_1];
}
if (got_0x23)
{
batteryData.cell_voltage[CELL_INDEX_2] = tempFrame.cell_voltage[CELL_INDEX_2];
batteryData.cell_voltage[CELL_INDEX_3] = tempFrame.cell_voltage[CELL_INDEX_3];
batteryData.cell_voltage[CELL_INDEX_4] = tempFrame.cell_voltage[CELL_INDEX_4];
}
if (got_0x4)
{
if (got_0x23)
{
batteryData.cell_voltage[CELL_INDEX_5] = tempFrame.cell_voltage[CELL_INDEX_5];
}
batteryData.cell_voltage[CELL_INDEX_6] = tempFrame.cell_voltage[CELL_INDEX_6];
batteryData.cell_voltage[CELL_INDEX_7] = tempFrame.cell_voltage[CELL_INDEX_7];
batteryData.cell_voltage[CELL_INDEX_8] = tempFrame.cell_voltage[CELL_INDEX_8];
}
if (got_0x25)
{
batteryData.cell_voltage[CELL_INDEX_9] = tempFrame.cell_voltage[CELL_INDEX_9];
batteryData.cell_voltage[CELL_INDEX_10] = tempFrame.cell_voltage[CELL_INDEX_10];
batteryData.cell_voltage[CELL_INDEX_11] = tempFrame.cell_voltage[CELL_INDEX_11];
}
if (got_0x6)
{
if (got_0x25)
{
batteryData.cell_voltage[CELL_INDEX_12] = tempFrame.cell_voltage[CELL_INDEX_12];
}
batteryData.cell_voltage[CELL_INDEX_13] = tempFrame.cell_voltage[CELL_INDEX_13];
batteryData.cell_voltage[CELL_INDEX_14] = tempFrame.cell_voltage[CELL_INDEX_14];
batteryData.cell_voltage[CELL_INDEX_15] = tempFrame.cell_voltage[CELL_INDEX_15];
}
if (got_0x27)
{
batteryData.cell_voltage[CELL_INDEX_16] = tempFrame.cell_voltage[CELL_INDEX_16];
batteryData.cell_voltage[CELL_INDEX_17] = tempFrame.cell_voltage[CELL_INDEX_17];
batteryData.cell_voltage[CELL_INDEX_18] = tempFrame.cell_voltage[CELL_INDEX_18];
}
if (got_0x0A) {
strncpy(batteryData.serial_number, tempFrame.serial_number, 8);
batteryData.serial_number[8] = '\0';
}
}
void printBatteryData() {
Serial.println("=== Battery Data ===");
Serial.print("Voltage: "); Serial.println(batteryData.voltage/100.0f);
Serial.print("Current: "); Serial.println(batteryData.current/100.0f);
Serial.print("Remaining %: "); Serial.println(batteryData.remaining_percent);
Serial.print("Cycle Life: "); Serial.println(batteryData.cycle_life);
Serial.print("Health: "); Serial.println(batteryData.health_status);
Serial.print("Capacity (mAh): "); Serial.println(batteryData.remaining_capacity_mah*100);
if (batteryData.serial_number[0] != '\0')
{
Serial.print("Serial: "); Serial.println(batteryData.serial_number);
}
else
{
Serial.println("Serial: UNKNOWN");
}
Serial.print("Cells: ");
for (int i = 0; i < 18; i++) {
Serial.print(batteryData.cell_voltage[i]);
Serial.print(" ");
}
Serial.println("\n====================");
}
// ======================= CAN PARSER =======================
void processCANFrame(CAN_message_t &msg) {
//if (msg.id != TARGET_ID) return; //FIXME:
if (msg.len != 8) return;
uint8_t tail = msg.buf[msg.len - 1];
// ---- Start Frame ----
if (tail == 0x80) {
// If we are already collecting, then previous frame ended
if (frameCollecting) {
frameCollecting = false;
got_0x0A = false;
// finalize old payload
copyIfReceived();
printBatteryData();
sendMavlinkBattery();
}
frameCollecting = true;
cellIndex = 0;
got_0x0A = false;
memset(&tempFrame, 0, sizeof(tempFrame));
got_0x80 = got_0x21 = got_0x02 = got_0x0A = false;
got_0x23 = got_0x4 = got_0x25 = got_0x6 = got_0x27 = false;
lastHeaderTime = millis();
tempFrame.manufacturer = (msg.buf[1] << 8) | msg.buf[2];
tempFrame.sku = (msg.buf[3] << 8) | msg.buf[4];
got_0x80 = true;
return;
}
if (!frameCollecting) return;
if (tail == 0x21) {
tempFrame.voltage = (msg.buf[0] << 8) | msg.buf[1];
tempFrame.current = (msg.buf[2] << 8) | msg.buf[3];
tempFrame.remaining_percent = (msg.buf[4] << 8) | msg.buf[5];
tempFrame.cycle_life = (msg.buf[6] << 8);
got_0x21 = true;
return;
}
if (tail == 0x02) {
tempFrame.cycle_life |= msg.buf[0];
tempFrame.health_status = (msg.buf[1] << 8) | msg.buf[2];
tempFrame.remaining_capacity_mah = (msg.buf[3] << 8) | msg.buf[4];
tempFrame.cell_voltage[CELL_INDEX_1] = (msg.buf[5]<<8) + msg.buf[6];
got_0x02 = true;
return;
}
if (tail == 0x23)
{
tempFrame.cell_voltage[CELL_INDEX_2] = (msg.buf[0] << 8) | msg.buf[1];
tempFrame.cell_voltage[CELL_INDEX_3] = (msg.buf[2] << 8) | msg.buf[3];
tempFrame.cell_voltage[CELL_INDEX_4] = (msg.buf[4] << 8) | msg.buf[5];
tempFrame.cell_voltage[CELL_INDEX_5] = (msg.buf[6] << 8);
got_0x23 = true;
return;
}
if (tail == 0x4)
{
tempFrame.cell_voltage[CELL_INDEX_5] |= (msg.buf[0]);
tempFrame.cell_voltage[CELL_INDEX_6] = (msg.buf[1] << 8) | msg.buf[2];
tempFrame.cell_voltage[CELL_INDEX_7] = (msg.buf[3] << 8) | msg.buf[4];
tempFrame.cell_voltage[CELL_INDEX_8] = (msg.buf[5] << 8) | msg.buf[6];
got_0x4 = true;
return;
}
if (tail == 0x25)
{
tempFrame.cell_voltage[CELL_INDEX_9] = (msg.buf[0] << 8) | msg.buf[1];
tempFrame.cell_voltage[CELL_INDEX_10] = (msg.buf[2] << 8) | msg.buf[3];
tempFrame.cell_voltage[CELL_INDEX_11] = (msg.buf[4] << 8) | msg.buf[5];
tempFrame.cell_voltage[CELL_INDEX_12] = (msg.buf[6] << 8);
got_0x25 = true;
return;
}
if (tail == 0x6)
{
tempFrame.cell_voltage[CELL_INDEX_12] |= (msg.buf[0]);
tempFrame.cell_voltage[CELL_INDEX_13] = (msg.buf[1] << 8) | msg.buf[2];
tempFrame.cell_voltage[CELL_INDEX_14] = (msg.buf[3] << 8) | msg.buf[4];
tempFrame.cell_voltage[CELL_INDEX_15] = (msg.buf[5] << 8) | msg.buf[6];
got_0x6 = true;
return;
}
if (tail == 0x27)
{
tempFrame.cell_voltage[CELL_INDEX_16] = (msg.buf[0] << 8) | msg.buf[1];
tempFrame.cell_voltage[CELL_INDEX_17] = (msg.buf[2] << 8) | msg.buf[3];
tempFrame.cell_voltage[CELL_INDEX_18] = (msg.buf[4] << 8) | msg.buf[5];
got_0x27 = true;
return;
}
if (tail == 0x0A) {
memcpy(tempFrame.serial_number, &msg.buf[2], 5);
tempFrame.serial_number[5] = '\0';
got_0x0A = true;
return;
}
// Optional timeout protection. Sendding Mavlink data at 5Hz rate
if (frameCollecting && millis() - lastHeaderTime > 200) {
// If no new 0x80 seen within timeout, finalize anyway
frameCollecting = false;
copyIfReceived();
printBatteryData();
sendMavlinkBattery();
}
}
// ======================= MAVLINK TX =======================
void sendMavlinkBattery() {
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// -------------------------------
// Convert local battery data
// -------------------------------
// NOTE: Your batteryData struct must have:
// - voltage (in decivolts or millivolts)
// - current (in deciamps or centiamps)
// - remaining_percent (0–100)
// - cell_voltage[18]
// Adjust scaling if needed.
// -------------------------------
// Convert voltage/current to MAVLink expected units
float voltage_total = batteryData.voltage / 100.0f; // Example: from decivolts → volts
float current_total = batteryData.current / 100.0f; // Example: from deciamps → amps
// MAVLink expects centi-amps (cA)
int16_t current_battery = (int16_t)(current_total * 100.0f);
// -------------------------------
// Prepare per-cell voltage arrays
// -------------------------------
uint16_t voltages[10];
uint16_t voltages_ext[4];
// First 10 cells
for (int i = 0; i < 10; i++) {
if (i < 18 && batteryData.cell_voltage[i] > 0)
voltages[i] = batteryData.cell_voltage[i]; // already in mV
else
voltages[i] = UINT16_MAX; // unused cell
}
// Extended cells 11–14 (for 12S–14S or up to 18S if partial data)
for (int i = 0; i < 4; i++) {
int cellIndex = i + 10;
if (cellIndex < 18 && batteryData.cell_voltage[cellIndex] > 0)
voltages_ext[i] = batteryData.cell_voltage[cellIndex];
else
voltages_ext[i] = 0; // per spec: 0 = not supported
}
// -------------------------------
// Call MAVLink pack function
// -------------------------------
uint16_t len = mavlink_msg_battery_status_pack(
1, // system_id
200, // component_id
&msg, // output message
0, // battery ID
MAV_BATTERY_FUNCTION_ALL, // function
MAV_BATTERY_TYPE_LIPO, // chemistry
INT16_MAX, // temperature unknown
voltages, // voltages[10]
current_battery, // [cA]
-1, // current_consumed (unknown)
-1, // energy_consumed (unknown)
(int8_t)batteryData.remaining_percent, // [%]
0, // time_remaining (unknown)
MAV_BATTERY_CHARGE_STATE_OK, // charge_state
voltages_ext, // voltages_ext[4]
MAV_BATTERY_MODE_UNKNOWN, // mode
0 // fault_bitmask
);
// Encode into sendable buffer
len = mavlink_msg_to_send_buffer(buf, &msg);
// Transmit over MAVLink serial
mavSerial.write(buf, len);
lastMavSend = millis();
// Debug output for
Serial.print("→ MAVLink BATTERY_STATUS sent | Cells: ");
Serial.print(18);
Serial.print(" | Voltage: ");
Serial.print(voltage_total, 2);
Serial.print("V | Current: ");
Serial.print(current_total, 2);
Serial.print("A | SOC: ");
Serial.print(batteryData.remaining_percent);
Serial.println("%");
}
// ======================= LOOP =======================
void loop() {
unsigned long currentMillis = millis();
if (currentMillis - previousMillis >= interval) {
previousMillis = currentMillis;
ledState = !ledState;
digitalWrite(LED_PIN, ledState ? HIGH : LOW);
}
memset(&batteryData, 0, sizeof(batteryData));
if (Can.read(CAN_RX_msg)) {
processCANFrame(CAN_RX_msg);
#if 0
// Print CAN message
Serial.print("Channel:");
Serial.print(CAN_RX_msg.bus);
if (CAN_RX_msg.flags.extended == false) {
Serial.print(" Standard ID:");
} else {
Serial.print(" Extended ID:");
}
Serial.print(CAN_RX_msg.id, HEX);
Serial.print(" DLC: ");
Serial.print(CAN_RX_msg.len);
if (CAN_RX_msg.flags.remote == false) {
Serial.print(" buf: ");
for (int i = 0; i < CAN_RX_msg.len; i++) {
Serial.print("0x");
Serial.print(CAN_RX_msg.buf[i], HEX);
if (i != (CAN_RX_msg.len - 1)) Serial.print(" ");
}
Serial.println();
} else {
Serial.println(" Data: REMOTE REQUEST FRAME");
}
#endif
}
// Optional: send MAVLink every 1 second even if no new data
if (millis() - lastMavSend > 1000) {
sendMavlinkBattery();
}
}
I am grateful for your, dagar (Daniel Agar) · GitHub, dakejahl (Jacob Dahl) · GitHub help.