Skip to content

Commit eccfb18

Browse files
MaEtUgRsfuhrer
authored andcommitted
battery_status message: remove serial_number which is now in battery_info message
1 parent 1d86ede commit eccfb18

File tree

4 files changed

+195
-2
lines changed

4 files changed

+195
-2
lines changed
Lines changed: 79 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
# Battery status
2+
#
3+
# Battery status information for up to 4 battery instances.
4+
# These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
5+
# Battery instance information is also logged and streamed in MAVLink telemetry.
6+
7+
uint32 MESSAGE_VERSION = 0
8+
uint8 MAX_INSTANCES = 4
9+
10+
uint64 timestamp # [us] Time since system start
11+
bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold.
12+
float32 voltage_v # [V] [@invalid 0] Battery voltage
13+
float32 current_a # [A] [@invalid -1] Battery current
14+
float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight)
15+
float32 discharged_mah # [mAh] [@invalid -1] Discharged amount
16+
float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity
17+
float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag
18+
float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load
19+
float32 temperature # [°C] [@invalid NaN] Temperature of the battery
20+
uint8 cell_count # [@invalid 0] Number of cells
21+
22+
23+
uint8 source # [@enum SOURCE] Battery source
24+
uint8 SOURCE_POWER_MODULE = 0 # Power module
25+
uint8 SOURCE_EXTERNAL = 1 # External
26+
uint8 SOURCE_ESCS = 2 # ESCs
27+
28+
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
29+
uint16 capacity # [mAh] Capacity of the battery when fully charged
30+
uint16 cycle_count # Number of discharge cycles the battery has experienced
31+
uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge
32+
uint16 serial_number # Serial number of the battery pack
33+
uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
34+
uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity
35+
uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation
36+
uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed
37+
uint16 interface_error # Interface error counter
38+
39+
float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages
40+
float32 max_cell_voltage_delta # Max difference between individual cell voltages
41+
42+
bool is_powering_off # Power off event imminent indication, false if unknown
43+
bool is_required # Set if the battery is explicitly required before arming
44+
45+
uint8 warning # [@enum WARNING STATE] Current battery warning
46+
uint8 WARNING_NONE = 0 # No battery low voltage warning active
47+
uint8 WARNING_LOW = 1 # Low voltage warning
48+
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately
49+
uint8 WARNING_EMERGENCY = 3 # Immediate landing required
50+
uint8 WARNING_FAILED = 4 # Battery has failed completely
51+
uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field
52+
uint8 STATE_CHARGING = 7 # Battery is charging
53+
54+
uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication
55+
uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
56+
uint8 FAULT_SPIKES = 1 # Voltage spikes
57+
uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed
58+
uint8 FAULT_OVER_CURRENT = 3 # Over-current
59+
uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature
60+
uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
61+
uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)
62+
uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
63+
uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
64+
uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem
65+
uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
66+
uint8 FAULT_COUNT = 11 # Counter. Keep this as last element
67+
68+
float32 full_charge_capacity_wh # [Wh] Compensated battery capacity
69+
float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining
70+
uint16 over_discharge_count # Number of battery overdischarge
71+
float32 nominal_voltage # [V] Nominal voltage of the battery pack
72+
73+
float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate
74+
float32 ocv_estimate # [V] Open circuit voltage estimate
75+
float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate
76+
float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate
77+
float32 voltage_prediction # [V] Predicted voltage
78+
float32 prediction_error # [V] Prediction error
79+
float32 estimation_covariance_norm # Norm of the covariance matrix

msg/translation_node/translations/all_translations.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
#include "translation_airspeed_validated_v1.h"
1010
#include "translation_arming_check_reply_v1.h"
11+
#include "translation_battery_status_v1.h"
1112
#include "translation_event_v1.h"
1213
#include "translation_vehicle_attitude_setpoint_v1.h"
1314
#include "translation_vehicle_status_v1.h"
Lines changed: 114 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,114 @@
1+
/****************************************************************************
2+
* Copyright (c) 2025 PX4 Development Team.
3+
* SPDX-License-Identifier: BSD-3-Clause
4+
****************************************************************************/
5+
#pragma once
6+
7+
// Translate BatteryStatus v0 <--> v1
8+
#include <px4_msgs_old/msg/battery_status_v0.hpp>
9+
#include <px4_msgs/msg/battery_status.hpp>
10+
11+
class BatteryStatusV1Translation {
12+
public:
13+
using MessageOlder = px4_msgs_old::msg::BatteryStatusV0;
14+
static_assert(MessageOlder::MESSAGE_VERSION == 0);
15+
16+
using MessageNewer = px4_msgs::msg::BatteryStatus;
17+
static_assert(MessageNewer::MESSAGE_VERSION == 1);
18+
19+
static constexpr const char* kTopic = "fmu/out/battery_status";
20+
21+
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) {
22+
msg_newer.timestamp = msg_older.timestamp;
23+
msg_newer.connected = msg_older.connected;
24+
msg_newer.voltage_v = msg_older.voltage_v;
25+
msg_newer.current_a = msg_older.current_a;
26+
msg_newer.current_average_a = msg_older.current_average_a;
27+
msg_newer.discharged_mah = msg_older.discharged_mah;
28+
msg_newer.remaining = msg_older.remaining;
29+
msg_newer.scale = msg_older.scale;
30+
msg_newer.time_remaining_s = msg_older.time_remaining_s;
31+
msg_newer.temperature = msg_older.temperature;
32+
msg_newer.cell_count = msg_older.cell_count;
33+
msg_newer.source = msg_older.source;
34+
msg_newer.priority = msg_older.priority;
35+
msg_newer.capacity = msg_older.capacity;
36+
msg_newer.cycle_count = msg_older.cycle_count;
37+
msg_newer.average_time_to_empty = msg_older.average_time_to_empty;
38+
// The serial number moved to the battery_info message and is char[32] instead of uint16
39+
msg_newer.manufacture_date = msg_older.manufacture_date;
40+
msg_newer.state_of_health = msg_older.state_of_health;
41+
msg_newer.max_error = msg_older.max_error;
42+
msg_newer.id = msg_older.id;
43+
msg_newer.interface_error = msg_older.interface_error;
44+
45+
for (int i = 0; i < 14; ++i) {
46+
msg_newer.voltage_cell_v[i] = msg_older.voltage_cell_v[i];
47+
}
48+
49+
msg_newer.max_cell_voltage_delta = msg_older.max_cell_voltage_delta;
50+
msg_newer.is_powering_off = msg_older.is_powering_off;
51+
msg_newer.is_required = msg_older.is_required;
52+
msg_newer.warning = msg_older.warning;
53+
msg_newer.faults = msg_older.faults;
54+
msg_newer.full_charge_capacity_wh = msg_older.full_charge_capacity_wh;
55+
msg_newer.remaining_capacity_wh = msg_older.remaining_capacity_wh;
56+
msg_newer.over_discharge_count = msg_older.over_discharge_count;
57+
msg_newer.nominal_voltage = msg_older.nominal_voltage;
58+
msg_newer.internal_resistance_estimate = msg_older.internal_resistance_estimate;
59+
msg_newer.ocv_estimate = msg_older.ocv_estimate;
60+
msg_newer.ocv_estimate_filtered = msg_older.ocv_estimate_filtered;
61+
msg_newer.volt_based_soc_estimate = msg_older.volt_based_soc_estimate;
62+
msg_newer.voltage_prediction = msg_older.voltage_prediction;
63+
msg_newer.prediction_error = msg_older.prediction_error;
64+
msg_newer.estimation_covariance_norm = msg_older.estimation_covariance_norm;
65+
}
66+
67+
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) {
68+
msg_older.timestamp = msg_newer.timestamp;
69+
msg_older.connected = msg_newer.connected;
70+
msg_older.voltage_v = msg_newer.voltage_v;
71+
msg_older.current_a = msg_newer.current_a;
72+
msg_older.current_average_a = msg_newer.current_average_a;
73+
msg_older.discharged_mah = msg_newer.discharged_mah;
74+
msg_older.remaining = msg_newer.remaining;
75+
msg_older.scale = msg_newer.scale;
76+
msg_older.time_remaining_s = msg_newer.time_remaining_s;
77+
msg_older.temperature = msg_newer.temperature;
78+
msg_older.cell_count = msg_newer.cell_count;
79+
msg_older.source = msg_newer.source;
80+
msg_older.priority = msg_newer.priority;
81+
msg_older.capacity = msg_newer.capacity;
82+
msg_older.cycle_count = msg_newer.cycle_count;
83+
msg_older.average_time_to_empty = msg_newer.average_time_to_empty;
84+
msg_older.serial_number = 0; // The serial number moved to the battery_info message and is char[32] instead of uint16
85+
msg_older.manufacture_date = msg_newer.manufacture_date;
86+
msg_older.state_of_health = msg_newer.state_of_health;
87+
msg_older.max_error = msg_newer.max_error;
88+
msg_older.id = msg_newer.id;
89+
msg_older.interface_error = msg_newer.interface_error;
90+
91+
for (int i = 0; i < 14; ++i) {
92+
msg_older.voltage_cell_v[i] = msg_newer.voltage_cell_v[i];
93+
}
94+
95+
msg_older.max_cell_voltage_delta = msg_newer.max_cell_voltage_delta;
96+
msg_older.is_powering_off = msg_newer.is_powering_off;
97+
msg_older.is_required = msg_newer.is_required;
98+
msg_older.warning = msg_newer.warning;
99+
msg_older.faults = msg_newer.faults;
100+
msg_older.full_charge_capacity_wh = msg_newer.full_charge_capacity_wh;
101+
msg_older.remaining_capacity_wh = msg_newer.remaining_capacity_wh;
102+
msg_older.over_discharge_count = msg_newer.over_discharge_count;
103+
msg_older.nominal_voltage = msg_newer.nominal_voltage;
104+
msg_older.internal_resistance_estimate = msg_newer.internal_resistance_estimate;
105+
msg_older.ocv_estimate = msg_newer.ocv_estimate;
106+
msg_older.ocv_estimate_filtered = msg_newer.ocv_estimate_filtered;
107+
msg_older.volt_based_soc_estimate = msg_newer.volt_based_soc_estimate;
108+
msg_older.voltage_prediction = msg_newer.voltage_prediction;
109+
msg_older.prediction_error = msg_newer.prediction_error;
110+
msg_older.estimation_covariance_norm = msg_newer.estimation_covariance_norm;
111+
}
112+
};
113+
114+
REGISTER_TOPIC_TRANSLATION_DIRECT(BatteryStatusV1Translation);

msg/versioned/BatteryStatus.msg

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
# These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
55
# Battery instance information is also logged and streamed in MAVLink telemetry.
66

7-
uint32 MESSAGE_VERSION = 0
7+
uint32 MESSAGE_VERSION = 1
88
uint8 MAX_INSTANCES = 4
99

1010
uint64 timestamp # [us] Time since system start
@@ -29,7 +29,6 @@ uint8 priority # Zero based priority is the connection on the Power Controller V
2929
uint16 capacity # [mAh] Capacity of the battery when fully charged
3030
uint16 cycle_count # Number of discharge cycles the battery has experienced
3131
uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge
32-
uint16 serial_number # Serial number of the battery pack
3332
uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
3433
uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity
3534
uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation

0 commit comments

Comments
 (0)