battery: pass priority in by setter

This commit is contained in:
Matthias Grob
2021-12-01 16:51:45 +01:00
parent f9fc9a9af6
commit 38d23f5345
12 changed files with 32 additions and 47 deletions
@@ -404,7 +404,7 @@ Syslink::handle_message(syslink_message_t *msg)
memcpy(&vbat, &msg->data[1], sizeof(float)); memcpy(&vbat, &msg->data[1], sizeof(float));
//memcpy(&iset, &msg->data[5], sizeof(float)); //memcpy(&iset, &msg->data[5], sizeof(float));
_battery.updateBatteryStatus(t, vbat, -1, true, 0); _battery.updateBatteryStatus(t, vbat, -1, true);
// Update battery charge state // Update battery charge state
if (charging) { if (charging) {
+3 -6
View File
@@ -87,8 +87,7 @@ INA226::INA226(const I2CSPIDriverConfig &config, int battery_index) :
hrt_absolute_time(), hrt_absolute_time(),
0.0, 0.0,
0.0, 0.0,
false, false
0
); );
} }
@@ -233,8 +232,7 @@ INA226::collect()
hrt_absolute_time(), hrt_absolute_time(),
(float) _bus_voltage * INA226_VSCALE, (float) _bus_voltage * INA226_VSCALE,
(float) _current * _current_lsb, (float) _current * _current_lsb,
success, success
0
); );
perf_end(_sample_perf); perf_end(_sample_perf);
@@ -302,8 +300,7 @@ INA226::RunImpl()
hrt_absolute_time(), hrt_absolute_time(),
0.0f, 0.0f,
0.0f, 0.0f,
false, false
0
); );
if (init() != PX4_OK) { if (init() != PX4_OK) {
+3 -6
View File
@@ -89,8 +89,7 @@ INA228::INA228(const I2CSPIDriverConfig &config, int battery_index) :
hrt_absolute_time(), hrt_absolute_time(),
0.0, 0.0,
0.0, 0.0,
false, false
0
); );
} }
@@ -314,8 +313,7 @@ INA228::collect()
hrt_absolute_time(), hrt_absolute_time(),
(float) _bus_voltage * INA228_VSCALE, (float) _bus_voltage * INA228_VSCALE,
(float) _current * _current_lsb, (float) _current * _current_lsb,
success, success
0
); );
perf_end(_sample_perf); perf_end(_sample_perf);
@@ -383,8 +381,7 @@ INA228::RunImpl()
hrt_absolute_time(), hrt_absolute_time(),
0.0f, 0.0f,
0.0f, 0.0f,
false, false
0
); );
if (init() != PX4_OK) { if (init() != PX4_OK) {
+3 -6
View File
@@ -72,8 +72,7 @@ INA238::INA238(const I2CSPIDriverConfig &config, int battery_index) :
hrt_absolute_time(), hrt_absolute_time(),
0.0, 0.0,
0.0, 0.0,
false, false
0
); );
} }
@@ -201,8 +200,7 @@ int INA238::collect()
hrt_absolute_time(), hrt_absolute_time(),
(float) bus_voltage * INA238_VSCALE, (float) bus_voltage * INA238_VSCALE,
(float) current * _current_lsb, (float) current * _current_lsb,
success, success
0
); );
perf_end(_sample_perf); perf_end(_sample_perf);
@@ -261,8 +259,7 @@ void INA238::RunImpl()
hrt_absolute_time(), hrt_absolute_time(),
0.0f, 0.0f,
0.0f, 0.0f,
false, false
0
); );
if (init() != PX4_OK) { if (init() != PX4_OK) {
+3 -6
View File
@@ -75,8 +75,7 @@ VOXLPM::init()
hrt_absolute_time(), hrt_absolute_time(),
0.0, 0.0,
0.0, 0.0,
false, false
0
); );
} }
@@ -347,8 +346,7 @@ VOXLPM::measure()
_battery.updateBatteryStatus(tnow, _battery.updateBatteryStatus(tnow,
_voltage, _voltage,
_amperage, _amperage,
true, true);
0);
} }
// fallthrough // fallthrough
@@ -374,8 +372,7 @@ VOXLPM::measure()
_battery.updateBatteryStatus(tnow, _battery.updateBatteryStatus(tnow,
0.0, 0.0,
0.0, 0.0,
true, true);
0);
} }
break; break;
+2 -3
View File
@@ -97,8 +97,7 @@ Battery::Battery(int index, ModuleParams *parent, const int sample_interval_us,
updateParams(); updateParams();
} }
void Battery::updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v, float current_a, bool connected, void Battery::updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v, float current_a, bool connected)
int priority)
{ {
if (!_battery_initialized) { if (!_battery_initialized) {
_voltage_filter_v.reset(voltage_v); _voltage_filter_v.reset(voltage_v);
@@ -136,7 +135,7 @@ void Battery::updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v,
battery_status.cell_count = _params.n_cells; battery_status.cell_count = _params.n_cells;
battery_status.connected = connected; battery_status.connected = connected;
battery_status.source = _source; battery_status.source = _source;
battery_status.priority = priority; battery_status.priority = _priority;
battery_status.capacity = _params.capacity > 0.f ? static_cast<uint16_t>(_params.capacity) : 0; battery_status.capacity = _params.capacity > 0.f ? static_cast<uint16_t>(_params.capacity) : 0;
battery_status.id = static_cast<uint8_t>(_index); battery_status.id = static_cast<uint8_t>(_index);
battery_status.warning = _warning; battery_status.warning = _warning;
+4 -3
View File
@@ -85,16 +85,16 @@ public:
*/ */
float full_cell_voltage() { return _params.v_charged; } float full_cell_voltage() { return _params.v_charged; }
void setPriority(const uint8_t priority) { _priority = priority; }
/** /**
* Update current battery status message. * Update current battery status message.
* *
* @param voltage_raw: Battery voltage, in Volts * @param voltage_raw: Battery voltage, in Volts
* @param current_raw: Battery current, in Amps * @param current_raw: Battery current, in Amps
* @param timestamp: Time at which the ADC was read (use hrt_absolute_time()) * @param timestamp: Time at which the ADC was read (use hrt_absolute_time())
* @param priority: The brick number -1. The term priority refers to the Vn connection on the LTC4417
*/ */
void updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v, float current_a, bool connected, void updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v, float current_a, bool connected);
int priority);
protected: protected:
struct { struct {
@@ -139,6 +139,7 @@ private:
uORB::PublicationMulti<battery_status_s> _battery_status_pub{ORB_ID(battery_status)}; uORB::PublicationMulti<battery_status_s> _battery_status_pub{ORB_ID(battery_status)};
const uint8_t _source{}; const uint8_t _source{};
uint8_t _priority{0};
bool _battery_initialized{false}; bool _battery_initialized{false};
AlphaFilter<float> _voltage_filter_v; AlphaFilter<float> _voltage_filter_v;
AlphaFilter<float> _current_filter_a; AlphaFilter<float> _current_filter_a;
@@ -49,9 +49,11 @@ static constexpr int DEFAULT_V_CHANNEL[1] = {0};
static constexpr int DEFAULT_I_CHANNEL[1] = {0}; static constexpr int DEFAULT_I_CHANNEL[1] = {0};
#endif #endif
AnalogBattery::AnalogBattery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source) : AnalogBattery::AnalogBattery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source,
const uint8_t priority) :
Battery(index, parent, sample_interval_us, source) Battery(index, parent, sample_interval_us, source)
{ {
Battery::setPriority(priority);
char param_name[17]; char param_name[17];
_analog_param_handles.v_offs_cur = param_find("BAT_V_OFFS_CURR"); _analog_param_handles.v_offs_cur = param_find("BAT_V_OFFS_CURR");
@@ -70,8 +72,7 @@ AnalogBattery::AnalogBattery(int index, ModuleParams *parent, const int sample_i
} }
void void
AnalogBattery::updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw, float current_raw, AnalogBattery::updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw, float current_raw)
int priority)
{ {
float voltage_v = voltage_raw * _analog_params.v_div; float voltage_v = voltage_raw * _analog_params.v_div;
float current_a = (current_raw - _analog_params.v_offs_cur) * _analog_params.a_per_v; float current_a = (current_raw - _analog_params.v_offs_cur) * _analog_params.a_per_v;
@@ -80,8 +81,7 @@ AnalogBattery::updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw,
(BOARD_ADC_OPEN_CIRCUIT_V <= BOARD_VALID_UV || is_valid()); (BOARD_ADC_OPEN_CIRCUIT_V <= BOARD_VALID_UV || is_valid());
Battery::updateBatteryStatus(timestamp, voltage_v, current_a, connected, Battery::updateBatteryStatus(timestamp, voltage_v, current_a, connected);
priority);
} }
bool AnalogBattery::is_valid() bool AnalogBattery::is_valid()
+3 -3
View File
@@ -39,7 +39,8 @@
class AnalogBattery : public Battery class AnalogBattery : public Battery
{ {
public: public:
AnalogBattery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source); AnalogBattery(int index, ModuleParams *parent, const int sample_interval_us, const uint8_t source,
const uint8_t priority);
/** /**
* Update current battery status message. * Update current battery status message.
@@ -50,8 +51,7 @@ public:
* @param source The source as defined by param BAT%d_SOURCE * @param source The source as defined by param BAT%d_SOURCE
* @param priority: The brick number -1. The term priority refers to the Vn connection on the LTC4417 * @param priority: The brick number -1. The term priority refers to the Vn connection on the LTC4417
*/ */
void updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw, float current_raw, void updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw, float current_raw);
int priority);
/** /**
* Whether the ADC channel for the voltage of this battery is valid. * Whether the ADC channel for the voltage of this battery is valid.
@@ -137,9 +137,9 @@ private:
BatteryStatus::BatteryStatus() : BatteryStatus::BatteryStatus() :
ModuleParams(nullptr), ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
_battery1(1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE), _battery1(1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 0),
#if BOARD_NUMBER_BRICKS > 1 #if BOARD_NUMBER_BRICKS > 1
_battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE), _battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 1),
#endif #endif
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME)) _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME))
{ {
@@ -221,8 +221,7 @@ BatteryStatus::adc_poll()
_analogBatteries[b]->updateBatteryStatusADC( _analogBatteries[b]->updateBatteryStatusADC(
hrt_absolute_time(), hrt_absolute_time(),
bat_voltage_adc_readings[b], bat_voltage_adc_readings[b],
bat_current_adc_readings[b], bat_current_adc_readings[b]
b
); );
} }
} }
+1 -3
View File
@@ -100,14 +100,12 @@ EscBattery::Run()
average_voltage_v /= esc_status.esc_count; average_voltage_v /= esc_status.esc_count;
const bool connected = true; const bool connected = true;
const int priority = 0;
_battery.updateBatteryStatus( _battery.updateBatteryStatus(
esc_status.timestamp, esc_status.timestamp,
average_voltage_v, average_voltage_v,
total_current_a, total_current_a,
connected, connected);
priority);
} }
} }
@@ -99,7 +99,7 @@ void BatterySimulator::Run()
float vbatt = math::gradual(_battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage()); float vbatt = math::gradual(_battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage());
vbatt *= _battery.cell_count(); vbatt *= _battery.cell_count();
_battery.updateBatteryStatus(now_us, vbatt, ibatt, true, 0); _battery.updateBatteryStatus(now_us, vbatt, ibatt, true);
perf_end(_loop_perf); perf_end(_loop_perf);
} }