Skip to content

uORB docs parser #24977

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft
wants to merge 7 commits into
base: main
Choose a base branch
from
Draft

uORB docs parser #24977

wants to merge 7 commits into from

Conversation

hamishwillee
Copy link
Contributor

Now that we're working on a docs standard for UORB messages, it makes sense to generate better docs from them.

This is a draft parser that splits out the fields, enums, constants, description if present. It does not yet, but will also provide some hints when docs are missing stuff.

Not finished.

'uint32'
}

ALLOWED_UNITS = set(["m", "m/s", "rad", "rad/s", "rpm" ,"V", "A", "mA", "mAh", "W", "dBm", "s", "ms", "us", "Ohm", "MB", "Kb/s"])
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note, these are the allowed units so far.

@hamishwillee
Copy link
Contributor Author

@MaEtUgR FYI only, I'm still tweaking this, but for the latest Battery Status proposed, the message would look like this.


BatteryStatus (UORB message)

source file

Battery status.

Battery status information for up to four battery instances.
These are populated from power module device drivers, and one battery updated from MAVLink.
Battery instance information is also logged and streamed from MAVLink.

Fields

Name (type) Units Values Description invalid
timestamp (uint64) us Time since system start.
connected (bool) Whether or not a battery is connected, based on a voltage threshold
voltage_v (float32) V Battery voltage. 0
current_a (float32) A Battery current. -1
current_average_a (float32) A Battery current average (for FW average in level flight). -1
discharged_mah (float32) mAh Discharged amount. -1
remaining (float32) range: 0 - 1 Remaining capacity. -1
scale (float32) min: 1 Power scaling factor. -1
time_remaining_s (float32) s Predicted time remaining until battery is empty under previous averaged load. NaN
temperature (float32) °C Temperature of the battery. NaN
cell_count (uint8) Number of cells. 0
source (uint8) SOURCE Battery source.
priority (uint8) Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
capacity (uint16) mAh Actual capacity of the battery.
cycle_count (uint16) Number of discharge cycles the battery has experienced.
average_time_to_empty (uint16) minutes Predicted remaining battery capacity based on the average rate of discharge.
serial_number (uint16) Serial number of the battery pack.
manufacture_date (uint16) Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
state_of_health (uint16) % range: 0 - 100 State of health. FullChargeCapacity/DesignCapacity.
max_error (uint16) % range: 1 - 100 Max error, expected margin of error in the state-of-charge calculation.
id (uint8) ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed.
interface_error (uint16) Interface error counter.
voltage_cell_v (float32[14]) V Battery individual cell voltages. 0
max_cell_voltage_delta (float32) Max difference between individual cell voltages.
is_powering_off (bool) Power off event imminent indication, false if unknown.
is_required (bool) Set if the battery is explicitly required before arming.
warning (uint8) WARNING STATE Current battery warning.
faults (uint16) FAULT Smart battery supply status/fault flags (bitmask) for health indication.
full_charge_capacity_wh (float32) Wh The compensated battery capacity.
remaining_capacity_wh (float32) Wh The compensated battery capacity remaining.
over_discharge_count (uint16) Number of battery overdischarge.
nominal_voltage (float32) V Nominal voltage of the battery pack.
internal_resistance_estimate (float32) Ohm Internal resistance per cell estimate.
ocv_estimate (float32) V Open circuit voltage estimate.
ocv_estimate_filtered (float32) V Filtered open circuit voltage estimate.
volt_based_soc_estimate (float32) range: 0 - 1 Normalized volt based state of charge estimate.
voltage_prediction (float32) V Predicted voltage.
prediction_error (float32) V Prediction error.
estimation_covariance_norm (float32) Norm of the covariance matrix.

Enums

SOURCE {#SOURCE}

Name (type) Value Description
SOURCE_POWER_MODULE (uint8) 0 Power module.
SOURCE_EXTERNAL (uint8) 1 External.
SOURCE_ESCS (uint8) 2 ESCs.

WARNING {#WARNING}

Name (type) Value Description
WARNING_NONE (uint8) 0 No battery low voltage warning active.
WARNING_LOW (uint8) 1 Low voltage warning.
WARNING_CRITICAL (uint8) 2 Critical voltage, return / abort immediately.
WARNING_EMERGENCY (uint8) 3 Immediate landing required.
WARNING_FAILED (uint8) 4 Battery has failed completely.

STATE {#STATE}

Name (type) Value Description
STATE_UNHEALTHY (uint8) 6 Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
STATE_CHARGING (uint8) 7 Battery is charging

FAULT {#FAULT}

Name (type) Value Description
FAULT_DEEP_DISCHARGE (uint8) 0 Battery has deep discharged.
FAULT_SPIKES (uint8) 1 Voltage spikes.
FAULT_CELL_FAIL (uint8) 2 One or more cells have failed.
FAULT_OVER_CURRENT (uint8) 3 Over-current.
FAULT_OVER_TEMPERATURE (uint8) 4 Over-temperature.
FAULT_UNDER_TEMPERATURE (uint8) 5 Under-temperature fault.
FAULT_INCOMPATIBLE_VOLTAGE (uint8) 6 Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
FAULT_INCOMPATIBLE_FIRMWARE (uint8) 7 Battery firmware is not compatible with current autopilot firmware.
FAULT_INCOMPATIBLE_MODEL (uint8) 8 Battery model is not supported by the system.
FAULT_HARDWARE_FAILURE (uint8) 9 hardware problem.
FAULT_FAILED_TO_ARM (uint8) 10 Battery had a problem while arming.
FAULT_COUNT (uint8) 11 Counter - keep it as last element!

Constants

Name (type) Value Description
MESSAGE_VERSION (uint32) 0
MAX_INSTANCES (uint8) 4

Source

Click here to see original file

# Battery status.
#
# Battery status information for up to four battery instances.
# These are populated from power module device drivers, and one battery updated from MAVLink.
# Battery instance information is also logged and streamed from MAVLink.

uint32 MESSAGE_VERSION = 0

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


uint8 source # [@enum SOURCE] Battery source.
uint8 SOURCE_POWER_MODULE = 0 # Power module.
uint8 SOURCE_EXTERNAL = 1 # External.
uint8 SOURCE_ESCS = 2 # ESCs.

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

float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages.
float32 max_cell_voltage_delta # Max difference between individual cell voltages.

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

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

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

uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication.
uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged.
uint8 FAULT_SPIKES = 1 # Voltage spikes.
uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed.
uint8 FAULT_OVER_CURRENT = 3 # Over-current.
uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature.
uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault.
uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware.
uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system.
uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem.
uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming.
uint8 FAULT_COUNT = 11 # Counter - keep it as last element!

uint8 MAX_INSTANCES = 4

float32 full_charge_capacity_wh # [Wh] The compensated battery capacity.
float32 remaining_capacity_wh # [Wh] The compensated battery capacity remaining.
uint16 over_discharge_count # Number of battery overdischarge.
float32 nominal_voltage # [V] Nominal voltage of the battery pack.

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

@hamishwillee hamishwillee force-pushed the uorb_msg_doc_parser branch 2 times, most recently from daec29f to 6dca8a0 Compare June 11, 2025 05:18
@hamishwillee hamishwillee force-pushed the uorb_msg_doc_parser branch from dd18024 to 44a1944 Compare June 18, 2025 02:27
@hamishwillee hamishwillee added the Documentation 📑 Anything improving the documentation of the code / ecosystem label Jun 26, 2025
@hamishwillee hamishwillee force-pushed the uorb_msg_doc_parser branch from 91903f3 to bfcd105 Compare July 16, 2025 06:45
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Documentation 📑 Anything improving the documentation of the code / ecosystem
Projects
None yet
Development

Successfully merging this pull request may close these issues.

1 participant