mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: Remove redundant state copy
Every backend stored a instance reference, which wasn't used in most locations which is redundant given that the state already tracks the instance for us as well.
This commit is contained in:
parent
3ab3face9b
commit
f919c409bb
|
@ -180,25 +180,25 @@ AP_BattMonitor::init()
|
|||
case BattMonitor_TYPE_ANALOG_VOLTAGE_ONLY:
|
||||
case BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT:
|
||||
state[instance].instance = instance;
|
||||
drivers[instance] = new AP_BattMonitor_Analog(*this, instance, state[instance]);
|
||||
drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance]);
|
||||
_num_instances++;
|
||||
break;
|
||||
case BattMonitor_TYPE_SOLO:
|
||||
state[instance].instance = instance;
|
||||
drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, instance, state[instance],
|
||||
drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance],
|
||||
hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_INTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR));
|
||||
_num_instances++;
|
||||
break;
|
||||
case BattMonitor_TYPE_MAXELL:
|
||||
state[instance].instance = instance;
|
||||
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, instance, state[instance],
|
||||
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance],
|
||||
hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_EXTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR));
|
||||
_num_instances++;
|
||||
break;
|
||||
case BattMonitor_TYPE_BEBOP:
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
||||
state[instance].instance = instance;
|
||||
drivers[instance] = new AP_BattMonitor_Bebop(*this, instance, state[instance]);
|
||||
drivers[instance] = new AP_BattMonitor_Bebop(*this, state[instance]);
|
||||
_num_instances++;
|
||||
#endif
|
||||
break;
|
||||
|
|
|
@ -7,11 +7,11 @@
|
|||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/// Constructor
|
||||
AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state) :
|
||||
AP_BattMonitor_Backend(mon, instance, mon_state)
|
||||
AP_BattMonitor_Analog::AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state) :
|
||||
AP_BattMonitor_Backend(mon, mon_state)
|
||||
{
|
||||
_volt_pin_analog_source = hal.analogin->channel(mon._volt_pin[instance]);
|
||||
_curr_pin_analog_source = hal.analogin->channel(mon._curr_pin[instance]);
|
||||
_volt_pin_analog_source = hal.analogin->channel(mon._volt_pin[_state.instance]);
|
||||
_curr_pin_analog_source = hal.analogin->channel(mon._curr_pin[_state.instance]);
|
||||
|
||||
// always healthy
|
||||
_state.healthy = true;
|
||||
|
|
|
@ -82,7 +82,7 @@ class AP_BattMonitor_Analog : public AP_BattMonitor_Backend
|
|||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_BattMonitor_Analog(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state);
|
||||
AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state);
|
||||
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read();
|
||||
|
|
|
@ -22,10 +22,9 @@
|
|||
base class constructor.
|
||||
This incorporates initialisation as well.
|
||||
*/
|
||||
AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state) :
|
||||
AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state) :
|
||||
_mon(mon),
|
||||
_state(mon_state),
|
||||
_instance(instance)
|
||||
_state(mon_state)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -43,11 +42,11 @@ uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
|
|||
/// set capacity for this instance
|
||||
void AP_BattMonitor_Backend::set_capacity(uint32_t capacity)
|
||||
{
|
||||
_mon._pack_capacity[_instance] = capacity;
|
||||
_mon._pack_capacity[_state.instance] = capacity;
|
||||
}
|
||||
|
||||
/// get capacity for this instance
|
||||
int32_t AP_BattMonitor_Backend::get_capacity() const
|
||||
{
|
||||
return _mon.pack_capacity_mah(_instance);
|
||||
return _mon.pack_capacity_mah(_state.instance);
|
||||
}
|
||||
|
|
|
@ -22,7 +22,7 @@ class AP_BattMonitor_Backend
|
|||
{
|
||||
public:
|
||||
// constructor. This incorporates initialisation as well.
|
||||
AP_BattMonitor_Backend(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state);
|
||||
AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state);
|
||||
|
||||
// we declare a virtual destructor so that BattMonitor driver can
|
||||
// override with a custom destructor if need be
|
||||
|
@ -46,5 +46,4 @@ public:
|
|||
protected:
|
||||
AP_BattMonitor &_mon; // reference to front-end
|
||||
AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)
|
||||
uint8_t _instance; // this instance
|
||||
};
|
||||
|
|
|
@ -22,8 +22,8 @@ class AP_BattMonitor_Bebop :public AP_BattMonitor_Backend
|
|||
{
|
||||
public:
|
||||
// constructor. This incorporates initialisation as well.
|
||||
AP_BattMonitor_Bebop(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state):
|
||||
AP_BattMonitor_Backend(mon, instance, mon_state),
|
||||
AP_BattMonitor_Bebop(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state):
|
||||
AP_BattMonitor_Backend(mon, mon_state),
|
||||
_prev_vbat_raw(0.0f),
|
||||
_prev_vbat(0.0f),
|
||||
_battery_voltage_max(0.0f)
|
||||
|
|
|
@ -16,7 +16,7 @@ class AP_BattMonitor_SMBus : public AP_BattMonitor_Backend
|
|||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_BattMonitor_SMBus(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor_SMBus(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
|
|
|
@ -36,10 +36,10 @@ uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
|
|||
*/
|
||||
|
||||
// Constructor
|
||||
AP_BattMonitor_SMBus_Maxell::AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor_SMBus_Maxell::AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: AP_BattMonitor_SMBus(mon, instance, mon_state, std::move(dev))
|
||||
: AP_BattMonitor_SMBus(mon, mon_state, std::move(dev))
|
||||
{
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Maxell::timer, void));
|
||||
}
|
||||
|
|
|
@ -11,7 +11,7 @@ class AP_BattMonitor_SMBus_Maxell : public AP_BattMonitor_SMBus
|
|||
public:
|
||||
|
||||
// Constructor
|
||||
AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
|
|
|
@ -29,10 +29,10 @@
|
|||
*/
|
||||
|
||||
// Constructor
|
||||
AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||
: AP_BattMonitor_SMBus(mon, instance, mon_state, std::move(dev))
|
||||
: AP_BattMonitor_SMBus(mon, mon_state, std::move(dev))
|
||||
{
|
||||
_pec_supported = true;
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Solo::timer, void));
|
||||
|
|
|
@ -11,7 +11,7 @@ class AP_BattMonitor_SMBus_Solo : public AP_BattMonitor_SMBus
|
|||
public:
|
||||
|
||||
// Constructor
|
||||
AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, uint8_t instance,
|
||||
AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
|
||||
AP_BattMonitor::BattMonitor_State &mon_state,
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||
|
||||
|
|
Loading…
Reference in New Issue