mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: fixed reset_remaining() for INAxxx and LTC2946
these can use the generic reset_remaining() call in the backend
This commit is contained in:
parent
5722cb584d
commit
c8b2622f45
|
@ -18,7 +18,6 @@ public:
|
|||
bool has_cell_voltages() const override { return false; }
|
||||
bool has_temperature() const override { return false; }
|
||||
bool has_current() const override { return true; }
|
||||
bool reset_remaining(float percentage) override { return false; }
|
||||
bool get_cycle_count(uint16_t &cycles) const override { return false; }
|
||||
|
||||
void init(void) override;
|
||||
|
|
|
@ -19,7 +19,6 @@ public:
|
|||
bool has_cell_voltages() const override { return false; }
|
||||
bool has_temperature() const override { return false; }
|
||||
bool has_current() const override { return true; }
|
||||
bool reset_remaining(float percentage) override { return false; }
|
||||
bool get_cycle_count(uint16_t &cycles) const override { return false; }
|
||||
|
||||
void init(void) override;
|
||||
|
|
|
@ -16,7 +16,6 @@ public:
|
|||
bool has_cell_voltages() const override { return false; }
|
||||
bool has_temperature() const override { return false; }
|
||||
bool has_current() const override { return true; }
|
||||
bool reset_remaining(float percentage) override { return false; }
|
||||
bool get_cycle_count(uint16_t &cycles) const override { return false; }
|
||||
|
||||
virtual void init(void) override;
|
||||
|
|
Loading…
Reference in New Issue