From 5decb82b948ce060144cd9eed7e9b4f5984689b2 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 2 Jun 2022 14:33:01 +1000 Subject: [PATCH] Update to RFC with capacity_ fields --- src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp index 8e4a50f528..66666d35ed 100644 --- a/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp +++ b/src/modules/mavlink/streams/BATTERY_STATUS_V2.hpp @@ -71,7 +71,7 @@ private: // TODO: Determine how to better map between battery ID within the firmware and in MAVLink bat_msg.id = battery_status.id - 1; - bat_msg.current_consumed = (battery_status.connected) ? battery_status.discharged_mah : UINT32_MAX; + bat_msg.capacity_consumed = (battery_status.connected) ? battery_status.discharged_mah : UINT32_MAX; bat_msg.current = (battery_status.connected) ? battery_status.current_filtered_a * 1000 : UINT32_MAX; // mA bat_msg.percent_remaining = (battery_status.connected) ? roundf(battery_status.remaining * 100.f) : UINT32_MAX; bat_msg.status_flags = battery_status.status_flags; @@ -79,10 +79,10 @@ private: // get remaining charge in mAH if (battery_status.connected && PX4_ISFINITE(battery_status.remaining_capacity_wh) && (battery_status.voltage_filtered_v > 0.f) ) { - bat_msg.current_remaining = (battery_status.remaining_capacity_wh / battery_status.voltage_filtered_v) * 1000.f; // mAH + bat_msg.capacity_remaining = (battery_status.remaining_capacity_wh / battery_status.voltage_filtered_v) * 1000.f; // mAH } else { - bat_msg.current_remaining = UINT32_MAX; + bat_msg.capacity_remaining = UINT32_MAX; } // check if temperature valid