Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_BattMonitor: add option minimum volt option #222

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 1 addition & 9 deletions libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ 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;
Expand All @@ -82,9 +81,6 @@ 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++;
}
Expand All @@ -104,11 +100,7 @@ void AP_BattMonitor_ESC::read(void)
}

if (voltage_escs > 0) {
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.voltage = voltage_sum / voltage_escs;
_state.healthy = true;
} else {
_state.voltage = 0;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,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, 7:Allow DroneCAN InfoAux to be from a different CAN node, 8:Aggregate monitor reports minimum voltage instead of average
// @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:Allow DroneCAN InfoAux to be from a different CAN node, 9:Sum monitor measures minimum voltage instead of average
// @User: Advanced
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
#endif // HAL_BUILD_AP_PERIPH
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@ class AP_BattMonitor_Params {
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
Minimum_Voltage = (1U<<8), // aggregate monitors report minimum voltage rather than average
InternalUseOnly = (1U<<8), // for use internally to ArduPilot, not to be (eg.) sent via MAVLink BATTERY_STATUS
Minimum_Voltage = (1U<<9), // sum monitor measures minimum voltage rather than average
};

BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); }
Expand Down
27 changes: 20 additions & 7 deletions libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ AP_BattMonitor_Sum::read()
float current_sum = 0;
uint8_t current_count = 0;

float consumed_mah_sum = 0;
float consumed_wh_sum = 0;

for (uint8_t i=0; i<_mon.num_instances(); i++) {
if (i == _instance) {
// never include self
Expand All @@ -71,33 +74,43 @@ AP_BattMonitor_Sum::read()
if (!_mon.healthy(i)) {
continue;
}
if (voltage_count == 0 || _mon.voltage(i) < voltage_min) {
voltage_min = _mon.voltage(i);
const float voltage = _mon.voltage(i);
if (voltage_count == 0 || voltage < voltage_min) {
voltage_min = voltage;
}
voltage_sum += _mon.voltage(i);
voltage_sum += voltage;
voltage_count++;
float current;
if (_mon.current_amps(current, i)) {
current_sum += current;
current_count++;
}

float consumed_mah;
if (_mon.consumed_mah(consumed_mah, i)) {
consumed_mah_sum += consumed_mah;
}

float consumed_wh;
if (_mon.consumed_wh(consumed_wh, i)) {
consumed_wh_sum += consumed_wh;
}
}
const uint32_t tnow_us = AP_HAL::micros();
const uint32_t dt_us = tnow_us - _state.last_time_micros;

if (voltage_count > 0) {
if (uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Minimum_Voltage)) {
if (option_is_set(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;
_state.consumed_mah = consumed_mah_sum;
_state.consumed_wh = consumed_wh_sum;
}

update_consumed(_state, dt_us);

_has_current = (current_count > 0);
_state.healthy = (voltage_count > 0);

Expand Down
Loading