From 9c0c85c9e27f798e3f75ee207e8e7c70f608d862 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 25 Jun 2021 16:02:51 +0200 Subject: [PATCH] battery_status: naming consistency current_filtered_a -> current_average_a --- msg/battery_status.msg | 2 +- src/drivers/batt_smbus/batt_smbus.cpp | 2 +- src/drivers/smart_battery/batmon/batmon.cpp | 2 +- src/drivers/uavcan/sensors/battery.cpp | 2 +- src/drivers/uavcan/sensors/cbat.cpp | 2 +- src/drivers/uavcan_v1/Subscribers/legacy/LegacyBatteryInfo.hpp | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/msg/battery_status.msg b/msg/battery_status.msg index 77a190a065..45e0df136d 100644 --- a/msg/battery_status.msg +++ b/msg/battery_status.msg @@ -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 diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 0326b7133c..80b76e1acf 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -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. diff --git a/src/drivers/smart_battery/batmon/batmon.cpp b/src/drivers/smart_battery/batmon/batmon.cpp index 4a92565a3d..d1c3880504 100644 --- a/src/drivers/smart_battery/batmon/batmon.cpp +++ b/src/drivers/smart_battery/batmon/batmon.cpp @@ -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); diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index 0d00fbb6fa..b17b07b35b 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -69,7 +69,7 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure= 1, or -1 if unknown diff --git a/src/drivers/uavcan_v1/Subscribers/legacy/LegacyBatteryInfo.hpp b/src/drivers/uavcan_v1/Subscribers/legacy/LegacyBatteryInfo.hpp index f1840a12ca..7e1664c276 100644 --- a/src/drivers/uavcan_v1/Subscribers/legacy/LegacyBatteryInfo.hpp +++ b/src/drivers/uavcan_v1/Subscribers/legacy/LegacyBatteryInfo.hpp @@ -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;