Skip to content

Commit

Permalink
AP_BattMonitor: Handle allocating too many analog channels
Browse files Browse the repository at this point in the history
If you over allocate the number of analog channels this results in a
crash. It's easy to trigger this if you have voltage only monitors as we
still eat up a current input channel, regarless of if we use it. There
are only 16 channels at this time on ChibiOS, so if you have 9 voltage
only battery monitors you are out.

This PR improves that situation by only allocating channels when needed,
and in the case where we run out we now set a ConfigError, which on a
flight controller is much more friendly then a instant segfault the
moment we read a battery monitor. NOTE: on AP_Periph this takes the
node off the bus, rather then just sitting in the bootloader. This was
consideted acceptable as the current behaviour was to segfault and then
sit in the bootloader, unless you made new firmware that limited the
number of channels allocated it wasn't possible to recover in this
situation anyways.
  • Loading branch information
WickedShell authored and rmackay9 committed Dec 24, 2024
1 parent 54e3d74 commit 5b96189
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 5 deletions.
14 changes: 12 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_BoardConfig/AP_BoardConfig.h>

#include "AP_BattMonitor_Analog.h"

Expand Down Expand Up @@ -88,7 +89,15 @@ AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon,
_state.var_info = var_info;

_volt_pin_analog_source = hal.analogin->channel(_volt_pin);
_curr_pin_analog_source = hal.analogin->channel(_curr_pin);
if (_volt_pin_analog_source == nullptr) {
AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);
}
if ((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT) {
_curr_pin_analog_source = hal.analogin->channel(_curr_pin);
if (_curr_pin_analog_source == nullptr) {
AP_BoardConfig::config_error("No analog channels for battery %d", mon_state.instance);
}
}

}

Expand Down Expand Up @@ -124,7 +133,8 @@ AP_BattMonitor_Analog::read()
/// return true if battery provides current info
bool AP_BattMonitor_Analog::has_current() const
{
return ((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT);
return (_curr_pin_analog_source != nullptr) &&
((AP_BattMonitor::Type)_params._type.get() == AP_BattMonitor::Type::ANALOG_VOLTAGE_AND_CURRENT);
}

#endif // AP_BATTERY_ANALOG_ENABLED
3 changes: 0 additions & 3 deletions libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,6 @@ AP_BattMonitor_Synthetic_Current::read()
const uint32_t tnow = AP_HAL::micros();
const uint32_t dt_us = tnow - _state.last_time_micros;

// this copes with changing the pin at runtime
_state.healthy &= _curr_pin_analog_source->set_pin(_curr_pin);

// read current
_state.current_amps = ((_state.voltage/_max_voltage)*sq(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)) * 0.0001 * _curr_amp_per_volt) + _curr_amp_offset ;

Expand Down

0 comments on commit 5b96189

Please sign in to comment.