AP_BattMonitor_Bebop.cpp 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220
  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_HAL/AP_HAL.h>
  14. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
  15. (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO)
  16. #include "AP_BattMonitor_Bebop.h"
  17. #include <AP_HAL_Linux/RCOutput_Bebop.h>
  18. #include <AP_HAL_Linux/RCOutput_Disco.h>
  19. #define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f)
  20. extern const AP_HAL::HAL &hal;
  21. using namespace Linux;
  22. /* polynomial compensation coefficients */
  23. static const float bat_comp_polynomial_coeffs[5] = {
  24. -1.2471059149657287e-16f,
  25. 3.2072883440944087e-12f,
  26. -3.3012241016211356e-08f,
  27. 1.4612693130825659e-04f,
  28. -1.9236755589522961e-01f
  29. };
  30. /* battery percent lookup table */
  31. static const struct {
  32. float voltage;
  33. float percent;
  34. } bat_lut[] = {
  35. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
  36. {9.5, 0},
  37. {11.04, 5},
  38. {11.11, 10},
  39. {11.21, 15},
  40. {11.3, 25},
  41. {11.4, 45},
  42. {11.6, 55},
  43. {11.9, 79},
  44. {12.02, 84},
  45. {12.11, 88},
  46. {12.19, 91},
  47. {12.26, 94},
  48. {12.35, 96},
  49. {12.45, 98},
  50. {12.5, 100}
  51. #else
  52. // bebop
  53. {10.50f, 0.0f},
  54. {10.741699f, 2.6063901f},
  55. {10.835779f, 5.1693798f},
  56. {10.867705f, 7.7323696f},
  57. {10.900651f, 10.295359f},
  58. {11.008754f, 20.547318f},
  59. {11.148267f, 38.488246f},
  60. {11.322504f, 53.866185f},
  61. {11.505738f, 66.681133f},
  62. {11.746556f, 79.496082f},
  63. {12.110226f, 94.874021f},
  64. {12.3f, 100.0f }
  65. #endif
  66. };
  67. #define BATTERY_PERCENT_LUT_SIZE ARRAY_SIZE(bat_lut)
  68. void AP_BattMonitor_Bebop::init(void)
  69. {
  70. _battery_voltage_max = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
  71. _prev_vbat_raw = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
  72. _prev_vbat = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
  73. }
  74. float AP_BattMonitor_Bebop::_filter_voltage(float vbat_raw)
  75. {
  76. static const float a[2] = {
  77. 1.0f, -9.9686333183343789e-01f
  78. };
  79. static const float b[2] = {
  80. 1.5683340832810533e-03f, 1.5683340832810533e-03f
  81. };
  82. float vbat;
  83. static int only_once = 1;
  84. /* on first time reset filter with first raw value */
  85. if (only_once) {
  86. vbat = vbat_raw;
  87. _prev_vbat_raw = vbat_raw;
  88. _prev_vbat = vbat_raw;
  89. only_once = 0;
  90. } else if (vbat_raw > 0.0f) {
  91. /* 1st order fitler */
  92. vbat = b[0] * vbat_raw +
  93. b[1] * _prev_vbat_raw - a[1] * _prev_vbat;
  94. _prev_vbat_raw = vbat_raw;
  95. _prev_vbat = vbat;
  96. } else {
  97. vbat = _prev_vbat;
  98. }
  99. return vbat;
  100. }
  101. float AP_BattMonitor_Bebop::_compute_compensation(const uint16_t *rpm,
  102. float vbat_raw)
  103. {
  104. float vbat, res;
  105. size_t i, j;
  106. vbat = vbat_raw;
  107. for (i = 0; i < BEBOP_BLDC_MOTORS_NUM; i++) {
  108. res = 0;
  109. for (j = 0; j < ARRAY_SIZE(bat_comp_polynomial_coeffs); j++)
  110. res = res * rpm[i] + bat_comp_polynomial_coeffs[j];
  111. vbat -= res;
  112. }
  113. return vbat;
  114. }
  115. float AP_BattMonitor_Bebop::_compute_battery_percentage(float vbat)
  116. {
  117. float percent = 0.0f;
  118. int i;
  119. if (vbat <= bat_lut[0].voltage) {
  120. percent = 0.0f;
  121. } else if (vbat >= bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage) {
  122. percent = 100.0f;
  123. } else {
  124. i = 0;
  125. while (vbat >= bat_lut[i].voltage)
  126. i++;
  127. percent += bat_lut[i - 1].percent +
  128. (vbat - bat_lut[i - 1].voltage) *
  129. (bat_lut[i].percent - bat_lut[i - 1].percent) /
  130. (bat_lut[i].voltage - bat_lut[i - 1].voltage);
  131. }
  132. return percent;
  133. }
  134. void AP_BattMonitor_Bebop::read(void)
  135. {
  136. int ret;
  137. uint32_t tnow;
  138. BebopBLDC_ObsData data;
  139. float capacity, remaining, vbat, vbat_raw;
  140. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  141. auto rcout = Linux::RCOutput_Bebop::from(hal.rcout);
  142. #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
  143. auto rcout = Linux::RCOutput_Disco::from(hal.rcout);
  144. #endif
  145. tnow = AP_HAL::micros();
  146. ret = rcout->read_obs_data(data);
  147. if (ret < 0) {
  148. _state.healthy = false;
  149. return;
  150. }
  151. /* get battery voltage observed by cypress */
  152. vbat_raw = (float)data.batt_mv / 1000.0f;
  153. /* do not compute battery status on ramping or braking transition */
  154. if (data.status == BEBOP_BLDC_STATUS_RAMPING ||
  155. data.status == BEBOP_BLDC_STATUS_STOPPING)
  156. return;
  157. /* if motors are spinning compute polynomial compensation */
  158. if (data.status == BEBOP_BLDC_STATUS_SPINNING_1 ||
  159. data.status == BEBOP_BLDC_STATUS_SPINNING_2) {
  160. vbat = _compute_compensation(data.rpm, vbat_raw);
  161. /* otherwise compute constant compensation */
  162. } else {
  163. vbat = vbat_raw - BATTERY_VOLTAGE_COMPENSATION_LANDED;
  164. }
  165. /* filter raw value */
  166. vbat = _filter_voltage(vbat);
  167. /* ensure battery voltage/percent will not grow up during use */
  168. if (vbat > _battery_voltage_max) {
  169. vbat = _battery_voltage_max;
  170. } else if (vbat < 0.0f) {
  171. vbat = 0.0f;
  172. _battery_voltage_max = 0.0f;
  173. } else {
  174. _battery_voltage_max = vbat;
  175. }
  176. /* compute remaining battery percent and get battery capacity */
  177. remaining = _compute_battery_percentage(vbat);
  178. capacity = (float) _params._pack_capacity;
  179. /* fillup battery state */
  180. _state.voltage = vbat;
  181. _state.last_time_micros = tnow;
  182. _state.healthy = true;
  183. _state.consumed_mah = capacity - (remaining * capacity) / 100.0f;
  184. }
  185. #endif