Skip to content

Commit

Permalink
analog_battery: add option for filter
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexKlimaj committed Nov 22, 2024
1 parent 14468d4 commit 1484982
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 3 deletions.
3 changes: 3 additions & 0 deletions boards/ark/fpv/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,9 @@

#define BOARD_BATTERY1_V_DIV (21.0f) // (20k + 1k) / 1k = 21

#define BOARD_BATTERY_ADC_VOLTAGE_FILTER_S 0.075f
#define BOARD_BATTERY_ADC_CURRENT_FILTER_S 0.125f

#define ADC_SCALED_PAYLOAD_SENSE ADC_SCALED_12V_CHANNEL

/* HW has to large of R termination on ADC todo:change when HW value is chosen */
Expand Down
4 changes: 2 additions & 2 deletions src/lib/mathlib/math/filter/AlphaFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ class AlphaFilter
*
* Both parameters have to be provided in the same units.
*
* @param sample_interval interval between two samples
* @param time_constant filter time constant determining convergence
* @param sample_interval interval between two samples in seconds
* @param time_constant filter time constant determining convergence in seconds
*/
void setParameters(float sample_interval, float time_constant)
{
Expand Down
24 changes: 23 additions & 1 deletion src/modules/battery_status/analog_battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,16 +71,38 @@ AnalogBattery::AnalogBattery(int index, ModuleParams *parent, const int sample_i

snprintf(param_name, sizeof(param_name), "BAT%d_I_OVERWRITE", index);
_analog_param_handles.i_overwrite = param_find(param_name);

#if defined(BOARD_BATTERY_ADC_VOLTAGE_FILTER_S) || defined(BOARD_BATTERY_ADC_CURRENT_FILTER_S)
const float expected_filter_dt = static_cast<float>(sample_interval_us) / 1e6f;
#endif

#ifdef BOARD_BATTERY_ADC_VOLTAGE_FILTER_S
_voltage_filter.setParameters(expected_filter_dt, BOARD_BATTERY_ADC_VOLTAGE_FILTER_S);
#endif

#ifdef BOARD_BATTERY_ADC_CURRENT_FILTER_S
_current_filter.setParameters(expected_filter_dt, BOARD_BATTERY_ADC_CURRENT_FILTER_S);
#endif
}

void
AnalogBattery::updateBatteryStatusADC(hrt_abstime timestamp, float voltage_raw, float current_raw)
{
const float voltage_v = voltage_raw * _analog_params.v_div;
float voltage_v = voltage_raw * _analog_params.v_div;
const bool connected = voltage_v > BOARD_ADC_OPEN_CIRCUIT_V &&
(BOARD_ADC_OPEN_CIRCUIT_V <= BOARD_VALID_UV || is_valid());
float current_a = (current_raw - _analog_params.v_offs_cur) * _analog_params.a_per_v;

#ifdef BOARD_BATTERY_ADC_VOLTAGE_FILTER_S
_voltage_filter.update(fmaxf(voltage_v, 0.f));
voltage_v = _voltage_filter.getState();
#endif

#ifdef BOARD_BATTERY_ADC_CURRENT_FILTER_S
_current_filter.update(fmaxf(current_a, 0.f));
current_a = _current_filter.getState();
#endif

// Overwrite the measured current if current overwrite is defined and vehicle is unarmed
if (_analog_params.i_overwrite > 0) {
updateTopics();
Expand Down
9 changes: 9 additions & 0 deletions src/modules/battery_status/analog_battery.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#pragma once

#include <battery/battery.h>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <parameters/param.h>
#include <uORB/topics/vehicle_status.h>

Expand Down Expand Up @@ -96,5 +97,13 @@ class AnalogBattery : public Battery
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uint8_t _arming_state{0};

#ifdef BOARD_BATTERY_ADC_VOLTAGE_FILTER_S
AlphaFilter<float> _voltage_filter;
#endif

#ifdef BOARD_BATTERY_ADC_CURRENT_FILTER_S
AlphaFilter<float> _current_filter;
#endif

void updateTopics();
};

0 comments on commit 1484982

Please sign in to comment.