mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: added option to send resting voltage to GCS
This commit is contained in:
parent
f1ec657c41
commit
9c067f360f
|
@ -438,6 +438,19 @@ float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const
|
|||
}
|
||||
}
|
||||
|
||||
/// voltage - returns battery voltage in volts for GCS, may be resting voltage if option enabled
|
||||
float AP_BattMonitor::gcs_voltage(uint8_t instance) const
|
||||
{
|
||||
if ((_params[instance]._options.get() & uint32_t(AP_BattMonitor_Params::Options::GCS_Resting_Voltage)) != 0) {
|
||||
return voltage_resting_estimate(instance);
|
||||
}
|
||||
if (instance < _num_instances) {
|
||||
return state[instance].voltage;
|
||||
} else {
|
||||
return 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
/// current_amps - returns the instantaneous current draw in amperes
|
||||
bool AP_BattMonitor::current_amps(float ¤t, uint8_t instance) const {
|
||||
if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) {
|
||||
|
|
|
@ -162,6 +162,10 @@ public:
|
|||
float voltage(uint8_t instance) const;
|
||||
float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
// voltage for a GCS, may be resistance compensated
|
||||
float gcs_voltage(uint8_t instance) const;
|
||||
float gcs_voltage(void) const { return gcs_voltage(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// get voltage with sag removed (based on battery current draw and resistance)
|
||||
/// this will always be greater than or equal to the raw voltage
|
||||
float voltage_resting_estimate(uint8_t instance) const;
|
||||
|
|
|
@ -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
|
||||
// @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
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
|
||||
|
||||
|
|
|
@ -24,6 +24,7 @@ public:
|
|||
MPPT_Power_On_At_Arm = (1U<<3), // MPPT Enabled when vehicle is armed, if HW supports it
|
||||
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
|
||||
};
|
||||
|
||||
BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
|
||||
|
|
Loading…
Reference in New Issue