mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: Handle allocating too many analog channels
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.
This commit is contained in:
parent
cb6907992b
commit
946a25fcaa
|
@ -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"
|
||||
|
||||
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue