AP_BattMonitor.h 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194
  1. #pragma once
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Param/AP_Param.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <GCS_MAVLink/GCS_MAVLink.h>
  6. #include "AP_BattMonitor_Params.h"
  7. // maximum number of battery monitors
  8. #define AP_BATT_MONITOR_MAX_INSTANCES 9
  9. // first monitor is always the primary monitor
  10. #define AP_BATT_PRIMARY_INSTANCE 0
  11. #define AP_BATT_SERIAL_NUMBER_DEFAULT -1
  12. #define AP_BATT_MONITOR_TIMEOUT 5000
  13. #define AP_BATT_MONITOR_RES_EST_TC_1 0.5f
  14. #define AP_BATT_MONITOR_RES_EST_TC_2 0.1f
  15. // declare backend class
  16. class AP_BattMonitor_Backend;
  17. class AP_BattMonitor_Analog;
  18. class AP_BattMonitor_SMBus;
  19. class AP_BattMonitor_SMBus_Solo;
  20. class AP_BattMonitor_SMBus_Maxell;
  21. class AP_BattMonitor_UAVCAN;
  22. class AP_BattMonitor
  23. {
  24. friend class AP_BattMonitor_Backend;
  25. friend class AP_BattMonitor_Analog;
  26. friend class AP_BattMonitor_SMBus;
  27. friend class AP_BattMonitor_SMBus_Solo;
  28. friend class AP_BattMonitor_SMBus_Maxell;
  29. friend class AP_BattMonitor_UAVCAN;
  30. friend class AP_BattMonitor_Sum;
  31. friend class AP_BattMonitor_FuelFlow;
  32. friend class AP_BattMonitor_FuelLevel_PWM;
  33. public:
  34. // battery failsafes must be defined in levels of severity so that vehicles wont fall backwards
  35. enum BatteryFailsafe {
  36. BatteryFailsafe_None = 0,
  37. BatteryFailsafe_Low,
  38. BatteryFailsafe_Critical
  39. };
  40. FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t);
  41. AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities);
  42. /* Do not allow copies */
  43. AP_BattMonitor(const AP_BattMonitor &other) = delete;
  44. AP_BattMonitor &operator=(const AP_BattMonitor&) = delete;
  45. static AP_BattMonitor *get_singleton() {
  46. return _singleton;
  47. }
  48. struct cells {
  49. uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
  50. };
  51. // The BattMonitor_State structure is filled in by the backend driver
  52. struct BattMonitor_State {
  53. cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec
  54. float voltage; // voltage in volts
  55. float current_amps; // current in amperes
  56. float consumed_mah; // total current draw in milliamp hours since start-up
  57. float consumed_wh; // total energy consumed in Wh since start-up
  58. uint32_t last_time_micros; // time when voltage and current was last read in microseconds
  59. uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum in milliseconds
  60. uint32_t critical_voltage_start_ms; // critical voltage failsafe start timer in milliseconds
  61. float temperature; // battery temperature in degrees Celsius
  62. uint32_t temperature_time; // timestamp of the last received temperature message
  63. float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate in Volt
  64. float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage
  65. BatteryFailsafe failsafe; // stage failsafe the battery is in
  66. bool healthy; // battery monitor is communicating correctly
  67. bool is_powering_off; // true when power button commands power off
  68. bool powerOffNotified; // only send powering off notification once
  69. };
  70. // Return the number of battery monitor instances
  71. uint8_t num_instances(void) const { return _num_instances; }
  72. // detect and initialise any available battery monitors
  73. void init();
  74. /// Read the battery voltage and current for all batteries. Should be called at 10hz
  75. void read();
  76. // healthy - returns true if monitor is functioning
  77. bool healthy(uint8_t instance) const;
  78. bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); }
  79. /// voltage - returns battery voltage in millivolts
  80. float voltage(uint8_t instance) const;
  81. float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }
  82. /// get voltage with sag removed (based on battery current draw and resistance)
  83. /// this will always be greater than or equal to the raw voltage
  84. float voltage_resting_estimate(uint8_t instance) const;
  85. float voltage_resting_estimate() const { return voltage_resting_estimate(AP_BATT_PRIMARY_INSTANCE); }
  86. /// current_amps - returns the instantaneous current draw in amperes
  87. bool current_amps(float &current, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
  88. /// consumed_mah - returns total current drawn since start-up in milliampere.hours
  89. bool consumed_mah(float &mah, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
  90. /// consumed_wh - returns total energy drawn since start-up in watt.hours
  91. bool consumed_wh(float&wh, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
  92. /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
  93. virtual uint8_t capacity_remaining_pct(uint8_t instance) const;
  94. uint8_t capacity_remaining_pct() const { return capacity_remaining_pct(AP_BATT_PRIMARY_INSTANCE); }
  95. /// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
  96. int32_t pack_capacity_mah(uint8_t instance) const;
  97. int32_t pack_capacity_mah() const { return pack_capacity_mah(AP_BATT_PRIMARY_INSTANCE); }
  98. /// returns true if a battery failsafe has ever been triggered
  99. bool has_failsafed(void) const { return _has_triggered_failsafe; };
  100. /// returns the highest failsafe action that has been triggered
  101. int8_t get_highest_failsafe_priority(void) const { return _highest_failsafe_priority; };
  102. /// get_type - returns battery monitor type
  103. enum AP_BattMonitor_Params::BattMonitor_Type get_type() const { return get_type(AP_BATT_PRIMARY_INSTANCE); }
  104. enum AP_BattMonitor_Params::BattMonitor_Type get_type(uint8_t instance) const { return _params[instance].type(); }
  105. /// true when (voltage * current) > watt_max
  106. bool overpower_detected() const;
  107. bool overpower_detected(uint8_t instance) const;
  108. // cell voltages
  109. bool has_cell_voltages() { return has_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }
  110. bool has_cell_voltages(const uint8_t instance) const;
  111. const cells & get_cell_voltages() const { return get_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }
  112. const cells & get_cell_voltages(const uint8_t instance) const;
  113. // temperature
  114. bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); };
  115. bool get_temperature(float &temperature, const uint8_t instance) const;
  116. // get battery resistance estimate in ohms
  117. float get_resistance() const { return get_resistance(AP_BATT_PRIMARY_INSTANCE); }
  118. float get_resistance(uint8_t instance) const { return state[instance].resistance; }
  119. // returns false if we fail arming checks, in which case the buffer will be populated with a failure message
  120. bool arming_checks(size_t buflen, char *buffer) const;
  121. // sends powering off mavlink broadcasts and sets notify flag
  122. void checkPoweringOff(void);
  123. // reset battery remaining percentage
  124. bool reset_remaining(uint16_t battery_mask, float percentage);
  125. static const struct AP_Param::GroupInfo var_info[];
  126. protected:
  127. /// parameters
  128. AP_BattMonitor_Params _params[AP_BATT_MONITOR_MAX_INSTANCES];
  129. private:
  130. static AP_BattMonitor *_singleton;
  131. BattMonitor_State state[AP_BATT_MONITOR_MAX_INSTANCES];
  132. AP_BattMonitor_Backend *drivers[AP_BATT_MONITOR_MAX_INSTANCES];
  133. uint32_t _log_battery_bit;
  134. uint8_t _num_instances; /// number of monitors
  135. void convert_params(void);
  136. /// returns the failsafe state of the battery
  137. BatteryFailsafe check_failsafe(const uint8_t instance);
  138. void check_failsafes(void); // checks all batteries failsafes
  139. battery_failsafe_handler_fn_t _battery_failsafe_handler_fn;
  140. const int8_t *_failsafe_priorities; // array of failsafe priorities, sorted highest to lowest priority, -1 indicates no more entries
  141. int8_t _highest_failsafe_priority; // highest selected failsafe action level (used to restrict what actions we move into)
  142. bool _has_triggered_failsafe; // true after a battery failsafe has been triggered for the first time
  143. };
  144. namespace AP {
  145. AP_BattMonitor &battery();
  146. };