PX4 Firmware
PX4 Autopilot Software http://px4.io
Battery Class Reference

#include <battery.h>

Inheritance diagram for Battery:
Collaboration diagram for Battery:

Public Member Functions

 Battery ()
 
void reset (battery_status_s *battery_status)
 Reset all battery stats and report invalid/nothing. More...
 
int cell_count ()
 Get the battery cell count. More...
 
float empty_cell_voltage ()
 Get the empty voltage per cell. More...
 
float full_cell_voltage ()
 Get the full voltage per cell. More...
 
void updateBatteryStatus (hrt_abstime timestamp, float voltage_v, float current_a, bool connected, bool selected_source, int priority, float throttle_normalized, bool armed, battery_status_s *status)
 Update current battery status message. More...
 

Private Member Functions

void filterVoltage (float voltage_v)
 
void filterThrottle (float throttle)
 
void filterCurrent (float current_a)
 
void sumDischarged (hrt_abstime timestamp, float current_a)
 
void estimateRemaining (float voltage_v, float current_a, float throttle, bool armed)
 
void determineWarning (bool connected)
 
void computeScale ()
 
 DEFINE_PARAMETERS ((ParamFloat< px4::params::BAT_V_EMPTY >) _param_bat_v_empty,(ParamFloat< px4::params::BAT_V_CHARGED >) _param_bat_v_charged,(ParamInt< px4::params::BAT_N_CELLS >) _param_bat_n_cells,(ParamFloat< px4::params::BAT_CAPACITY >) _param_bat_capacity,(ParamFloat< px4::params::BAT_V_LOAD_DROP >) _param_bat_v_load_drop,(ParamFloat< px4::params::BAT_R_INTERNAL >) _param_bat_r_internal,(ParamFloat< px4::params::BAT_LOW_THR >) _param_bat_low_thr,(ParamFloat< px4::params::BAT_CRIT_THR >) _param_bat_crit_thr,(ParamFloat< px4::params::BAT_EMERGEN_THR >) _param_bat_emergen_thr) bool _battery_initialized
 

Private Attributes

float _voltage_filtered_v = -1.f
 
float _throttle_filtered = -1.f
 
float _current_filtered_a = -1.f
 
float _discharged_mah = 0.f
 
float _discharged_mah_loop = 0.f
 
float _remaining_voltage = -1.f
 normalized battery charge level remaining based on voltage More...
 
float _remaining = -1.f
 normalized battery charge level, selected based on config param More...
 
float _scale = 1.f
 
uint8_t _warning
 
hrt_abstime _last_timestamp
 

Detailed Description

Definition at line 49 of file battery.h.

Constructor & Destructor Documentation

◆ Battery()

Battery::Battery ( )

Definition at line 47 of file battery.cpp.

Member Function Documentation

◆ cell_count()

int Battery::cell_count ( )
inline

Get the battery cell count.

Definition at line 62 of file battery.h.

◆ computeScale()

void Battery::computeScale ( )
private

Definition at line 226 of file battery.cpp.

References _remaining_voltage, _scale, and f().

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ DEFINE_PARAMETERS()

Battery::DEFINE_PARAMETERS ( (ParamFloat< px4::params::BAT_V_EMPTY >)  _param_bat_v_empty,
(ParamFloat< px4::params::BAT_V_CHARGED >)  _param_bat_v_charged,
(ParamInt< px4::params::BAT_N_CELLS >)  _param_bat_n_cells,
(ParamFloat< px4::params::BAT_CAPACITY >)  _param_bat_capacity,
(ParamFloat< px4::params::BAT_V_LOAD_DROP >)  _param_bat_v_load_drop,
(ParamFloat< px4::params::BAT_R_INTERNAL >)  _param_bat_r_internal,
(ParamFloat< px4::params::BAT_LOW_THR >)  _param_bat_low_thr,
(ParamFloat< px4::params::BAT_CRIT_THR >)  _param_bat_crit_thr,
(ParamFloat< px4::params::BAT_EMERGEN_THR >)  _param_bat_emergen_thr 
)
private

Referenced by full_cell_voltage().

Here is the caller graph for this function:

◆ determineWarning()

void Battery::determineWarning ( bool  connected)
private

Definition at line 209 of file battery.cpp.

References _remaining, and _warning.

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the caller graph for this function:

◆ empty_cell_voltage()

float Battery::empty_cell_voltage ( )
inline

Get the empty voltage per cell.

Definition at line 67 of file battery.h.

◆ estimateRemaining()

void Battery::estimateRemaining ( float  voltage_v,
float  current_a,
float  throttle,
bool  armed 
)
private

Definition at line 170 of file battery.cpp.

References _discharged_mah_loop, _remaining, _remaining_voltage, f(), math::gradual(), and math::max().

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ filterCurrent()

void Battery::filterCurrent ( float  current_a)
private

Definition at line 120 of file battery.cpp.

References _current_filtered_a.

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the caller graph for this function:

◆ filterThrottle()

void Battery::filterThrottle ( float  throttle)
private

Definition at line 134 of file battery.cpp.

References _throttle_filtered.

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the caller graph for this function:

◆ filterVoltage()

void Battery::filterVoltage ( float  voltage_v)
private

Definition at line 105 of file battery.cpp.

References _voltage_filtered_v.

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the caller graph for this function:

◆ full_cell_voltage()

float Battery::full_cell_voltage ( )
inline

Get the full voltage per cell.

Definition at line 72 of file battery.h.

References armed, computeScale(), DEFINE_PARAMETERS(), determineWarning(), estimateRemaining(), filterCurrent(), filterThrottle(), filterVoltage(), hrt_abstime, status, sumDischarged(), and updateBatteryStatus().

Here is the call graph for this function:

◆ reset()

void Battery::reset ( battery_status_s battery_status)

Reset all battery stats and report invalid/nothing.

Definition at line 55 of file battery.cpp.

References battery_status_s::cell_count, battery_status_s::connected, battery_status_s::current_a, battery_status_s::remaining, battery_status_s::scale, and battery_status_s::warning.

Referenced by DfLtc2946Wrapper::DfLtc2946Wrapper(), VOXLPM::init(), and updateBatteryStatus().

Here is the caller graph for this function:

◆ sumDischarged()

void Battery::sumDischarged ( hrt_abstime  timestamp,
float  current_a 
)
private

Definition at line 148 of file battery.cpp.

References _discharged_mah, _discharged_mah_loop, _last_timestamp, dt, and f().

Referenced by full_cell_voltage(), and updateBatteryStatus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateBatteryStatus()

void Battery::updateBatteryStatus ( hrt_abstime  timestamp,
float  voltage_v,
float  current_a,
bool  connected,
bool  selected_source,
int  priority,
float  throttle_normalized,
bool  armed,
battery_status_s status 
)

Update current battery status message.

Parameters
voltage_vcurrent voltage in V
current_acurrent current in A
connectedBattery is connected
selected_sourceThis battery is on the brick that the selected source for selected_source
priorityThe brick number -1. The term priority refers to the Vn connection on the LTC4417
throttle_normalizedthrottle from 0 to 1

Definition at line 68 of file battery.cpp.

References _current_filtered_a, _discharged_mah, _remaining, _scale, _throttle_filtered, _voltage_filtered_v, _warning, computeScale(), battery_status_s::connected, battery_status_s::current_a, battery_status_s::current_filtered_a, determineWarning(), battery_status_s::discharged_mah, estimateRemaining(), f(), filterCurrent(), filterThrottle(), filterVoltage(), battery_status_s::priority, battery_status_s::remaining, reset(), battery_status_s::scale, sumDischarged(), battery_status_s::system_source, battery_status_s::temperature, battery_status_s::timestamp, battery_status_s::voltage_filtered_v, battery_status_s::voltage_v, and battery_status_s::warning.

Referenced by DfLtc2946Wrapper::_publish(), DfBebopBusWrapper::_publish(), BatteryStatus::adc_poll(), full_cell_voltage(), and VOXLPM::measure().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _current_filtered_a

float Battery::_current_filtered_a = -1.f
private

Definition at line 113 of file battery.h.

Referenced by filterCurrent(), and updateBatteryStatus().

◆ _discharged_mah

float Battery::_discharged_mah = 0.f
private

Definition at line 114 of file battery.h.

Referenced by sumDischarged(), and updateBatteryStatus().

◆ _discharged_mah_loop

float Battery::_discharged_mah_loop = 0.f
private

Definition at line 115 of file battery.h.

Referenced by estimateRemaining(), and sumDischarged().

◆ _last_timestamp

hrt_abstime Battery::_last_timestamp
private

Definition at line 120 of file battery.h.

Referenced by sumDischarged().

◆ _remaining

float Battery::_remaining = -1.f
private

normalized battery charge level, selected based on config param

Definition at line 117 of file battery.h.

Referenced by determineWarning(), estimateRemaining(), and updateBatteryStatus().

◆ _remaining_voltage

float Battery::_remaining_voltage = -1.f
private

normalized battery charge level remaining based on voltage

Definition at line 116 of file battery.h.

Referenced by computeScale(), and estimateRemaining().

◆ _scale

float Battery::_scale = 1.f
private

Definition at line 118 of file battery.h.

Referenced by computeScale(), and updateBatteryStatus().

◆ _throttle_filtered

float Battery::_throttle_filtered = -1.f
private

Definition at line 112 of file battery.h.

Referenced by filterThrottle(), and updateBatteryStatus().

◆ _voltage_filtered_v

float Battery::_voltage_filtered_v = -1.f
private

Definition at line 111 of file battery.h.

Referenced by filterVoltage(), and updateBatteryStatus().

◆ _warning

uint8_t Battery::_warning
private

Definition at line 119 of file battery.h.

Referenced by determineWarning(), and updateBatteryStatus().


The documentation for this class was generated from the following files: