From 6bc9b7c4351f81497dac47ba12e1f248aa6ee40c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 10 Mar 2023 18:04:05 +1100 Subject: [PATCH] AP_BattMonitor: rename fuel_remain_pct to fuel_remain_scale --- libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp index efff4d4bd6..f9ee6d2bbf 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp @@ -43,7 +43,7 @@ bool AP_BattMonitor_Generator_FuelLevel::has_consumed_energy(void) const } // Use consumed_mAh in BattMonitor to display fuel remaining - return generator->has_fuel_remaining_pct(); + return generator->has_fuel_remaining(); } void AP_BattMonitor_Generator_FuelLevel::init() @@ -78,7 +78,7 @@ void AP_BattMonitor_Generator_FuelLevel::read() _state.voltage = 1.0f; // This is a bodge to display tank level as a percentage on GCS. Users should set _params.pack_capacity == 100 to get a clear percentage in GCS - _state.consumed_mah = (1 - generator->get_fuel_remaining_pct()) * _params._pack_capacity.get(); + _state.consumed_mah = (1 - generator->get_fuel_remaining()) * _params._pack_capacity.get(); // If we got this far then must be healthy _state.healthy = true;