AP_BattMonitor: support configuring battery #2 in hwdef

This commit is contained in:
Andy Piper 2023-03-08 18:49:09 +00:00 committed by Andrew Tridgell
parent 7a85121daf
commit d565a378b7
3 changed files with 23 additions and 0 deletions

View File

@ -255,11 +255,15 @@ AP_BattMonitor::init()
#ifdef HAL_BATT_MONITOR_DEFAULT #ifdef HAL_BATT_MONITOR_DEFAULT
_params[0]._type.set_default(int8_t(HAL_BATT_MONITOR_DEFAULT)); _params[0]._type.set_default(int8_t(HAL_BATT_MONITOR_DEFAULT));
#endif #endif
#ifdef HAL_BATT2_MONITOR_DEFAULT
_params[1]._type.set_default(int8_t(HAL_BATT2_MONITOR_DEFAULT));
#endif
// create each instance // create each instance
for (uint8_t instance=0; instance<AP_BATT_MONITOR_MAX_INSTANCES; instance++) { for (uint8_t instance=0; instance<AP_BATT_MONITOR_MAX_INSTANCES; instance++) {
// clear out the cell voltages // clear out the cell voltages
memset(&state[instance].cell_voltages, 0xFF, sizeof(cells)); memset(&state[instance].cell_voltages, 0xFF, sizeof(cells));
state[instance].instance = instance;
switch (get_type(instance)) { switch (get_type(instance)) {
case Type::ANALOG_VOLTAGE_ONLY: case Type::ANALOG_VOLTAGE_ONLY:

View File

@ -149,6 +149,7 @@ public:
bool powerOffNotified; // only send powering off notification once bool powerOffNotified; // only send powering off notification once
uint32_t time_remaining; // remaining battery time uint32_t time_remaining; // remaining battery time
bool has_time_remaining; // time_remaining is only valid if this is true bool has_time_remaining; // time_remaining is only valid if this is true
uint8_t instance; // instance number of this backend
const struct AP_Param::GroupInfo *var_info; const struct AP_Param::GroupInfo *var_info;
}; };

View File

@ -67,6 +67,24 @@ AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon,
AP_BattMonitor_Backend(mon, mon_state, params) AP_BattMonitor_Backend(mon, mon_state, params)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
// no other good way of setting these defaults
#if AP_BATT_MONITOR_MAX_INSTANCES > 1
if (mon_state.instance == 1) {
#ifdef HAL_BATT2_VOLT_PIN
_volt_pin.set_default(HAL_BATT2_VOLT_PIN);
#endif
#ifdef HAL_BATT2_CURR_PIN
_curr_pin.set_default(HAL_BATT2_CURR_PIN);
#endif
#ifdef HAL_BATT2_VOLT_SCALE
_volt_multiplier.set_default(HAL_BATT2_VOLT_SCALE);
#endif
#ifdef HAL_BATT2_CURR_SCALE
_curr_amp_per_volt.set_default(HAL_BATT2_VOLT_SCALE);
#endif
}
#endif
_state.var_info = var_info; _state.var_info = var_info;
_volt_pin_analog_source = hal.analogin->channel(_volt_pin); _volt_pin_analog_source = hal.analogin->channel(_volt_pin);