mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
BatteryStatus: remove voltage_filtered_a
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
c2ae6a7e24
commit
33701aa3d5
@ -1148,7 +1148,6 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
|
||||
|
||||
hil_battery_status.timestamp = gyro_accel_time;
|
||||
hil_battery_status.voltage_v = 16.0f;
|
||||
hil_battery_status.voltage_filtered_v = 16.0f;
|
||||
hil_battery_status.current_a = 10.0f;
|
||||
hil_battery_status.discharged_mah = -1.0f;
|
||||
hil_battery_status.connected = true;
|
||||
|
||||
@ -1,7 +1,6 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
bool connected # Whether or not a battery is connected, based on a voltage threshold
|
||||
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_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
|
||||
|
||||
@ -116,7 +116,6 @@ void BATT_SMBUS::RunImpl()
|
||||
|
||||
// Convert millivolts to volts.
|
||||
new_report.voltage_v = ((float)result) / 1000.0f;
|
||||
new_report.voltage_filtered_v = new_report.voltage_v;
|
||||
|
||||
// Read current.
|
||||
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
|
||||
|
||||
@ -76,7 +76,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_average_a = bat_info.average_power_10sec;
|
||||
bat_status.remaining = bat_info.state_of_charge_pct / 100.0f;
|
||||
bat_status.scale = -1;
|
||||
|
||||
@ -241,7 +241,7 @@ OSDatxxxx::add_battery_info(uint8_t pos_x, uint8_t pos_y)
|
||||
int ret = PX4_OK;
|
||||
|
||||
// TODO: show battery symbol based on battery fill level
|
||||
snprintf(buf, sizeof(buf), "%c%5.2f", OSD_SYMBOL_BATT_3, (double)_battery_voltage_filtered_v);
|
||||
snprintf(buf, sizeof(buf), "%c%5.2f", OSD_SYMBOL_BATT_3, (double)_battery_voltage_v);
|
||||
buf[sizeof(buf) - 1] = '\0';
|
||||
|
||||
for (int i = 0; buf[i] != '\0'; i++) {
|
||||
@ -330,7 +330,7 @@ OSDatxxxx::update_topics()
|
||||
_battery_sub.copy(&battery);
|
||||
|
||||
if (battery.connected) {
|
||||
_battery_voltage_filtered_v = battery.voltage_filtered_v;
|
||||
_battery_voltage_v = battery.voltage_v;
|
||||
_battery_discharge_mah = battery.discharged_mah;
|
||||
_battery_valid = true;
|
||||
|
||||
|
||||
@ -111,7 +111,7 @@ private:
|
||||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||
|
||||
// battery
|
||||
float _battery_voltage_filtered_v{0.f};
|
||||
float _battery_voltage_v{0.f};
|
||||
float _battery_discharge_mah{0.f};
|
||||
bool _battery_valid{false};
|
||||
|
||||
|
||||
@ -224,7 +224,7 @@ void CrsfRc::Run()
|
||||
battery_status_s battery_status;
|
||||
|
||||
if (_battery_status_sub.update(&battery_status)) {
|
||||
uint16_t voltage = battery_status.voltage_filtered_v * 10;
|
||||
uint16_t voltage = battery_status.voltage_v * 10;
|
||||
uint16_t current = battery_status.current_a * 10;
|
||||
int fuel = battery_status.discharged_mah;
|
||||
uint8_t remaining = battery_status.remaining * 100;
|
||||
|
||||
@ -81,7 +81,7 @@ bool CRSFTelemetry::send_battery()
|
||||
return false;
|
||||
}
|
||||
|
||||
uint16_t voltage = battery_status.voltage_filtered_v * 10;
|
||||
uint16_t voltage = battery_status.voltage_v * 10;
|
||||
uint16_t current = battery_status.current_a * 10;
|
||||
int fuel = battery_status.discharged_mah;
|
||||
uint8_t remaining = battery_status.remaining * 100;
|
||||
|
||||
@ -90,7 +90,7 @@ bool GHSTTelemetry::send_battery_status()
|
||||
battery_status_s battery_status;
|
||||
|
||||
if (_battery_status_sub.update(&battery_status)) {
|
||||
voltage_in_10mV = battery_status.voltage_filtered_v * FACTOR_VOLTS_TO_10MV;
|
||||
voltage_in_10mV = battery_status.voltage_v * FACTOR_VOLTS_TO_10MV;
|
||||
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,
|
||||
|
||||
@ -146,7 +146,6 @@ void Batmon::RunImpl()
|
||||
|
||||
// Convert millivolts to volts.
|
||||
new_report.voltage_v = ((float)result) / 1000.0f;
|
||||
new_report.voltage_filtered_v = new_report.voltage_v;
|
||||
|
||||
// Read current.
|
||||
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
|
||||
|
||||
@ -115,7 +115,6 @@ void TattuCan::Run()
|
||||
battery_status.state_of_health = static_cast<uint16_t>(tattu_message.health_status);
|
||||
|
||||
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.remaining = static_cast<float>(tattu_message.remaining_percent) / 100.0f;
|
||||
battery_status.temperature = static_cast<float>(tattu_message.temperature);
|
||||
|
||||
@ -104,7 +104,6 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
|
||||
|
||||
_battery_status[instance].timestamp = hrt_absolute_time();
|
||||
_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_average_a = msg.current;
|
||||
|
||||
|
||||
@ -261,7 +261,6 @@ int SMBUS_SBS_BaseClass<T>::populate_smbus_data(battery_status_s &data)
|
||||
|
||||
// Convert millivolts to volts.
|
||||
data.voltage_v = ((float)result) * 0.001f;
|
||||
data.voltage_filtered_v = data.voltage_v;
|
||||
|
||||
// Read current.
|
||||
ret |= _interface->read_word(BATT_SMBUS_CURRENT, result);
|
||||
|
||||
@ -1770,7 +1770,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.remaining = (float)battery_mavlink.battery_remaining / 100.0f;
|
||||
battery_status.discharged_mah = (float)battery_mavlink.current_consumed;
|
||||
@ -2372,7 +2371,6 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
|
||||
|
||||
hil_battery_status.timestamp = timestamp;
|
||||
hil_battery_status.voltage_v = 16.0f;
|
||||
hil_battery_status.voltage_filtered_v = 16.0f;
|
||||
hil_battery_status.current_a = 10.0f;
|
||||
hil_battery_status.discharged_mah = -1.0f;
|
||||
hil_battery_status.connected = true;
|
||||
@ -2726,7 +2724,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
|
||||
{
|
||||
battery_status_s hil_battery_status{};
|
||||
hil_battery_status.voltage_v = 11.1f;
|
||||
hil_battery_status.voltage_filtered_v = 11.1f;
|
||||
hil_battery_status.current_a = 10.0f;
|
||||
hil_battery_status.discharged_mah = -1.0f;
|
||||
hil_battery_status.timestamp = hrt_absolute_time();
|
||||
|
||||
@ -161,10 +161,10 @@ private:
|
||||
// If it doesn't fit, we have to split it into UINT16-1 chunks and the remaining
|
||||
// voltage for the subsequent field.
|
||||
// This won't work for voltages of more than 655 volts.
|
||||
const int num_fields_required = static_cast<int>(battery_status.voltage_filtered_v * 1000.f) / (UINT16_MAX - 1) + 1;
|
||||
const int num_fields_required = static_cast<int>(battery_status.voltage_v * 1000.f) / (UINT16_MAX - 1) + 1;
|
||||
|
||||
if (num_fields_required <= mavlink_cell_slots) {
|
||||
float remaining_voltage = battery_status.voltage_filtered_v * 1000.f;
|
||||
float remaining_voltage = battery_status.voltage_v * 1000.f;
|
||||
|
||||
for (int i = 0; i < num_fields_required - 1; ++i) {
|
||||
bat_msg.voltages[i] = UINT16_MAX - 1;
|
||||
|
||||
@ -166,7 +166,7 @@ private:
|
||||
const battery_status_s &lowest_battery = battery_status[lowest_battery_index];
|
||||
|
||||
if (lowest_battery.connected) {
|
||||
msg.voltage_battery = lowest_battery.voltage_filtered_v * 1000.0f;
|
||||
msg.voltage_battery = lowest_battery.voltage_v * 1000.0f;
|
||||
msg.current_battery = lowest_battery.current_a * 100.0f;
|
||||
msg.battery_remaining = ceilf(lowest_battery.remaining * 100.0f);
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user