APM:Libraries
AP_BattMonitor_Bebop.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 
17 #include <AP_HAL/AP_HAL.h>
18 
19 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
20  (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO)
21 
22 #include "AP_BattMonitor_Bebop.h"
25 
26 #define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f)
27 
28 
29 extern const AP_HAL::HAL &hal;
30 
31 using namespace Linux;
32 
33 /* polynomial compensation coefficients */
34 static const float bat_comp_polynomial_coeffs[5] = {
35  -1.2471059149657287e-16f,
36  3.2072883440944087e-12f,
37  -3.3012241016211356e-08f,
38  1.4612693130825659e-04f,
39  -1.9236755589522961e-01f
40 };
41 
42 /* battery percent lookup table */
43 static const struct {
44  float voltage;
45  float percent;
46 } bat_lut[] = {
47 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
48  {9.5, 0},
49  {11.04, 5},
50  {11.11, 10},
51  {11.21, 15},
52  {11.3, 25},
53  {11.4, 45},
54  {11.6, 55},
55  {11.9, 79},
56  {12.02, 84},
57  {12.11, 88},
58  {12.19, 91},
59  {12.26, 94},
60  {12.35, 96},
61  {12.45, 98},
62  {12.5, 100}
63 #else
64  // bebop
65  {10.50f, 0.0f},
66  {10.741699f, 2.6063901f},
67  {10.835779f, 5.1693798f},
68  {10.867705f, 7.7323696f},
69  {10.900651f, 10.295359f},
70  {11.008754f, 20.547318f},
71  {11.148267f, 38.488246f},
72  {11.322504f, 53.866185f},
73  {11.505738f, 66.681133f},
74  {11.746556f, 79.496082f},
75  {12.110226f, 94.874021f},
76  {12.3f, 100.0f }
77 #endif
78 };
79 #define BATTERY_PERCENT_LUT_SIZE ARRAY_SIZE(bat_lut)
80 
82 {
83  _battery_voltage_max = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
84  _prev_vbat_raw = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
85  _prev_vbat = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
86 }
87 
89 {
90  static const float a[2] = {
91  1.0f, -9.9686333183343789e-01f
92  };
93  static const float b[2] = {
94  1.5683340832810533e-03f, 1.5683340832810533e-03f
95  };
96  float vbat;
97  static int only_once = 1;
98 
99  /* on first time reset filter with first raw value */
100  if (only_once) {
101  vbat = vbat_raw;
102  _prev_vbat_raw = vbat_raw;
103  _prev_vbat = vbat_raw;
104  only_once = 0;
105  } else if (vbat_raw > 0.0f) {
106  /* 1st order fitler */
107  vbat = b[0] * vbat_raw +
108  b[1] * _prev_vbat_raw - a[1] * _prev_vbat;
109  _prev_vbat_raw = vbat_raw;
110  _prev_vbat = vbat;
111  } else {
112  vbat = _prev_vbat;
113  }
114 
115  return vbat;
116 }
117 
119  float vbat_raw)
120 {
121  float vbat, res;
122  size_t i, j;
123 
124  vbat = vbat_raw;
125  for (i = 0; i < BEBOP_BLDC_MOTORS_NUM; i++) {
126  res = 0;
127  for (j = 0; j < ARRAY_SIZE(bat_comp_polynomial_coeffs); j++)
128  res = res * rpm[i] + bat_comp_polynomial_coeffs[j];
129 
130  vbat -= res;
131  }
132 
133  return vbat;
134 }
135 
137 {
138  float percent = 0.0f;
139  int i;
140 
141  if (vbat <= bat_lut[0].voltage) {
142  percent = 0.0f;
143  } else if (vbat >= bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage) {
144  percent = 100.0f;
145  } else {
146  i = 0;
147  while (vbat >= bat_lut[i].voltage)
148  i++;
149 
150  percent += bat_lut[i - 1].percent +
151  (vbat - bat_lut[i - 1].voltage) *
152  (bat_lut[i].percent - bat_lut[i - 1].percent) /
153  (bat_lut[i].voltage - bat_lut[i - 1].voltage);
154  }
155 
156  return percent;
157 }
158 
160 {
161  int ret;
162  uint32_t tnow;
163  BebopBLDC_ObsData data;
164  float capacity, remaining, vbat, vbat_raw;
165 
166 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
167  auto rcout = Linux::RCOutput_Bebop::from(hal.rcout);
168 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
169  auto rcout = Linux::RCOutput_Disco::from(hal.rcout);
170 #endif
171  tnow = AP_HAL::micros();
172 
173  ret = rcout->read_obs_data(data);
174  if (ret < 0) {
175  _state.healthy = false;
176  return;
177  }
178 
179  /* get battery voltage observed by cypress */
180  vbat_raw = (float)data.batt_mv / 1000.0f;
181 
182  /* do not compute battery status on ramping or braking transition */
183  if (data.status == BEBOP_BLDC_STATUS_RAMPING ||
185  return;
186 
187  /* if motors are spinning compute polynomial compensation */
188  if (data.status == BEBOP_BLDC_STATUS_SPINNING_1 ||
190  vbat = _compute_compensation(data.rpm, vbat_raw);
191  /* otherwise compute constant compensation */
192  } else {
193  vbat = vbat_raw - BATTERY_VOLTAGE_COMPENSATION_LANDED;
194  }
195 
196  /* filter raw value */
197  vbat = _filter_voltage(vbat);
198 
199  /* ensure battery voltage/percent will not grow up during use */
200  if (vbat > _battery_voltage_max) {
201  vbat = _battery_voltage_max;
202  } else if (vbat < 0.0f) {
203  vbat = 0.0f;
204  _battery_voltage_max = 0.0f;
205  } else {
206  _battery_voltage_max = vbat;
207  }
208 
209  /* compute remaining battery percent and get battery capacity */
210  remaining = _compute_battery_percentage(vbat);
211  capacity = (float) _params._pack_capacity;
212 
213  /* fillup battery state */
214  _state.voltage = vbat;
215  _state.last_time_micros = tnow;
216  _state.healthy = true;
217  _state.consumed_mah = capacity - (remaining * capacity) / 100.0f;
218 }
219 
220 #endif
#define BATTERY_VOLTAGE_COMPENSATION_LANDED
#define BEBOP_BLDC_STATUS_SPINNING_2
static RCOutput_Bebop * from(AP_HAL::RCOutput *rcout)
#define BEBOP_BLDC_STATUS_SPINNING_1
float _compute_battery_percentage(float vbat)
#define BEBOP_BLDC_STATUS_RAMPING
#define BATTERY_PERCENT_LUT_SIZE
#define BEBOP_BLDC_STATUS_STOPPING
static const float bat_comp_polynomial_coeffs[5]
static RCOutput_Bebop * from(AP_HAL::RCOutput *rcoutput)
#define f(i)
static const struct @12 bat_lut[]
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]
float voltage
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
float _filter_voltage(float vbat_raw)
float percent
float _compute_compensation(const uint16_t *rpm, float vbat_raw)
uint32_t micros()
Definition: system.cpp:152