From a76d6ba190466f2e57541fafd8ff0a6f8b2fb9fe Mon Sep 17 00:00:00 2001 From: Lokesh-Ramina Date: Wed, 6 Mar 2024 17:34:35 -0800 Subject: [PATCH] AP_BattMonitor: add option minimum volt option Allows aggregate monitors like Sum and ESC to report the minimum voltage instead of the average voltage. This is useful for systems with multiple isolated batteries where the lowest voltage is the limiting factor. SW-97 --- libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp | 10 +++++++++- libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor_Params.h | 4 +++- libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp | 10 +++++++++- 4 files changed, 22 insertions(+), 4 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp index 713561ecb9..a70c1d4a9b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp @@ -32,6 +32,7 @@ void AP_BattMonitor_ESC::read(void) uint8_t voltage_escs = 0; // number of ESCs with valid voltage uint8_t temperature_escs = 0; // number of ESCs with valid temperature float voltage_sum = 0; + float voltage_min = 0; float current_sum = 0; float temperature_sum = 0; uint32_t highest_ms = 0; @@ -50,6 +51,9 @@ void AP_BattMonitor_ESC::read(void) } if (telem.get_voltage(i, voltage)) { + if (voltage_escs == 0 || voltage_min > voltage) { + voltage_min = voltage; + } voltage_sum += voltage; voltage_escs++; } @@ -69,7 +73,11 @@ void AP_BattMonitor_ESC::read(void) } if (voltage_escs > 0) { - _state.voltage = voltage_sum / voltage_escs; + if (uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Minimum_Voltage)) { + _state.voltage = voltage_min; + } else { + _state.voltage = voltage_sum / voltage_escs; + } _state.healthy = true; } else { _state.voltage = 0; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index de38fd9f4d..6cefbf6bcb 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -143,7 +143,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: OPTIONS // @DisplayName: Battery monitor options // @Description: This sets options to change the behaviour of the battery monitor - // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS + // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS, 7:Aggregate monitor reports minimum voltage instead of average, 8:Aggregate monitor reports maximum current instead of average, 9:Aggregate monitor reports maximum temperature instead of average, 10:Aggregate monitor reports minimum temperature instead of average // @User: Advanced AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0), diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 32ae410223..de2decc68d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -17,7 +17,7 @@ class AP_BattMonitor_Params { BattMonitor_LowVoltageSource_Raw = 0, BattMonitor_LowVoltageSource_SagCompensated = 1 }; - enum class Options : uint8_t { + enum class Options : uint16_t { Ignore_UAVCAN_SoC = (1U<<0), // Ignore UAVCAN State-of-Charge (charge %) supplied value from the device and use the internally calculated one MPPT_Use_Input_Value = (1U<<1), // MPPT reports voltage and current from Input (usually solar panel) instead of the output MPPT_Power_Off_At_Disarm = (1U<<2), // MPPT Disabled when vehicle is disarmed, if HW supports it @@ -25,6 +25,8 @@ class AP_BattMonitor_Params { MPPT_Power_Off_At_Boot = (1U<<4), // MPPT Disabled at startup (aka boot), if HW supports it MPPT_Power_On_At_Boot = (1U<<5), // MPPT Enabled at startup (aka boot), if HW supports it. If Power_Off_at_Boot is also set, the behavior is Power_Off_at_Boot GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS + // AllowSplitAuxInfo = (1U<<7), // allow different node to provide aux info for DroneCAN (Reserved for ArduPilot 4.5+) + Minimum_Voltage = (1U<<8), // aggregate monitors report minimum voltage rather than average }; BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp index 7ce61484f8..fd4ebbda0b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp @@ -45,6 +45,7 @@ void AP_BattMonitor_Sum::read() { float voltage_sum = 0; + float voltage_min = 0; uint8_t voltage_count = 0; float current_sum = 0; uint8_t current_count = 0; @@ -65,6 +66,9 @@ AP_BattMonitor_Sum::read() if (!_mon.healthy(i)) { continue; } + if (voltage_count == 0 || _mon.voltage(i) < voltage_min) { + voltage_min = _mon.voltage(i); + } voltage_sum += _mon.voltage(i); voltage_count++; float current; @@ -77,7 +81,11 @@ AP_BattMonitor_Sum::read() const uint32_t dt_us = tnow_us - _state.last_time_micros; if (voltage_count > 0) { - _state.voltage = voltage_sum / voltage_count; + if (uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Minimum_Voltage)) { + _state.voltage = voltage_min; + } else { + _state.voltage = voltage_sum / voltage_count; + } } if (current_count > 0) { _state.current_amps = current_sum;