AP_BattMonitor: remove Bebop fixed capacity

Bebop, Bebop2 and Disco all use this class but it was always setting the capacity to the Bebop one, overriding the parameter
This commit is contained in:
Francisco Ferreira 2016-10-22 17:47:59 +01:00 committed by Lucas De Marchi
parent c0b913a975
commit 3a89421c70
3 changed files with 13 additions and 6 deletions

View File

@ -45,3 +45,9 @@ void AP_BattMonitor_Backend::set_capacity(uint32_t capacity)
{
_mon._pack_capacity[_instance] = capacity;
}
/// get capacity for this instance
int32_t AP_BattMonitor_Backend::get_capacity() const
{
return _mon.pack_capacity_mah(_instance);
}

View File

@ -39,6 +39,9 @@ public:
/// set capacity for this instance
void set_capacity(uint32_t capacity);
/// get capacity for this instance
int32_t get_capacity() const;
protected:
AP_BattMonitor &_mon; // reference to front-end

View File

@ -23,7 +23,6 @@
#include <AP_HAL_Linux/RCOutput_Bebop.h>
#include <AP_HAL_Linux/RCOutput_Disco.h>
#define BATTERY_CAPACITY (1200U) /* mAh */
#define BATTERY_VOLTAGE_COMPENSATION_LANDED (0.2f)
@ -81,7 +80,6 @@ static const struct {
void AP_BattMonitor_Bebop::init(void)
{
set_capacity(BATTERY_CAPACITY);
_battery_voltage_max = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
_prev_vbat_raw = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
_prev_vbat = bat_lut[BATTERY_PERCENT_LUT_SIZE - 1].voltage;
@ -163,7 +161,7 @@ void AP_BattMonitor_Bebop::read(void)
int ret;
uint32_t tnow;
BebopBLDC_ObsData data;
float remaining, vbat, vbat_raw;
float capacity, remaining, vbat, vbat_raw;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
auto rcout = Linux::RCOutput_Bebop::from(hal.rcout);
@ -208,15 +206,15 @@ void AP_BattMonitor_Bebop::read(void)
_battery_voltage_max = vbat;
}
/* compute remaining battery percent */
/* compute remaining battery percent and get battery capacity */
remaining = _compute_battery_percentage(vbat);
capacity = (float) get_capacity();
/* fillup battery state */
_state.voltage = vbat;
_state.last_time_micros = tnow;
_state.healthy = true;
_state.current_total_mah = BATTERY_CAPACITY -
(remaining * BATTERY_CAPACITY) / 100.0f;
_state.current_total_mah = capacity - (remaining * capacity) / 100.0f;
}
#endif