mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
BattMon_Backend: add init and set_capacity methods
This commit is contained in:
parent
11576a0f1e
commit
c6440a48b3
@ -152,6 +152,11 @@ AP_BattMonitor::init()
|
||||
#endif
|
||||
_num_instances++;
|
||||
}
|
||||
|
||||
// call init function for each backend
|
||||
if (drivers[instance] != NULL) {
|
||||
drivers[instance]->init();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -25,7 +25,8 @@
|
||||
*/
|
||||
AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state) :
|
||||
_mon(mon),
|
||||
_state(mon_state)
|
||||
_state(mon_state),
|
||||
_instance(instance)
|
||||
{
|
||||
}
|
||||
|
||||
@ -34,3 +35,9 @@ uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
|
||||
{
|
||||
return (100.0f * (_mon._pack_capacity[_state.instance] - _state.current_total_mah) / _mon._pack_capacity[_state.instance]);
|
||||
}
|
||||
|
||||
/// set capacity for this instance
|
||||
void AP_BattMonitor_Backend::set_capacity(uint32_t capacity)
|
||||
{
|
||||
_mon._pack_capacity[_instance] = capacity;
|
||||
}
|
||||
|
@ -31,14 +31,21 @@ public:
|
||||
// override with a custom destructor if need be
|
||||
virtual ~AP_BattMonitor_Backend(void) {}
|
||||
|
||||
// initialise
|
||||
virtual void init() {}
|
||||
|
||||
// read the latest battery voltage
|
||||
virtual void read() = 0;
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t capacity_remaining_pct() const;
|
||||
|
||||
/// set capacity for this instance
|
||||
void set_capacity(uint32_t capacity);
|
||||
|
||||
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
|
||||
};
|
||||
#endif // __AP_BATTMONITOR_BACKEND_H__
|
||||
|
Loading…
Reference in New Issue
Block a user