mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BattMonitor: Require all backends to provide init
This commit is contained in:
parent
3402d07651
commit
0cee2f2896
@ -101,6 +101,8 @@ public:
|
||||
/// returns true if battery monitor provides current info
|
||||
bool has_current() const override;
|
||||
|
||||
void init(void) override {}
|
||||
|
||||
protected:
|
||||
|
||||
AP_HAL::AnalogSource *_volt_pin_analog_source;
|
||||
|
@ -29,7 +29,7 @@ public:
|
||||
virtual ~AP_BattMonitor_Backend(void) {}
|
||||
|
||||
// initialise
|
||||
virtual void init() {}
|
||||
virtual void init() = 0;
|
||||
|
||||
// read the latest battery voltage
|
||||
virtual void read() = 0;
|
||||
|
@ -17,6 +17,10 @@ AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon,
|
||||
_mon._pack_capacity[_state.instance] = 0;
|
||||
}
|
||||
|
||||
void AP_BattMonitor_SMBus::init(void) {
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus::timer, void));
|
||||
}
|
||||
|
||||
/// read the battery_voltage and current, should be called at 10hz
|
||||
void AP_BattMonitor_SMBus::read(void)
|
||||
{
|
||||
|
@ -28,6 +28,8 @@ public:
|
||||
// all smart batteries are expected to provide current
|
||||
bool has_current() const override { return true; }
|
||||
|
||||
void init(void) override;
|
||||
|
||||
protected:
|
||||
|
||||
void read(void) override;
|
||||
@ -65,6 +67,8 @@ protected:
|
||||
|
||||
bool _has_cell_voltages; // smbus backends flag this as true once they have recieved a valid cell voltage report
|
||||
|
||||
virtual void timer(void) = 0; // timer function to read from the battery
|
||||
|
||||
};
|
||||
|
||||
// include specific implementations
|
||||
|
@ -40,9 +40,7 @@ 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, mon_state, std::move(dev))
|
||||
{
|
||||
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Maxell::timer, void));
|
||||
}
|
||||
{}
|
||||
|
||||
void AP_BattMonitor_SMBus_Maxell::timer()
|
||||
{
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
void timer(void);
|
||||
void timer(void) override;
|
||||
|
||||
// check if PEC supported with the version value in SpecificationInfo() function
|
||||
// returns true once PEC is confirmed as working or not working
|
||||
|
@ -33,7 +33,6 @@ AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
|
||||
: 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));
|
||||
}
|
||||
|
||||
void AP_BattMonitor_SMBus_Solo::timer()
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
void timer(void);
|
||||
void timer(void) override;
|
||||
|
||||
// read_block - returns number of characters read if successful, zero if unsuccessful
|
||||
uint8_t read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero) const;
|
||||
|
Loading…
Reference in New Issue
Block a user