Issue with Battery Status in PX4

Hi everyone, I’m having an issue with sending battery status data from a ROS node to QGroundControl using MAVLink.

What I’m trying to do:

  • I have a ROS node that reads battery data (voltage, current, percentage, capacity) and sends it to QGC using the BATTERY_STATUS MAVLink message at 0.5Hz.
  • The goal is to display the battery status correctly in QGC.

The problem:

  • In QGC, the battery percentage is displayed correctly, however, I still get a Vehicle Error: Failsafe activated due to low battery level, triggering RTL in 5 seconds. when trying to takeoff.
  • When clicking on the displayed battery, I notice that the time_remaining field always shows 00H:00M:01S, regardless of whether I: calculate the time remaining, set it to a fixed value or to invalid (0). Also it says battery 255, is this the ID? If so, it should be 1.

Relevant code (ROS node):

    def send_battery_status(self, drone_id, voltage, current, percentage, capacity):           
          # Create MAVLink battery status message
          msg = mavlink.MAVLink_battery_status_message(
              id=int(drone_id),  # set to 1 for drone1
              battery_function=1,
              type=1,
              temperature=32767,
              voltages=[int(voltage)] + [65535] * 9, 
              current_battery=int(current / 10),  # Convert current from mA to cA
              current_consumed=-1,  
              energy_consumed=-1, 
              battery_remaining=int(percentage)
          )
          raw_msg = msg.pack(mavlink.MAVLink(self.mavlink_system_id, self.mavlink_component_id))
          self.sock.sendto(raw_msg, (self.mavlink_target_ip, self.mavlink_target_port))

Additional details:

  • PX4 Firmware: v1.14.2
  • QGC Version: v4.4.3
  • Battery Monitoring Source (in QGC): Disabled
  • When checking the drone1/mavros/battery ROS topic and on the PX4 terminal using listener battery_status command the data seems to be correct but the error still triggers.
INFO  [commander] Ready for takeoff!
pxh> listener battery_status

TOPIC: battery_status
 battery_status
    timestamp: 1736438079006182 (0.003000 seconds ago)
    voltage_v: 22.76800
    voltage_filtered_v: 22.76800
    current_a: -1.17000
    current_filtered_a: -1.17000
    current_average_a: 0.00000
    discharged_mah: -1.00000
    remaining: 0.64000
    scale: 0.00000
    time_remaining_s: 0.00000
    temperature: 32767.00000
    voltage_cell_v: [22.76800, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000]
    max_cell_voltage_delta: 0.00000
    custom_faults: 0
    average_power: 0.00000
    available_energy: 0.00000
    full_charge_capacity_wh: 0.00000
    remaining_capacity_wh: 0.00000
    design_capacity: 0.00000
    nominal_voltage: 0.00000
    capacity: 0
    cycle_count: 0
    average_time_to_empty: 0
    serial_number: 0
    manufacture_date: 0
    state_of_health: 0
    max_error: 0
    interface_error: 0
    faults: 0
    average_time_to_full: 0
    over_discharge_count: 0
    connected: True
    cell_count: 1
    source: 0
    priority: 0
    id: 0
    is_powering_off: False
    is_required: False
    warning: 0
    mode: 0

pxh> commander takeoff
pxh> INFO  [commander] Armed by internal command	
INFO  [navigator] Using minimum takeoff altitude: 2.50 m	
INFO  [tone_alarm] arming warning
WARN  [failsafe] Failsafe activated, entering Hold for 5 seconds	
INFO  [tone_alarm] battery warning (fast)
INFO  [commander] Takeoff detected	
WARN  [failsafe] Failsafe activated	
INFO  [navigator] RTL HOME activated	
INFO  [navigator] RTL: landing at home position.	
INFO  [navigator] RTL: climb to 0 m (1 m above destination)	
INFO  [navigator] RTL: return at 0 m (1 m above destination)	
INFO  [navigator] RTL: descend to 0 m (1 m above destination)	
INFO  [navigator] RTL: land at destination	
INFO  [commander] Landing detected	
INFO  [commander] Disarmed by landing	
INFO  [tone_alarm] notify neutral
INFO  [logger] closed logfile, bytes written: 8381639

Hi @manudelu , could you share a flight log that contains the failsafe event? Hard to troubleshoot without, maybe there was a misconfiguration, maybe a PX4 bug.

Hi @sfuhrer , I’m not sure if this is the correct log, but I’ve downloaded the .ulg file and uploaded it on Flight Review. You can access it here.

So I had a look at the log, somehow the failsafe “battery_low_remaining_time” gets triggered on arming. You can find the code for it here. The condition that triggers it is battery_low_remaining_time < rtl_time_estimate, where in your case battery_low_remaining_time is all the time 0.
To why it is 0: Here I’m no longer certain, the only paths I see form looking at the code is:

  • you get the battery info through the UavcanBatteryBridge, and as the remaining_capacity_wh is 0 in your case the time_remaining in this line is also 0. This line contains an error, as the time_remaining field should be NAN if the battery capacity is not known.

I don’t understand yet how you receive the battery information at all on the PX4 side, given you have BAT1_SOURCE set to -1.

What I would recommend you is either to update to a new PX4 version, where you can disable this failsafe, or check if changing the line in the uavcan bridge fixes it.