AP_BattMonitor_Backend.h 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_BattMonitor.h"
  17. class AP_BattMonitor_Backend
  18. {
  19. public:
  20. // constructor. This incorporates initialisation as well.
  21. AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params);
  22. // we declare a virtual destructor so that BattMonitor driver can
  23. // override with a custom destructor if need be
  24. virtual ~AP_BattMonitor_Backend(void) {}
  25. // initialise
  26. virtual void init() = 0;
  27. // read the latest battery voltage
  28. virtual void read() = 0;
  29. /// returns true if battery monitor instance provides consumed energy info
  30. virtual bool has_consumed_energy() const { return false; }
  31. /// returns true if battery monitor instance provides current info
  32. virtual bool has_current() const = 0;
  33. // returns true if battery monitor provides individual cell voltages
  34. virtual bool has_cell_voltages() const { return false; }
  35. /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
  36. uint8_t capacity_remaining_pct() const;
  37. /// get voltage with sag removed (based on battery current draw and resistance)
  38. /// this will always be greater than or equal to the raw voltage
  39. float voltage_resting_estimate() const;
  40. // update battery resistance estimate and voltage_resting_estimate
  41. void update_resistance_estimate();
  42. // updates failsafe timers, and returns what failsafes are active
  43. AP_BattMonitor::BatteryFailsafe update_failsafes(void);
  44. // returns false if we fail arming checks, in which case the buffer will be populated with a failure message
  45. bool arming_checks(char * buffer, size_t buflen) const;
  46. // reset remaining percentage to given value
  47. virtual bool reset_remaining(float percentage);
  48. protected:
  49. AP_BattMonitor &_mon; // reference to front-end
  50. AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)
  51. AP_BattMonitor_Params &_params; // reference to this instances parameters (held in the front-end)
  52. // checks what failsafes could be triggered
  53. void check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const;
  54. private:
  55. // resistance estimate
  56. uint32_t _resistance_timer_ms; // system time of last resistance estimate update
  57. float _voltage_filt; // filtered voltage
  58. float _current_max_amps; // maximum current since start-up
  59. float _current_filt_amps; // filtered current
  60. float _resistance_voltage_ref; // voltage used for maximum resistance calculation
  61. float _resistance_current_ref; // current used for maximum resistance calculation
  62. };