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) 26 #define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f) 31 using namespace Linux;
35 -1.2471059149657287e-16
f,
36 3.2072883440944087e-12
f,
37 -3.3012241016211356e-08
f,
38 1.4612693130825659e-04
f,
39 -1.9236755589522961e-01
f 47 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO 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},
79 #define BATTERY_PERCENT_LUT_SIZE ARRAY_SIZE(bat_lut) 90 static const float a[2] = {
91 1.0f, -9.9686333183343789e-01
f 93 static const float b[2] = {
94 1.5683340832810533e-03
f, 1.5683340832810533e-03
f 97 static int only_once = 1;
102 _prev_vbat_raw = vbat_raw;
103 _prev_vbat = vbat_raw;
105 }
else if (vbat_raw > 0.0
f) {
107 vbat = b[0] * vbat_raw +
108 b[1] * _prev_vbat_raw - a[1] * _prev_vbat;
109 _prev_vbat_raw = vbat_raw;
147 while (vbat >=
bat_lut[i].voltage)
150 percent +=
bat_lut[i - 1].percent +
151 (vbat -
bat_lut[i - 1].voltage) *
164 float capacity, remaining, vbat, vbat_raw;
166 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP 168 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO 173 ret = rcout->read_obs_data(data);
175 _state.healthy =
false;
180 vbat_raw = (float)data.
batt_mv / 1000.0f;
190 vbat = _compute_compensation(data.
rpm, vbat_raw);
197 vbat = _filter_voltage(vbat);
200 if (vbat > _battery_voltage_max) {
201 vbat = _battery_voltage_max;
202 }
else if (vbat < 0.0
f) {
204 _battery_voltage_max = 0.0f;
206 _battery_voltage_max = vbat;
210 remaining = _compute_battery_percentage(vbat);
211 capacity = (float) _params._pack_capacity;
214 _state.voltage = vbat;
215 _state.last_time_micros = tnow;
216 _state.healthy =
true;
217 _state.consumed_mah = capacity - (remaining * capacity) / 100.0f;
#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)
static const struct @12 bat_lut[]
uint16_t rpm[BEBOP_BLDC_MOTORS_NUM]
float _filter_voltage(float vbat_raw)
float _compute_compensation(const uint16_t *rpm, float vbat_raw)