From 799f910ca9a4fd2cf6a415970850c919ada712ee Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Fri, 19 Sep 2025 09:06:01 +1000 Subject: [PATCH] uORB message layout fixes (#25581) * uORB message layout fixes * Apply suggestions from code review --------- Co-authored-by: PX4BuildBot --- msg/versioned/ActuatorMotors.msg | 4 +- msg/versioned/ActuatorServos.msg | 2 +- msg/versioned/ArmingCheckReply.msg | 40 ++++----- msg/versioned/ArmingCheckRequest.msg | 8 +- msg/versioned/BatteryStatus.msg | 121 ++++++++++++++------------- 5 files changed, 88 insertions(+), 87 deletions(-) diff --git a/msg/versioned/ActuatorMotors.msg b/msg/versioned/ActuatorMotors.msg index 04b8ebbb4e..d165c5c1cb 100644 --- a/msg/versioned/ActuatorMotors.msg +++ b/msg/versioned/ActuatorMotors.msg @@ -8,9 +8,9 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) diff --git a/msg/versioned/ActuatorServos.msg b/msg/versioned/ActuatorServos.msg index 30b1b359b9..c547998d1c 100644 --- a/msg/versioned/ActuatorServos.msg +++ b/msg/versioned/ActuatorServos.msg @@ -9,4 +9,4 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. diff --git a/msg/versioned/ArmingCheckReply.msg b/msg/versioned/ArmingCheckReply.msg index 7ba4ad7bf3..b39649641f 100644 --- a/msg/versioned/ArmingCheckReply.msg +++ b/msg/versioned/ArmingCheckReply.msg @@ -1,4 +1,4 @@ -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -11,33 +11,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/msg/versioned/ArmingCheckRequest.msg b/msg/versioned/ArmingCheckRequest.msg index 42d56bdf51..df12a79d35 100644 --- a/msg/versioned/ArmingCheckRequest.msg +++ b/msg/versioned/ArmingCheckRequest.msg @@ -1,4 +1,4 @@ -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -9,8 +9,8 @@ uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 39f75ed611..94926ac3a2 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -7,72 +7,73 @@ uint32 MESSAGE_VERSION = 1 uint8 MAX_INSTANCES = 4 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is 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] Scaling factor to compensate for lower actuation power caused by voltage sag -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 +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is 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] Scaling factor to compensate for lower actuation power caused by voltage sag +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 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] Capacity of the battery when fully charged -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 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 +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +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 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 +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] 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 +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 +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 this as last element +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 this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] 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 +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