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:
Andrew Tridgell 2023-08-03 08:04:50 +10:00
parent 5722cb584d
commit c8b2622f45
3 changed files with 0 additions and 3 deletions

View File

@ -18,7 +18,6 @@ public:
bool has_cell_voltages() const override { return false; } bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; } bool has_temperature() const override { return false; }
bool has_current() const override { return true; } 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; } bool get_cycle_count(uint16_t &cycles) const override { return false; }
void init(void) override; void init(void) override;

View File

@ -19,7 +19,6 @@ public:
bool has_cell_voltages() const override { return false; } bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; } bool has_temperature() const override { return false; }
bool has_current() const override { return true; } 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; } bool get_cycle_count(uint16_t &cycles) const override { return false; }
void init(void) override; void init(void) override;

View File

@ -16,7 +16,6 @@ public:
bool has_cell_voltages() const override { return false; } bool has_cell_voltages() const override { return false; }
bool has_temperature() const override { return false; } bool has_temperature() const override { return false; }
bool has_current() const override { return true; } 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; } bool get_cycle_count(uint16_t &cycles) const override { return false; }
virtual void init(void) override; virtual void init(void) override;