Tattu 3.0 Battery 18S is not dronecan compatible, how to decode CAN Messages?

Hello Team,

Have Tattu 3.0 18S batteries which as per their official site is dronecan compatible but as bad luck has it found out to be otherwise.

Tried negotiating with the supplier. they sent a list of firmwares, procedure-to-flash and a can-to-uart device and charged 100$ but bad luck struck again for worse and got the BMS bricked.

As a last ditch approach trying to have the Proprietary messages of tattu batteries to Dronecan compatible message format. In order to do that have used STM32 Bluepill as a converter/relayer of CAN messages received on TJA1050 CAN transceiver which is in turn connected to CAN-H/CAN-L Lines of the battery. Costing under 3 $ for the setup. Video of the setup here

Got help from @dakejahl to refer a checkin PX4 about decoding Tattu Battery 12S messages.

Have attached the log file here and a snapshot of what was so far decoded by matching/comparing the information got over bluetooth connection to battery.

Need further help in decoding all battery voltage which is bit confusing as not able to grasp start and end of the messages.

Arduino Sketch if required will be attached.

I’m happy to look through this a bit - have worked with decoding different makes of smart battery CAN before.

Could you attach the currently decoded .txt file? Would be useful for highlighting and annotation.

Could you also clarify what further information you’re looking to get from the data stream? Is it individual cell voltages? Or something else?

My goodness. Glad that someone is happy decoding/reverse engineering :smiley:

Here is my summary of decoding Highlighted in yellow.
log of battery with serial number 17 with current.txt (361.8 KB)
.

Not able to identify the head and tail of a full-blown CAN message. Also it seems the battery-cell voltage for 18 Cells seems to be scattered across many 8-byte sub-message and the 8-byte messages are non-contiguous(inter-leaved with 2-byte messages).

Here is my rough-decoding of 8-byte sub-message
Channel:1 Extended ID:1109216 DLC: 8 buf: 0x1A 0x74 0xFF 0x17 0x0 0x37 0x0 0x21

Arduino Sketch for STM32 bluepill to conduit CAN messages received from TJA1050 transceiver to the laptop is attached here.

#include "stm32f1xx_hal_can.h"
#include <STM32_CAN.h>

/*
This example reads all data from CAN bus, prints it to serial,
and continuously blinks an LED independently of CAN messages.
*/

//STM32_CAN Can( CAN1, DEF );  //Use PA11/12 pins for CAN1.
STM32_CAN Can( CAN1, ALT );  //Use PB8/9 pins for CAN1.

static CAN_message_t CAN_RX_msg;

// LED pin (Blue Pill onboard LED)
#define LED_PIN PC13

// Timing variables for non-blocking LED
unsigned long previousMillis = 0;
const unsigned long interval = 5000; // 5 seconds
bool ledState = false;

void setup() {
  Serial.begin(9600);
  Can.begin();
  Can.setBaudRate(1000000);  //1000KBPS

  pinMode(LED_PIN, OUTPUT);
  digitalWrite(LED_PIN, LOW);  //LED OFF initially
}

void loop() {
  unsigned long currentMillis = millis();

  // Handle LED blinking
  if (currentMillis - previousMillis >= interval) {
    previousMillis = currentMillis;
    ledState = !ledState;            // Toggle LED state
    //Serial.println("Blinking LED:");

    digitalWrite(LED_PIN, ledState ? HIGH : LOW);
  }

  // Check CAN messages
  if (Can.read(CAN_RX_msg)) {
    // 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");
    }
  }
}

Okay great thanks for sharing!

So this is all a work in progress, but where I’m at so far:

  • Messages on ID 0x01E0959 just seem to be heartbeats or something, I’m ignoring them from now as it’s a static 2 byte payload. Maybe one of these bytes is just a status bitmask or something.
  • Messages on ID 0x1109216 seem to be the real data as you’ve pointed out. It’s one of those annoying implementations that uses a single ID for a range of different frame formats.

0x1109216:

As far as I can tell, the final byte in the payload indicates the format of the rest of the payload data.

For example,

if D7 == 0x21:
D0:D1 = V_batt * 100, 
D2:D3 = I_batt * 100, 
D4:D5 = SOC

The list of different tails that I’ve identified so far is below:
0x02 - V_cell
0x04 - V_cell
0x06 - V_cell
0x08 - Quite unsure about this one. First byte seems to be the only one that varies
0x0A - Maybe something like serial number or production date? Infrequent and static payload
0x21 - V_batt, I_batt, SOC
0x23 - V_cell
0x25 - V_cell
0x27 - V_cell
0x80 - Unsure but transmitted frequently. Likely more telemetry, maybe remaining capacity, temperature, this sort of stuff?

Now this part is quite speculative, but I’ve laid out the V_cell messages below in a way that I think makes sense. The 6 messages share the 18 cell voltages (V_cell * 1000), with a few of them being split across a couple of CAN frames (because the useable payload is 7 bytes and each V_cell is 2 bytes)

Note that the tail bytes are increasing (0x2, 0x23, 0x4, …).
I think this makes more sense when you look at the ‘tail byte’ convention for DroneCAN

And if we compare this to the binary versions of the tail byte:


You can see that the least significant five bits are ‘counting up’, and the ‘toggle’ bit is alternating between each message. This is what led me to believe this is the order we should expect the messages to be processed. In all there are 18 individual cell voltages spread across these 6 messages.

Hopefully this helps you somehow! Sorry I couldn’t quite get the other messages decoded yet but I’ve run out of time for today. I think writing some code to parse the individual cell voltages based on the tail byte would be easy enough with your setup.

1 Like

Wow, CAN-bus payload format really helped to bring some rationality to the message clutter. I concur with your decoding but have following observation/doubts.

[quote=“RHagg, post:4, topic:140181”]
And if we compare this to the binary versions of the tail byte:

Start-of-transfer bit set is seen many a times - 0x80 for instance.
but not able to find End-of-transfer message bit being set. Does it mean if the next start-of-transfer bit message is seen the previous message(held in buffer) should be marked as terminated and be processed?

i.e.
0x4XXX, 0x5XXX 0x6XXX 0x7xXX are not seen yet in the dump at the end of a payload which should essentially indicate end of a message.

One more observation is that the increasing order 0xXXX2, 0xXXX3 0xXXX4 … is not always seen till 0xXXX8. Does it mean only changed fields are given along with some always fixed static fields? What does toggle bit indicate? how to interpret it?

Temperature was around 23*C as per Bluetooth App which was connected to battery at the time of log collection. Will try to map it to

0x1A 0x0 [0x0 0x17](may be temp?) 0x0 0x37 0x0 0x21

Thanks a Ton :smiley:

The structure isn’t necessarily the same as the DroneCAN tail byte. I just used the DroneCAN structure for illustrative purposes. If Tattu have implemented their own format, it’s possible they don’t have a ‘start of transfer’ and ‘end of transfer’ bit - maybe those concepts are communicated elsewhere. Notice how Tattu are increasing the ‘Transfer ID’ field for every single CAN frame in that sequence. The normal DroneCAN format is to increase the transfer ID only once per multi-frame transfer.

I don’t think I understand your observation here, sorry.

The toggle bit is just a mechanism that is alternated between high and low for each individual frame in a multi-frame transfer. It means that if you’re transferring a set of data that spreads across 5 CAN frames, the toggle bit will be as follows:
frame 1: toggle bit = 0
frame 2: toggle bit = 1
frame 3: toggle bit = 0
frame 4: toggle bit = 1
frame 5: toggle bit = 0

I’m fairly sure that in the 0x21 messages the 0x00 0x17 that you’ve highlighted here is current, since it comes out as a signed int16. It also maps well to the value you showed in the screenshot of -2.1A.

I’ve also just realised that the 0x0A ended frame is likely carrying the ‘PACK barcode’. Your first screenshot includes ‘H230831007200017’
If we convert the 0x0A frame to ASCII:

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.