BatteryStatus: remove current_filtered_a

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2024-07-03 14:47:16 +02:00 committed by Matthias Grob
parent e03e0261a1
commit c2ae6a7e24
14 changed files with 9 additions and 22 deletions

View File

@ -3,7 +3,6 @@ bool connected # Whether or not a battery is connected, based on a voltage th
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 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown

View File

@ -122,7 +122,6 @@ void BATT_SMBUS::RunImpl()
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
new_report.current_a = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f) * _c_mult;
new_report.current_filtered_a = new_report.current_a;
// Read average current.
ret |= _interface->read_word(BATT_SMBUS_AVERAGE_CURRENT, result);

View File

@ -77,7 +77,6 @@ public:
battery_status_s bat_status {0};
bat_status.timestamp = hrt_absolute_time();
bat_status.voltage_filtered_v = bat_info.voltage;
bat_status.current_filtered_a = bat_info.current;
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;

View File

@ -225,7 +225,7 @@ void CrsfRc::Run()
if (_battery_status_sub.update(&battery_status)) {
uint16_t voltage = battery_status.voltage_filtered_v * 10;
uint16_t current = battery_status.current_filtered_a * 10;
uint16_t current = battery_status.current_a * 10;
int fuel = battery_status.discharged_mah;
uint8_t remaining = battery_status.remaining * 100;
this->SendTelemetryBattery(voltage, current, fuel, remaining);

View File

@ -82,7 +82,7 @@ bool CRSFTelemetry::send_battery()
}
uint16_t voltage = battery_status.voltage_filtered_v * 10;
uint16_t current = battery_status.current_filtered_a * 10;
uint16_t current = battery_status.current_a * 10;
int fuel = battery_status.discharged_mah;
uint8_t remaining = battery_status.remaining * 100;
return crsf_send_telemetry_battery(_uart_fd, voltage, current, fuel, remaining);

View File

@ -91,7 +91,7 @@ bool GHSTTelemetry::send_battery_status()
if (_battery_status_sub.update(&battery_status)) {
voltage_in_10mV = battery_status.voltage_filtered_v * FACTOR_VOLTS_TO_10MV;
current_in_10mA = battery_status.current_filtered_a * FACTOR_AMPS_TO_10MA;
current_in_10mA = battery_status.current_a * FACTOR_AMPS_TO_10MA;
fuel_in_10mAh = battery_status.discharged_mah * FACTOR_MAH_TO_10MAH;
success = ghst_send_telemetry_battery_status(_uart_fd,
static_cast<uint16_t>(voltage_in_10mV),

View File

@ -152,7 +152,6 @@ void Batmon::RunImpl()
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
new_report.current_a = (-1.0f * ((float)(*(int16_t *)&result)) / 1000.0f);
new_report.current_filtered_a = new_report.current_a;
// Read average current.
ret |= _interface->read_word(BATT_SMBUS_AVERAGE_CURRENT, result);

View File

@ -117,7 +117,6 @@ void TattuCan::Run()
battery_status.voltage_v = static_cast<float>(tattu_message.voltage) / 1000.0f;
battery_status.voltage_filtered_v = static_cast<float>(tattu_message.voltage) / 1000.0f;
battery_status.current_a = static_cast<float>(tattu_message.current) / 1000.0f;
battery_status.current_filtered_a = static_cast<float>(tattu_message.current) / 1000.0f;
battery_status.remaining = static_cast<float>(tattu_message.remaining_percent) / 100.0f;
battery_status.temperature = static_cast<float>(tattu_message.temperature);
battery_status.capacity = tattu_message.standard_capacity;

View File

@ -106,7 +106,6 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
_battery_status[instance].voltage_v = msg.voltage;
_battery_status[instance].voltage_filtered_v = msg.voltage;
_battery_status[instance].current_a = msg.current;
_battery_status[instance].current_filtered_a = msg.current;
_battery_status[instance].current_average_a = msg.current;
if (_batt_update_mod[instance] == BatteryDataType::Raw) {

View File

@ -31,15 +31,11 @@ def rls_update(theta, P, x, V, I, lam):
return theta_corr, P_corr, error, data_cov, 0, 0
return theta_temp, P_temp, error, data_cov, gamma[0], gamma[1]
def main(log_name, n_cells, full_cell, empty_cell, lam, filtered):
def main(log_name, n_cells, full_cell, empty_cell, lam):
log = ULog(log_name)
timestamps = us2s(getData(log, 'battery_status', 'timestamp'))
if (filtered):
I = getData(log, 'battery_status', 'current_filtered_a')
V = getData(log, 'battery_status', 'voltage_filtered_v')
else:
I = getData(log, 'battery_status', 'current_a')
V = getData(log, 'battery_status', 'voltage_v')
I = getData(log, 'battery_status', 'current_a')
V = getData(log, 'battery_status', 'voltage_v')
remaining = getData(log, 'battery_status', 'remaining')
if not timestamps.size or not I.size or not V.size or not remaining.size:
@ -176,6 +172,5 @@ if __name__ == "__main__":
parser.add_argument('-u', type = float, required = False, default = 4.05, help = 'Full cell voltage')
parser.add_argument('-e', type = float, required = False, default = 3.6, help = 'Empty cell voltage')
parser.add_argument('-l', type = float, required = False, default = 0.99, help = 'Forgetting factor')
parser.add_argument('-d', type = bool, required = False, default = False, help = 'Filter measurements')
args = parser.parse_args()
main(args.f, args.c, args.u, args.e, args.l, args.d)
main(args.f, args.c, args.u, args.e, args.l)

View File

@ -267,7 +267,6 @@ int SMBUS_SBS_BaseClass<T>::populate_smbus_data(battery_status_s &data)
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
data.current_a = (-1.0f * ((float)(*(int16_t *)&result)) * 0.001f);
data.current_filtered_a = data.current_a;
// Read remaining capacity.
ret |= _interface->read_word(BATT_SMBUS_RELATIVE_SOC, result);

View File

@ -1772,7 +1772,6 @@ MavlinkReceiver::handle_message_battery_status(mavlink_message_t *msg)
battery_status.voltage_v = voltage_sum;
battery_status.voltage_filtered_v = voltage_sum;
battery_status.current_a = (float)(battery_mavlink.current_battery) / 100.0f;
battery_status.current_filtered_a = battery_status.current_a;
battery_status.remaining = (float)battery_mavlink.battery_remaining / 100.0f;
battery_status.discharged_mah = (float)battery_mavlink.current_consumed;
battery_status.cell_count = cell_count;

View File

@ -74,7 +74,7 @@ private:
bat_msg.type = MAV_BATTERY_TYPE_LIPO;
bat_msg.current_consumed = (battery_status.connected) ? battery_status.discharged_mah : -1;
bat_msg.energy_consumed = -1;
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_filtered_a * 100 : -1;
bat_msg.current_battery = (battery_status.connected) ? battery_status.current_a * 100 : -1;
bat_msg.battery_remaining = (battery_status.connected) ? roundf(battery_status.remaining * 100.f) : -1;
// MAVLink extension: 0 is unsupported, in uORB it's NAN
bat_msg.time_remaining = (battery_status.connected && (PX4_ISFINITE(battery_status.time_remaining_s))) ?

View File

@ -167,7 +167,7 @@ private:
if (lowest_battery.connected) {
msg.voltage_battery = lowest_battery.voltage_filtered_v * 1000.0f;
msg.current_battery = lowest_battery.current_filtered_a * 100.0f;
msg.current_battery = lowest_battery.current_a * 100.0f;
msg.battery_remaining = ceilf(lowest_battery.remaining * 100.0f);
} else {