battery_status: naming consistency current_filtered_a -> current_average_a

This commit is contained in:
Matthias Grob
2021-06-25 16:02:51 +02:00
parent 41cc73e555
commit 9c0c85c9e2
6 changed files with 6 additions and 6 deletions

View File

@@ -3,7 +3,7 @@ float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 voltage_filtered_v # Battery voltage in volts, filtered, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown
float32 current_filtered_a # Battery current in amperes, filtered, 0 if unknown
float32 average_current_a # Battery current average in amperes, -1 if unknown
float32 current_average_a # Battery current average in amperes, -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown

View File

@@ -129,7 +129,7 @@ void BATT_SMBUS::RunImpl()
float average_current = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f) * _c_mult;
new_report.average_current_a = average_current;
new_report.current_average_a = average_current;
// If current is high, turn under voltage protection off. This is neccessary to prevent
// a battery from cutting off while flying with high current near the end of the packs capacity.

View File

@@ -169,7 +169,7 @@ void Batmon::RunImpl()
float average_current = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f);
new_report.average_current_a = average_current;
new_report.current_average_a = average_current;
// Read run time to empty (minutes).
ret |= _interface->read_word(BATT_SMBUS_RUN_TIME_TO_EMPTY, result);

View File

@@ -69,7 +69,7 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
battery.voltage_filtered_v = msg.voltage;
battery.current_a = msg.current;
battery.current_filtered_a = msg.current;
// battery.average_current_a = msg.;
// battery.current_average_a = msg.;
sumDischarged(battery.timestamp, battery.current_a);
battery.discharged_mah = _discharged_mah;

View File

@@ -68,7 +68,7 @@ UavcanCBATBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<cuav::equip
battery.voltage_filtered_v = battery.voltage_v;
battery.current_a = msg.current;
battery.current_filtered_a = battery.current_a;
battery.average_current_a = msg.average_current;
battery.current_average_a = msg.average_current;
battery.discharged_mah = msg.passed_charge * 1000;
battery.remaining = msg.state_of_charge / 100.0f;
// battery.scale = msg.; // Power scaling factor, >= 1, or -1 if unknown

View File

@@ -79,7 +79,7 @@ public:
bat_status.timestamp = hrt_absolute_time();
bat_status.voltage_filtered_v = bat_info.voltage;
bat_status.current_filtered_a = bat_info.current;
bat_status.average_current_a = bat_info.average_power_10sec;
bat_status.current_average_a = bat_info.average_power_10sec;
bat_status.remaining = bat_info.state_of_charge_pct / 100.0f;
bat_status.scale = -1;