AP_BattMonitor: add and use Battery backend internal-use-only flag

sometimes the information from a backend is very useful for logging, but not via telemetry.

Add an option bit to signify this
This commit is contained in:
Peter Barker 2024-08-07 16:10:07 +10:00 committed by Peter Barker
parent 34549cf0cb
commit 8ee09c299e
3 changed files with 12 additions and 1 deletions

View File

@ -777,6 +777,14 @@ float AP_BattMonitor::gcs_voltage(uint8_t instance) const
return state[instance].voltage;
}
bool AP_BattMonitor::option_is_set(uint8_t instance, AP_BattMonitor_Params::Options option) const
{
if (instance >= _num_instances || drivers[instance] == nullptr) {
return false;
}
return drivers[instance]->option_is_set(option);
}
/// current_amps - returns the instantaneous current draw in amperes
bool AP_BattMonitor::current_amps(float &current, uint8_t instance) const {
if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {

View File

@ -262,6 +262,8 @@ public:
void MPPT_set_powered_state_to_all(const bool power_on);
void MPPT_set_powered_state(const uint8_t instance, const bool power_on);
bool option_is_set(uint8_t instance, AP_BattMonitor_Params::Options option) const;
// cycle count
bool get_cycle_count(uint8_t instance, uint16_t &cycles) const;

View File

@ -17,7 +17,7 @@ public:
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
@ -26,6 +26,7 @@ public:
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
InternalUseOnly = (1U<<8), // for use internally to ArduPilot, not to be (eg.) sent via MAVLink BATTERY_STATUS
};
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }