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_BatteryMonitor: add missing failsafe with no action #27358

Merged
merged 1 commit into from
Jul 1, 2024
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
12 changes: 12 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -701,6 +701,7 @@ void AP_BattMonitor::read()
}
#endif

const uint32_t now_ms = AP_HAL::millis();
for (uint8_t i=0; i<_num_instances; i++) {
if (drivers[i] == nullptr) {
continue;
Expand All @@ -719,6 +720,11 @@ void AP_BattMonitor::read()
drivers[i]->update_esc_telem_outbound();
#endif

// Update last heathy timestamp
if (state[i].healthy) {
state[i].last_healthy_ms = now_ms;
}

#if HAL_LOGGING_ENABLED
if (logger != nullptr && logger->should_log(_log_battery_bit)) {
const uint64_t time_us = AP_HAL::micros64();
Expand Down Expand Up @@ -852,6 +858,11 @@ void AP_BattMonitor::check_failsafes(void)
switch (type) {
case Failsafe::None:
continue; // should not have been called in this case
case Failsafe::Unhealthy:
// Report only for unhealthy, could add action param in the future
action = 0;
type_str = "missing, last:";
break;
case Failsafe::Low:
action = _params[i]._failsafe_low_action;
type_str = "low";
Expand Down Expand Up @@ -1079,6 +1090,7 @@ MAV_BATTERY_CHARGE_STATE AP_BattMonitor::get_mavlink_charge_state(const uint8_t
switch (state[instance].failsafe) {

case Failsafe::None:
case Failsafe::Unhealthy:
if (get_mavlink_fault_bitmask(instance) != 0 || !healthy()) {
return MAV_BATTERY_CHARGE_STATE_UNHEALTHY;
}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ class AP_BattMonitor
// battery failsafes must be defined in levels of severity so that vehicles wont fall backwards
enum class Failsafe : uint8_t {
None = 0,
Unhealthy,
IamPete1 marked this conversation as resolved.
Show resolved Hide resolved
Low,
Critical
};
Expand Down Expand Up @@ -153,6 +154,7 @@ class AP_BattMonitor
float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage
Failsafe failsafe; // stage failsafe the battery is in
bool healthy; // battery monitor is communicating correctly
uint32_t last_healthy_ms; // Time when monitor was last healthy
bool is_powering_off; // true when power button commands power off
bool powerOffNotified; // only send powering off notification once
uint32_t time_remaining; // remaining battery time
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,11 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Backend::update_failsafes(void)
return AP_BattMonitor::Failsafe::Low;
}

// 5 second health timeout
if ((now - _state.last_healthy_ms) > 5000) {
return AP_BattMonitor::Failsafe::Unhealthy;
}

// if we've gotten this far then battery is ok
return AP_BattMonitor::Failsafe::None;
}
Expand Down
Loading