AP_BattMonitor_Backend.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247
  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. #include <AP_Common/AP_Common.h>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include "AP_BattMonitor.h"
  16. #include "AP_BattMonitor_Backend.h"
  17. /*
  18. base class constructor.
  19. This incorporates initialisation as well.
  20. */
  21. AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state,
  22. AP_BattMonitor_Params &params) :
  23. _mon(mon),
  24. _state(mon_state),
  25. _params(params)
  26. {
  27. }
  28. /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
  29. uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
  30. {
  31. float mah_remaining = _params._pack_capacity - _state.consumed_mah;
  32. if ( _params._pack_capacity > 10 ) { // a very very small battery
  33. return MIN(MAX((100 * (mah_remaining) / _params._pack_capacity), 0), UINT8_MAX);
  34. } else {
  35. return 0;
  36. }
  37. }
  38. // update battery resistance estimate
  39. // faster rates of change of the current and voltage readings cause faster updates to the resistance estimate
  40. // the battery resistance is calculated by comparing the latest current and voltage readings to a low-pass filtered current and voltage
  41. // high current steps are integrated into the resistance estimate by varying the time constant of the resistance filter
  42. void AP_BattMonitor_Backend::update_resistance_estimate()
  43. {
  44. // return immediately if no current
  45. if (!has_current() || !is_positive(_state.current_amps)) {
  46. return;
  47. }
  48. // update maximum current seen since startup and protect against divide by zero
  49. _current_max_amps = MAX(_current_max_amps, _state.current_amps);
  50. float current_delta = _state.current_amps - _current_filt_amps;
  51. if (is_zero(current_delta)) {
  52. return;
  53. }
  54. // update reference voltage and current
  55. if (_state.voltage > _resistance_voltage_ref) {
  56. _resistance_voltage_ref = _state.voltage;
  57. _resistance_current_ref = _state.current_amps;
  58. }
  59. // calculate time since last update
  60. uint32_t now = AP_HAL::millis();
  61. float loop_interval = (now - _resistance_timer_ms) / 1000.0f;
  62. _resistance_timer_ms = now;
  63. // estimate short-term resistance
  64. float filt_alpha = constrain_float(loop_interval/(loop_interval + AP_BATT_MONITOR_RES_EST_TC_1), 0.0f, 0.5f);
  65. float resistance_alpha = MIN(1, AP_BATT_MONITOR_RES_EST_TC_2*fabsf((_state.current_amps-_current_filt_amps)/_current_max_amps));
  66. float resistance_estimate = -(_state.voltage-_voltage_filt)/current_delta;
  67. if (is_positive(resistance_estimate)) {
  68. _state.resistance = _state.resistance*(1-resistance_alpha) + resistance_estimate*resistance_alpha;
  69. }
  70. // calculate maximum resistance
  71. if ((_resistance_voltage_ref > _state.voltage) && (_state.current_amps > _resistance_current_ref)) {
  72. float resistance_max = (_resistance_voltage_ref - _state.voltage) / (_state.current_amps - _resistance_current_ref);
  73. _state.resistance = MIN(_state.resistance, resistance_max);
  74. }
  75. // update the filtered voltage and currents
  76. _voltage_filt = _voltage_filt*(1-filt_alpha) + _state.voltage*filt_alpha;
  77. _current_filt_amps = _current_filt_amps*(1-filt_alpha) + _state.current_amps*filt_alpha;
  78. // update estimated voltage without sag
  79. _state.voltage_resting_estimate = _state.voltage + _state.current_amps * _state.resistance;
  80. }
  81. float AP_BattMonitor_Backend::voltage_resting_estimate() const
  82. {
  83. // resting voltage should always be greater than or equal to the raw voltage
  84. return MAX(_state.voltage, _state.voltage_resting_estimate);
  85. }
  86. AP_BattMonitor::BatteryFailsafe AP_BattMonitor_Backend::update_failsafes(void)
  87. {
  88. const uint32_t now = AP_HAL::millis();
  89. bool low_voltage, low_capacity, critical_voltage, critical_capacity;
  90. check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);
  91. if (critical_voltage) {
  92. // this is the first time our voltage has dropped below minimum so start timer
  93. if (_state.critical_voltage_start_ms == 0) {
  94. _state.critical_voltage_start_ms = now;
  95. } else if (_params._low_voltage_timeout > 0 &&
  96. now - _state.critical_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {
  97. return AP_BattMonitor::BatteryFailsafe_Critical;
  98. }
  99. } else {
  100. // acceptable voltage so reset timer
  101. _state.critical_voltage_start_ms = 0;
  102. }
  103. if (critical_capacity) {
  104. return AP_BattMonitor::BatteryFailsafe_Critical;
  105. }
  106. if (low_voltage) {
  107. // this is the first time our voltage has dropped below minimum so start timer
  108. if (_state.low_voltage_start_ms == 0) {
  109. _state.low_voltage_start_ms = now;
  110. } else if (_params._low_voltage_timeout > 0 &&
  111. now - _state.low_voltage_start_ms > uint32_t(_params._low_voltage_timeout)*1000U) {
  112. return AP_BattMonitor::BatteryFailsafe_Low;
  113. }
  114. } else {
  115. // acceptable voltage so reset timer
  116. _state.low_voltage_start_ms = 0;
  117. }
  118. if (low_capacity) {
  119. return AP_BattMonitor::BatteryFailsafe_Low;
  120. }
  121. // if we've gotten this far then battery is ok
  122. return AP_BattMonitor::BatteryFailsafe_None;
  123. }
  124. static bool update_check(size_t buflen, char *buffer, bool failed, const char *message)
  125. {
  126. if (failed) {
  127. strncpy(buffer, message, buflen);
  128. return false;
  129. }
  130. return true;
  131. }
  132. bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const
  133. {
  134. bool low_voltage, low_capacity, critical_voltage, critical_capacity;
  135. check_failsafe_types(low_voltage, low_capacity, critical_voltage, critical_capacity);
  136. bool below_arming_voltage = is_positive(_params._arming_minimum_voltage) &&
  137. (_state.voltage < _params._arming_minimum_voltage);
  138. bool below_arming_capacity = (_params._arming_minimum_capacity > 0) &&
  139. ((_params._pack_capacity - _state.consumed_mah) < _params._arming_minimum_capacity);
  140. bool fs_capacity_inversion = is_positive(_params._critical_capacity) &&
  141. is_positive(_params._low_capacity) &&
  142. (_params._low_capacity < _params._critical_capacity);
  143. bool fs_voltage_inversion = is_positive(_params._critical_voltage) &&
  144. is_positive(_params._low_voltage) &&
  145. (_params._low_voltage < _params._critical_voltage);
  146. bool result = update_check(buflen, buffer, low_voltage, "low voltage failsafe");
  147. result = result && update_check(buflen, buffer, low_capacity, "low capacity failsafe");
  148. result = result && update_check(buflen, buffer, critical_voltage, "critical voltage failsafe");
  149. result = result && update_check(buflen, buffer, critical_capacity, "critical capacity failsafe");
  150. result = result && update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage");
  151. result = result && update_check(buflen, buffer, below_arming_capacity, "below minimum arming capacity");
  152. result = result && update_check(buflen, buffer, fs_capacity_inversion, "capacity failsafe critical > low");
  153. result = result && update_check(buflen, buffer, fs_voltage_inversion, "voltage failsafe critical > low");
  154. return result;
  155. }
  156. void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const
  157. {
  158. // use voltage or sag compensated voltage
  159. float voltage_used;
  160. switch (_params.failsafe_voltage_source()) {
  161. case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_Raw:
  162. default:
  163. voltage_used = _state.voltage;
  164. break;
  165. case AP_BattMonitor_Params::BattMonitor_LowVoltageSource_SagCompensated:
  166. voltage_used = voltage_resting_estimate();
  167. break;
  168. }
  169. // check critical battery levels
  170. if ((voltage_used > 0) && (_params._critical_voltage > 0) && (voltage_used < _params._critical_voltage)) {
  171. critical_voltage = true;
  172. } else {
  173. critical_voltage = false;
  174. }
  175. // check capacity failsafe if current monitoring is enabled
  176. if (has_current() && (_params._critical_capacity > 0) &&
  177. ((_params._pack_capacity - _state.consumed_mah) < _params._critical_capacity)) {
  178. critical_capacity = true;
  179. } else {
  180. critical_capacity = false;
  181. }
  182. if ((voltage_used > 0) && (_params._low_voltage > 0) && (voltage_used < _params._low_voltage)) {
  183. low_voltage = true;
  184. } else {
  185. low_voltage = false;
  186. }
  187. // check capacity if current monitoring is enabled
  188. if (has_current() && (_params._low_capacity > 0) &&
  189. ((_params._pack_capacity - _state.consumed_mah) < _params._low_capacity)) {
  190. low_capacity = true;
  191. } else {
  192. low_capacity = false;
  193. }
  194. }
  195. /*
  196. default implementation for reset_remaining(). This sets consumed_wh
  197. and consumed_mah based on the given percentage. Use percentage=100
  198. for a full battery
  199. */
  200. bool AP_BattMonitor_Backend::reset_remaining(float percentage)
  201. {
  202. percentage = constrain_float(percentage, 0, 100);
  203. const float used_proportion = (100 - percentage) * 0.01;
  204. _state.consumed_mah = used_proportion * _params._pack_capacity;
  205. // without knowing the history we can't do consumed_wh
  206. // accurately. Best estimate is based on current voltage. This
  207. // will be good when resetting the battery to a value close to
  208. // full charge
  209. _state.consumed_wh = _state.consumed_mah * 1000 * _state.voltage;
  210. // reset failsafe state for this backend
  211. _state.failsafe = update_failsafes();
  212. return true;
  213. }