Skip to content

Commit 288bcc6

Browse files
committed
Units/enum/range before description
1 parent 8a93867 commit 288bcc6

1 file changed

Lines changed: 51 additions & 51 deletions

File tree

msg/versioned/BatteryStatus.msg

Lines changed: 51 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -6,76 +6,76 @@
66

77
uint32 MESSAGE_VERSION = 0
88

9-
uint64 timestamp # Time since system start [us]
9+
uint64 timestamp # [us] Time since system start.
1010
bool connected # Whether or not a battery is connected, based on a voltage threshold
11-
float32 voltage_v # Battery voltage [V] [@invalid 0]
12-
float32 current_a # Battery current [A] [@invalid -1]
13-
float32 current_average_a # Battery current average (for FW average in level flight) [A] [@invalid -1]
14-
float32 discharged_mah # Discharged amount [mAh] [@invalid -1]
15-
float32 remaining # Remaining capacity [@range 0,1] [@invalid -1]
16-
float32 scale # Power scaling factor [@range 1,] [@invalid -1]
17-
float32 time_remaining_s # Predicted time remaining until battery is empty under previous averaged load [s] [@invalid NaN]
18-
float32 temperature # Temperature of the battery [°C] [@invalid NaN]
19-
uint8 cell_count # Number of cells [@invalid 0]
11+
float32 voltage_v # [V] [@invalid 0] Battery voltage.
12+
float32 current_a # [A] [@invalid -1] Battery current.
13+
float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight).
14+
float32 discharged_mah # [mAh] [@invalid -1] Discharged amount.
15+
float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity.
16+
float32 scale # [@range 1,] [@invalid -1] Power scaling factor.
17+
float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load.
18+
float32 temperature # [°C] [@invalid NaN] Temperature of the battery.
19+
uint8 cell_count # [@invalid 0] Number of cells.
2020

2121

22-
uint8 source # Battery source [@enum SOURCE]
23-
uint8 SOURCE_POWER_MODULE = 0 # Power module
22+
uint8 source # [@enum SOURCE] Battery source.
23+
uint8 SOURCE_POWER_MODULE = 0 # Power module.
2424
uint8 SOURCE_EXTERNAL = 1 # External
2525
uint8 SOURCE_ESCS = 2 # ESCs
2626

2727
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
28-
uint16 capacity # Actual capacity of the battery [mAh]
29-
uint16 cycle_count # Number of discharge cycles the battery has experienced
30-
uint16 average_time_to_empty # Predicted remaining battery capacity based on the average rate of discharge [minutes]
31-
uint16 serial_number # Serial number of the battery pack
28+
uint16 capacity # [mAh] Actual capacity of the battery.
29+
uint16 cycle_count # Number of discharge cycles the battery has experienced.
30+
uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge.
31+
uint16 serial_number # Serial number of the battery pack.
3232
uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
33-
uint16 state_of_health # State of health. FullChargeCapacity/DesignCapacity [%] [@range 0, 100].
34-
uint16 max_error # Max error, expected margin of error in the state-of-charge calculation [%] [@range 1, 100]
33+
uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity.
34+
uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation.
3535
uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed.
36-
uint16 interface_error # Interface error counter
36+
uint16 interface_error # Interface error counter.
3737

38-
float32[14] voltage_cell_v # Battery individual cell voltages [V] [@invalid 0]
39-
float32 max_cell_voltage_delta # Max difference between individual cell voltages
38+
float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages.
39+
float32 max_cell_voltage_delta # Max difference between individual cell voltages.
4040

41-
bool is_powering_off # Power off event imminent indication, false if unknown
42-
bool is_required # Set if the battery is explicitly required before arming
41+
bool is_powering_off # Power off event imminent indication, false if unknown.
42+
bool is_required # Set if the battery is explicitly required before arming.
4343

44-
uint8 warning # Current battery warning [@enum WARNING STATE]
45-
uint8 WARNING_NONE = 0 # No battery low voltage warning active
46-
uint8 WARNING_LOW = 1 # Low voltage warning
47-
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately
48-
uint8 WARNING_EMERGENCY = 3 # Immediate landing required
49-
uint8 WARNING_FAILED = 4 # Battery has failed completely
44+
uint8 warning # [@enum WARNING STATE] Current battery warning.
45+
uint8 WARNING_NONE = 0 # No battery low voltage warning active.
46+
uint8 WARNING_LOW = 1 # Low voltage warning.
47+
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately.
48+
uint8 WARNING_EMERGENCY = 3 # Immediate landing required.
49+
uint8 WARNING_FAILED = 4 # Battery has failed completely.
5050

5151
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.
5252
uint8 STATE_CHARGING = 7 # Battery is charging
5353

54-
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. [@enum FAULT]
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
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.
6161
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
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.
6666
uint8 FAULT_COUNT = 11 # Counter - keep it as last element!
6767

6868
uint8 MAX_INSTANCES = 4
6969

70-
float32 full_charge_capacity_wh # The compensated battery capacity [Wh]
71-
float32 remaining_capacity_wh # The compensated battery capacity remaining [Wh]
72-
uint16 over_discharge_count # Number of battery overdischarge
73-
float32 nominal_voltage # Nominal voltage of the battery pack [V]
70+
float32 full_charge_capacity_wh # [Wh] The compensated battery capacity.
71+
float32 remaining_capacity_wh # [Wh] The compensated battery capacity remaining.
72+
uint16 over_discharge_count # Number of battery overdischarge.
73+
float32 nominal_voltage # [V] Nominal voltage of the battery pack.
7474

75-
float32 internal_resistance_estimate # Internal resistance per cell estimate [Ohm]
76-
float32 ocv_estimate # Open circuit voltage estimate [V]
77-
float32 ocv_estimate_filtered # Filtered open circuit voltage estimate [V]
78-
float32 volt_based_soc_estimate # Normalized volt based state of charge estimate [@range 0, 1]
79-
float32 voltage_prediction # Predicted voltage [V]
80-
float32 prediction_error # Prediction error [V]
81-
float32 estimation_covariance_norm # Norm of the covariance matrix
75+
float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate.
76+
float32 ocv_estimate # [V] Open circuit voltage estimate.
77+
float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate.
78+
float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate.
79+
float32 voltage_prediction # [V] Predicted voltage.
80+
float32 prediction_error # [V] Prediction error.
81+
float32 estimation_covariance_norm # Norm of the covariance matrix.

0 commit comments

Comments
 (0)