AP_BattMonitor: avoid casting DroneCAN backend to incorrect type

- split get_type into allocated_type and configured_type
 - check allocated type rather than configured type when looking at backends

Prevents overwrite of random memory when backends are changed at runtime.
This commit is contained in:
Peter Barker 2024-06-05 00:58:27 +10:00 committed by Andrew Tridgell
parent 364452ffc8
commit 029e0b15b3
3 changed files with 33 additions and 11 deletions

View File

@ -480,7 +480,8 @@ AP_BattMonitor::init()
memset(&state[instance].cell_voltages, 0xFF, sizeof(cells));
state[instance].instance = instance;
switch (get_type(instance)) {
const auto allocation_type = configured_type(instance);
switch (allocation_type) {
#if AP_BATTERY_ANALOG_ENABLED
case Type::ANALOG_VOLTAGE_ONLY:
case Type::ANALOG_VOLTAGE_AND_CURRENT:
@ -607,7 +608,9 @@ AP_BattMonitor::init()
default:
break;
}
if (drivers[instance] != nullptr) {
state[instance].type = allocation_type;
}
// if the backend has some local parameters then make those available in the tree
if (drivers[instance] && state[instance].var_info) {
backend_var_info[instance] = state[instance].var_info;
@ -699,7 +702,16 @@ void AP_BattMonitor::read()
#endif
for (uint8_t i=0; i<_num_instances; i++) {
if (drivers[i] != nullptr && get_type(i) != Type::NONE) {
if (drivers[i] == nullptr) {
continue;
}
if (allocated_type(i) != configured_type(i)) {
continue;
}
// allow run-time disabling; this is technically redundant
if (configured_type(i) == Type::NONE) {
continue;
}
drivers[i]->read();
drivers[i]->update_resistance_estimate();
@ -714,7 +726,6 @@ void AP_BattMonitor::read()
drivers[i]->Log_Write_BCL(i, time_us);
}
#endif
}
}
check_failsafes();
@ -1126,7 +1137,14 @@ void AP_BattMonitor::MPPT_set_powered_state(const uint8_t instance, const bool p
bool AP_BattMonitor::healthy() const
{
for (uint8_t i=0; i< _num_instances; i++) {
if (get_type(i) != Type::NONE && !healthy(i)) {
if (allocated_type(i) != configured_type(i)) {
return false;
}
// allow run-time disabling; this is technically redundant
if (configured_type(i) == Type::NONE) {
continue;
}
if (!healthy(i)) {
return false;
}
}

View File

@ -160,6 +160,7 @@ public:
uint8_t state_of_health_pct; // state of health (SOH) in percent
bool has_state_of_health_pct; // state_of_health_pct is only valid if this is true
uint8_t instance; // instance number of this backend
Type type; // allocated instance type
const struct AP_Param::GroupInfo *var_info;
};
@ -219,11 +220,14 @@ public:
/// returns the highest failsafe action that has been triggered
int8_t get_highest_failsafe_priority(void) const { return _highest_failsafe_priority; };
/// get_type - returns battery monitor type
enum Type get_type() const { return get_type(AP_BATT_PRIMARY_INSTANCE); }
enum Type get_type(uint8_t instance) const {
/// configured_type - returns battery monitor type as configured in parameters
enum Type configured_type(uint8_t instance) const {
return (Type)_params[instance]._type.get();
}
/// allocated_type - returns battery monitor type as allocated
enum Type allocated_type(uint8_t instance) const {
return state[instance].type;
}
/// get_serial_number - returns battery serial number
int32_t get_serial_number() const { return get_serial_number(AP_BATT_PRIMARY_INSTANCE); }

View File

@ -79,7 +79,7 @@ AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneC
const auto &batt = AP::battery();
for (uint8_t i = 0; i < batt._num_instances; i++) {
if (batt.drivers[i] == nullptr ||
batt.get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) {
batt.allocated_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) {
continue;
}
AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)batt.drivers[i];
@ -90,7 +90,7 @@ AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneC
// find empty uavcan driver
for (uint8_t i = 0; i < batt._num_instances; i++) {
if (batt.drivers[i] != nullptr &&
batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
match_battery_id(i, battery_id)) {
AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i];
@ -241,7 +241,7 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap
for (uint8_t i = 0; i < batt._num_instances; i++) {
const auto *drv = batt.drivers[i];
if (drv != nullptr &&
batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
batt.allocated_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo &&
drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) &&
batt.get_serial_number(i) == int32_t(msg.battery_id)) {
driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i];