Add uorb message meta

This commit is contained in:
Hamish Willee
2025-07-24 09:57:59 +10:00
parent efb4ff3353
commit a84d085ce7
35 changed files with 617 additions and 292 deletions

View File

@@ -522,6 +522,7 @@
- [Airspeed](msg_docs/Airspeed.md)
- [AirspeedWind](msg_docs/AirspeedWind.md)
- [AutotuneAttitudeControlStatus](msg_docs/AutotuneAttitudeControlStatus.md)
- [BatteryInfo](msg_docs/BatteryInfo.md)
- [ButtonEvent](msg_docs/ButtonEvent.md)
- [CameraCapture](msg_docs/CameraCapture.md)
- [CameraStatus](msg_docs/CameraStatus.md)
@@ -540,6 +541,7 @@
- [DifferentialPressure](msg_docs/DifferentialPressure.md)
- [DistanceSensor](msg_docs/DistanceSensor.md)
- [DistanceSensorModeChangeRequest](msg_docs/DistanceSensorModeChangeRequest.md)
- [DronecanNodeStatus](msg_docs/DronecanNodeStatus.md)
- [Ekf2Timestamps](msg_docs/Ekf2Timestamps.md)
- [EscReport](msg_docs/EscReport.md)
- [EscStatus](msg_docs/EscStatus.md)
@@ -712,6 +714,10 @@
- [Wind](msg_docs/Wind.md)
- [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md)
- [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md)
- [ArmingCheckReplyV0](msg_docs/ArmingCheckReplyV0.md)
- [BatteryStatusV0](msg_docs/BatteryStatusV0.md)
- [EventV0](msg_docs/EventV0.md)
- [HomePositionV0](msg_docs/HomePositionV0.md)
- [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](mavlink/index.md)

View File

@@ -1,7 +1,5 @@
# ActionRequest (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActionRequest.msg)
```c
@@ -16,6 +14,7 @@ uint8 ACTION_KILL = 4
uint8 ACTION_SWITCH_MODE = 5
uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7
uint8 ACTION_TERMINATE = 8
uint8 source # how the request was triggered
uint8 SOURCE_STICK_GESTURE = 0

View File

@@ -2,23 +2,27 @@
Motor control message
Normalised thrust setpoint for up to 12 motors.
Published by the vehicle's allocation and consumed by the ESC protocol drivers e.g. PWM, DSHOT, UAVCAN.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg)
```c
# Motor control message
#
# Normalised thrust setpoint for up to 12 motors.
# Published by the vehicle's allocation and consumed by the ESC protocol drivers e.g. PWM, DSHOT, UAVCAN.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
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 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], where 1 means maximum positive thrust,
# -1 maximum negative (if not supported by the output, <0 maps to NaN),
# and 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)
```

View File

@@ -2,19 +2,23 @@
Servo control message
Normalised output setpoint for up to 8 servos.
Published by the vehicle's allocation and consumed by the actuator output drivers.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg)
```c
# Servo control message
#
# Normalised output setpoint for up to 8 servos.
# Published by the vehicle's allocation and consumed by the actuator output drivers.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
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], where 1 means maximum positive position,
# -1 maximum negative,
# and 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.
```

View File

@@ -1,17 +1,22 @@
# Airspeed (UORB message)
Airspeed data from sensors
This is published by airspeed sensor drivers, CAN airspeed sensors, simulators.
It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Airspeed.msg)
```c
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample
# Airspeed data from sensors
#
# This is published by airspeed sensor drivers, CAN airspeed sensors, simulators.
# It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers.
float32 indicated_airspeed_m_s # indicated airspeed in m/s
float32 true_airspeed_m_s # true filtered airspeed in m/s
float32 confidence # confidence value from 0 to 1 for this sensor
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Timestamp of the raw data
float32 indicated_airspeed_m_s # [m/s] Indicated airspeed
float32 true_airspeed_m_s # [m/s] True airspeed
float32 confidence # [@range 0,1] Confidence value for this sensor
```

View File

@@ -1,43 +1,59 @@
# ArmingCheckReply (UORB message)
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).
The request is sent regularly to all registered ROS modes, even while armed, so that the FMU always knows and can forward the current state.
Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply).
The message is not used by internal/FMU components, as their mode requirements are known at compile time.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg)
```c
uint32 MESSAGE_VERSION = 0
# 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).
# The request is sent regularly to all registered ROS modes, even while armed, so that the FMU always knows and can forward the current state.
#
# Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply).
# The message is not used by internal/FMU components, as their mode requirements are known at compile time.
uint64 timestamp # time since system start (microseconds)
uint32 MESSAGE_VERSION = 1
uint8 request_id
uint8 registration_id
uint64 timestamp # [us] Time since system start.
uint8 HEALTH_COMPONENT_INDEX_NONE = 0
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 # HEALTH_COMPONENT_INDEX_*
bool health_component_is_present
bool health_component_warning
bool health_component_error
uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies.
bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run
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).
uint8 num_events
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.
Event[5] events
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).
# Mode requirements
bool mode_req_angular_velocity
bool mode_req_attitude
bool mode_req_local_alt
bool mode_req_local_position
bool mode_req_local_position_relaxed
bool mode_req_global_position
bool mode_req_mission
bool mode_req_home_position
bool mode_req_prevent_arming
bool mode_req_manual_control
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
uint8 ORB_QUEUE_LENGTH = 4 #
```

View File

@@ -0,0 +1,41 @@
# ArmingCheckReplyV0 (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg)
```c
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint8 request_id
uint8 registration_id
uint8 HEALTH_COMPONENT_INDEX_NONE = 0
uint8 health_component_index # HEALTH_COMPONENT_INDEX_*
bool health_component_is_present
bool health_component_warning
bool health_component_error
bool can_arm_and_run # whether arming is possible, and if it's a navigation mode, if it can run
uint8 num_events
EventV0[5] events
# Mode requirements
bool mode_req_angular_velocity
bool mode_req_attitude
bool mode_req_local_alt
bool mode_req_local_position
bool mode_req_local_position_relaxed
bool mode_req_global_position
bool mode_req_mission
bool mode_req_home_position
bool mode_req_prevent_arming
bool mode_req_manual_control
uint8 ORB_QUEUE_LENGTH = 4
```

View File

@@ -1,16 +1,30 @@
# ArmingCheckRequest (UORB message)
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.
The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations.
The reply will include the published request_id, allowing correlation of all arming check information for a particular request.
The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply).
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg)
```c
# 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.
# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations.
#
# The reply will include the published request_id, allowing correlation of all arming check information for a particular request.
# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply).
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # [us] Time since system start.
# broadcast message to request all registered arming checks to be reported
uint8 request_id
uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages.
```

View File

@@ -0,0 +1,21 @@
# BatteryInfo (UORB message)
Battery information
Static or near-invariant battery information.
Should be streamed at low rate.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/BatteryInfo.msg)
```c
# Battery information
#
# Static or near-invariant battery information.
# Should be streamed at low rate.
uint64 timestamp # [us] Time since system start
uint8 id # Must match the id in the battery_status message for the same battery
char[32] serial_number # [@invalid 0 All bytes] Serial number of the battery pack in ASCII characters, 0 terminated
```

View File

@@ -1,83 +1,91 @@
# BatteryStatus (UORB message)
Battery status
Battery status information for up to 4 battery instances.
These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
Battery instance information is also logged and streamed in MAVLink telemetry.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/BatteryStatus.msg)
```c
uint32 MESSAGE_VERSION = 0
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 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
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown
float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown
float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown
uint8 SOURCE_POWER_MODULE = 0
uint8 SOURCE_EXTERNAL = 1
uint8 SOURCE_ESCS = 2
uint8 source # Battery source
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
uint16 cycle_count # number of discharge cycles the battery has experienced
uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min
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 + (Year1980)×512
uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%.
uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100%
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 # Battery individual cell voltages, 0 if unknown
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_NONE = 0 # no battery low voltage warning active
uint8 WARNING_LOW = 1 # warning of low voltage
uint8 WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
uint8 WARNING_EMERGENCY = 3 # immediate landing required
uint8 WARNING_FAILED = 4 # the 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 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!
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint8 warning # Current battery warning
# Battery status
#
# Battery status information for up to 4 battery instances.
# These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
# Battery instance information is also logged and streamed in MAVLink telemetry.
uint32 MESSAGE_VERSION = 1
uint8 MAX_INSTANCES = 4
float32 full_charge_capacity_wh # The compensated battery capacity
float32 remaining_capacity_wh # The compensated battery capacity remaining
uint16 over_discharge_count # Number of battery overdischarge
float32 nominal_voltage # Nominal voltage of the battery pack
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
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 # [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
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 + (Year1980)×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 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 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
```

View File

@@ -0,0 +1,92 @@
# BatteryStatusV0 (UORB message)
Battery status
Battery status information for up to 4 battery instances.
These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
Battery instance information is also logged and streamed in MAVLink telemetry.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/BatteryStatusV0.msg)
```c
# Battery status
#
# Battery status information for up to 4 battery instances.
# These are populated from power module and smart battery device drivers, and one battery updated from MAVLink.
# Battery instance information is also logged and streamed in MAVLink telemetry.
uint32 MESSAGE_VERSION = 0
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
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 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 + (Year1980)×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 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 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
```

View File

@@ -11,39 +11,39 @@ This is currently used only for logging cell status from MAVLink.
#
# This is currently used only for logging cell status from MAVLink.
uint64 timestamp # [us] Time since system start.
uint64 timestamp # [us] Time since system start
uint16 status # [@enum STATUS_FLAG] Status bitmap.
uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable.
uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable.
uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized.
uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked.
uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down.
uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state.
uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state.
uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections.
uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register.
uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use.
uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated.
uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered.
uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected.
uint16 status # [@enum STATUS_FLAG] Status bitmap
uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable
uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable
uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized
uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked
uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down
uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state
uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state
uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections
uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register
uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use
uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated
uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered
uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected
uint8 failure_reason # [@enum FAILURE_REASON] Failure reason.
uint8 FAILURE_REASON_NONE = 0 # No error.
uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown.
uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing.
uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection.
uint8 failure_reason # [@enum FAILURE_REASON] Failure reason
uint8 FAILURE_REASON_NONE = 0 # No error
uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown
uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing
uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection
uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type.
uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type
uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None
uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM
uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA
uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA
uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE
uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value.
uint16 mcc # [@invalid UINT16_MAX] Mobile country code.
uint16 mnc # [@invalid UINT16_MAX] Mobile network code.
uint16 lac # [@invalid 0] Location area code.
uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value
uint16 mcc # [@invalid UINT16_MAX] Mobile country code
uint16 mnc # [@invalid UINT16_MAX] Mobile network code
uint16 lac # [@invalid 0] Location area code
```

View File

@@ -0,0 +1,48 @@
# DronecanNodeStatus (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DronecanNodeStatus.msg)
```c
uint64 timestamp # time since system start (microseconds)
uint16 node_id # The node ID which this data comes from
# From the uavcan.protocol.NodeStatus message
uint32 uptime_sec # Node uptime
#
# Abstract node health.
#
uint8 HEALTH_OK = 0 # The node is functioning properly.
uint8 HEALTH_WARNING = 1 # A critical parameter went out of range or the node encountered a minor failure.
uint8 HEALTH_ERROR = 2 # The node encountered a major failure.
uint8 HEALTH_CRITICAL = 3 # The node suffered a fatal malfunction.
uint8 health
#
# Current mode.
#
# Mode OFFLINE can be actually reported by the node to explicitly inform other network
# participants that the sending node is about to shutdown. In this case other nodes will not
# have to wait OFFLINE_TIMEOUT_MS before they detect that the node is no longer available.
#
# Reserved values can be used in future revisions of the specification.
#
uint8 MODE_OPERATIONAL = 0 # Normal operating mode.
uint8 MODE_INITIALIZATION = 1 # Initialization is in progress; this mode is entered immediately after startup.
uint8 MODE_MAINTENANCE = 2 # E.g. calibration, the bootloader is running, etc.
uint8 MODE_SOFTWARE_UPDATE = 3 # New software/firmware is being loaded.
uint8 MODE_OFFLINE = 7 # The node is no longer available.
uint8 mode
#
# Not used currently, keep zero when publishing, ignore when receiving.
#
uint8 sub_mode
#
# Optional, vendor-specific node status code, e.g. a fault code or a status bitmask.
#
uint16 vendor_specific_status_code
```

View File

@@ -2,10 +2,12 @@
Events interface
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Event.msg)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Event.msg)
```c
# Events interface
uint32 MESSAGE_VERSION = 1
uint64 timestamp # time since system start (microseconds)
uint32 id # Event ID

View File

@@ -0,0 +1,24 @@
# EventV0 (UORB message)
this message is required here in the msg_old folder because other msg are depending on it
Events interface
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/EventV0.msg)
```c
# this message is required here in the msg_old folder because other msg are depending on it
# Events interface
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint32 id # Event ID
uint16 event_sequence # Event sequence number
uint8[25] arguments # (optional) arguments, depend on event id
uint8 log_levels # Log levels: 4 bits MSB: internal, 4 bits LSB: external
uint8 ORB_QUEUE_LENGTH = 16
```

View File

@@ -2,7 +2,7 @@
Input flags for the failsafe state machine set by the arming & health checks.
Flags must be named such that false == no failure (e.g. _invalid, _unhealthy, _lost)
Flags must be named such that false == no failure (e.g. \_invalid, \_unhealthy, \_lost)
The flag comments are used as label for the failsafe state machine simulation
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailsafeFlags.msg)
@@ -22,6 +22,7 @@ uint32 mode_req_local_alt
uint32 mode_req_local_position
uint32 mode_req_local_position_relaxed
uint32 mode_req_global_position
uint32 mode_req_global_position_relaxed
uint32 mode_req_mission
uint32 mode_req_offboard_signal
uint32 mode_req_home_position
@@ -39,6 +40,7 @@ bool local_position_invalid # Local position estimate invalid
bool local_position_invalid_relaxed # Local position with reduced accuracy requirements invalid (e.g. flying with optical flow)
bool local_velocity_invalid # Local velocity estimate invalid
bool global_position_invalid # Global position estimate invalid
bool global_position_invalid_relaxed # Global position estimate invalid with relaxed accuracy requirements
bool auto_mission_missing # No mission available
bool offboard_control_signal_lost # Offboard signal lost
bool home_position_invalid # No home position available

View File

@@ -7,7 +7,7 @@ GPS home position in WGS84 coordinates.
```c
# GPS home position in WGS84 coordinates.
uint32 MESSAGE_VERSION = 0
uint32 MESSAGE_VERSION = 1
uint64 timestamp # time since system start (microseconds)
@@ -19,6 +19,8 @@ float32 x # X coordinate in meters
float32 y # Y coordinate in meters
float32 z # Z coordinate in meters
float32 roll # Pitch angle in radians
float32 pitch # Roll angle in radians
float32 yaw # Yaw angle in radians
bool valid_alt # true when the altitude has been set

View File

@@ -0,0 +1,32 @@
# HomePositionV0 (UORB message)
GPS home position in WGS84 coordinates.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/HomePositionV0.msg)
```c
# GPS home position in WGS84 coordinates.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude in degrees
float64 lon # Longitude in degrees
float32 alt # Altitude in meters (AMSL)
float32 x # X coordinate in meters
float32 y # Y coordinate in meters
float32 z # Z coordinate in meters
float32 yaw # Yaw angle in radians
bool valid_alt # true when the altitude has been set
bool valid_hpos # true when the latitude and longitude have been set
bool valid_lpos # true when the local position (xyz) has been set
bool manual_home # true when home position was set manually
uint32 update_count # update counter of the home position
```

View File

@@ -1,16 +1,14 @@
# InternalCombustionEngineControl (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineControl.msg)
```c
uint64 timestamp # time since system start (microseconds)
bool ignition_on # activate/deactivate ignition (Spark Plug)
float32 throttle_control # [0,1] - Motor should idle with 0. Includes slew rate if enabled.
float32 choke_control # [0,1] - 1 fully closes the air inlet.
float32 starter_engine_control # [0,1] - control value for electric starter motor.
bool ignition_on # activate/deactivate ignition (spark plug)
float32 throttle_control # setpoint for throttle actuator, with slew rate if enabled, idles with 0 [norm] [@range 0,1] [@uncontrolled NAN to stop motor]
float32 choke_control # setpoint for choke actuator, 1: fully closed [norm] [@range 0,1]
float32 starter_engine_control # setpoint for (electric) starter motor [norm] [@range 0,1]
uint8 user_request # user intent for the ICE being on/off

View File

@@ -1,7 +1,5 @@
# ManualControlSwitches (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ManualControlSwitches.msg)
```c
@@ -30,16 +28,17 @@ uint8 return_switch # return to launch 2 position switch (mandatory
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
uint8 kill_switch # throttle kill: _NORMAL_, KILL
uint8 termination_switch # trigger termination which cannot be undone
uint8 gear_switch # landing gear switch: _DOWN_, UP
uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGHT
uint8 photo_switch # Photo trigger switch
uint8 video_switch # Photo trigger switch
uint8 payload_power_switch # Payload power switch
uint8 engage_main_motor_switch # Engage the main motor (for helicopters)
uint8 payload_power_switch # Payload power switch
uint32 switch_changes # number of switch changes
```

View File

@@ -1,16 +1,17 @@
# PurePursuitStatus (UORB message)
Pure pursuit status
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PurePursuitStatus.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Pure pursuit status
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 target_bearing # [rad] Target bearing calculated by the pure pursuit controller
float32 crosstrack_error # [m] Shortest distance from the vehicle to the path (Positiv: Vehicle is on the right hand side with respect to the oriented path vector, Negativ: Left of the path)
float32 distance_to_waypoint # [m] Distance from the vehicle to the current waypoint
float32 bearing_to_waypoint # [rad] Bearing towards current waypoint
uint64 timestamp # [us] Time since system start
float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller
float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller
float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path
float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint
float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint
```

View File

@@ -1,7 +1,5 @@
# RcChannels (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcChannels.msg)
```c
@@ -36,13 +34,14 @@ uint8 FUNCTION_FLTBTN_SLOT_5 = 25
uint8 FUNCTION_FLTBTN_SLOT_6 = 26
uint8 FUNCTION_ENGAGE_MAIN_MOTOR = 27
uint8 FUNCTION_PAYLOAD_POWER = 28
uint8 FUNCTION_TERMINATION = 29
uint8 FUNCTION_FLTBTN_SLOT_COUNT = 6
uint64 timestamp_last_valid # Timestamp of last valid RC signal
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
uint8 channel_count # Number of valid channels
int8[29] function # Functions mapping
int8[30] function # Functions mapping
uint8 rssi # Receive signal strength index
bool signal_lost # Control signal lost, should be checked together with topic timeout
uint32 frame_drop_count # Number of dropped frames

View File

@@ -1,12 +1,13 @@
# RoverAttitudeSetpoint (UORB message)
Rover Attitude Setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeSetpoint.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Attitude Setpoint
float32 yaw_setpoint # [rad] Expressed in NED frame
uint64 timestamp # [us] Time since system start
float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint
```

View File

@@ -1,13 +1,14 @@
# RoverAttitudeStatus (UORB message)
Rover Attitude Status
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeStatus.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Attitude Status
float32 measured_yaw # [rad/s] Measured yaw rate
float32 adjusted_yaw_setpoint # [rad/s] Yaw setpoint that is being tracked (Applied slew rates)
uint64 timestamp # [us] Time since system start
float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw
float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates)
```

View File

@@ -1,17 +1,17 @@
# RoverPositionSetpoint (UORB message)
Rover Position Setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Position Setpoint
float32[2] position_ned # 2-dimensional position setpoint in NED frame [m]
float32[2] start_ned # (Optional) 2-dimensional start position in NED frame used to define the line that the rover will track to position_ned [m] (Defaults to vehicle position)
float32 cruising_speed # (Optional) Specify rover speed [m/s] (Defaults to maximum speed)
float32 arrival_speed # (Optional) Specify arrival speed [m/s] (Defaults to zero)
float32 yaw # [rad] [-pi,pi] from North. Optional, NAN if not set. Mecanum only. (Defaults to vehicle yaw)
uint64 timestamp # [us] Time since system start
float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position
float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track
float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed
float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with
float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel
```

View File

@@ -1,12 +1,13 @@
# RoverRateSetpoint (UORB message)
Rover Rate setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateSetpoint.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Rate setpoint
float32 yaw_rate_setpoint # [rad/s] Expressed in NED frame
uint64 timestamp # [us] Time since system start
float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint
```

View File

@@ -1,14 +1,15 @@
# RoverRateStatus (UORB message)
Rover Rate Status
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateStatus.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Rate Status
float32 measured_yaw_rate # [rad/s] Measured yaw rate
float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint that is being tracked (Applied slew rates)
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
uint64 timestamp # [us] Time since system start
float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate
float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates)
float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller
```

View File

@@ -1,14 +1,13 @@
# RoverSteeringSetpoint (UORB message)
Rover Steering setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSteeringSetpoint.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Steering setpoint
float32 normalized_steering_angle # [-1, 1] Normalized steering angle (Ackermann only, Positiv: Steer right, Negativ: Steer left)
float32 normalized_speed_diff # [-1, 1] Normalized speed difference between the left and right wheels of the rover (Differential/Mecanum only, Positiv = Turn right, Negativ: Turn left)
uint64 timestamp # [us] Time since system start
float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels
```

View File

@@ -1,14 +1,14 @@
# RoverThrottleSetpoint (UORB message)
Rover Throttle setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverThrottleSetpoint.msg)
```c
# Rover Throttle setpoint
uint64 timestamp # time since system start (microseconds)
float32 throttle_body_x # throttle setpoint along body X axis [-1, 1] (Positiv = forwards, Negativ = backwards)
float32 throttle_body_y # throttle setpoint along body Y axis [-1, 1] (Mecanum only, Positiv = right, Negativ = left)
uint64 timestamp # [us] Time since system start
float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis
float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis
```

View File

@@ -1,14 +1,15 @@
# RoverVelocitySetpoint (UORB message)
Rover Velocity Setpoint
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocitySetpoint.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Velocity Setpoint
float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative)
float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction]
float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame
uint64 timestamp # [us] Time since system start
float32 speed # [m/s] [@range -inf (Backwards), inf (Forwards)] Speed setpoint
float32 bearing # [rad] [@range -pi,pi] [@frame NED] [@invalid: NaN, speed is defined in body x direction] Bearing setpoint
float32 yaw # [rad] [@range -pi, pi] [@frame NED] [@invalid NaN, Defaults to vehicle yaw] Mecanum only: Yaw setpoint
```

View File

@@ -1,17 +1,18 @@
# RoverVelocityStatus (UORB message)
Rover Velocity Status
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverVelocityStatus.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Rover Velocity Status
float32 measured_speed_body_x # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards
float32 adjusted_speed_body_x_setpoint # [m/s] Post slew rate speed setpoint in body x direction. Positiv: forwards, Negativ: backwards
float32 pid_throttle_body_x_integral # Integral of the PID for the closed loop controller of the speed in body x direction
float32 measured_speed_body_y # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left (Mecanum only)
float32 adjusted_speed_body_y_setpoint # [m/s] Post slew rate speed setpoint in body y direction. Positiv: right, Negativ: left (Mecanum only)
float32 pid_throttle_body_y_integral # Integral of the PID for the closed loop controller of the speed in body y direction (Mecanum only)
uint64 timestamp # [us] Time since system start
float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction
float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates)
float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction
float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction
float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates)
float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction
```

View File

@@ -1,19 +1,17 @@
# SatelliteInfo (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SatelliteInfo.msg)
```c
uint64 timestamp # time since system start (microseconds)
uint8 SAT_INFO_MAX_SATELLITES = 20
uint8 SAT_INFO_MAX_SATELLITES = 40
uint8 count # Number of satellites visible to the receiver
uint8[20] svid # Space vehicle ID [1..255], see scheme below
uint8[20] used # 0: Satellite not used, 1: used for navigation
uint8[20] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite
uint8[20] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg.
uint8[20] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite.
uint8[20] prn # Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144)
uint8[40] svid # Space vehicle ID [1..255], see scheme below
uint8[40] used # 0: Satellite not used, 1: used for navigation
uint8[40] elevation # Elevation (0: right on top of receiver, 90: on the horizon) of satellite
uint8[40] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg.
uint8[40] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite.
uint8[40] prn # Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144)
```

View File

@@ -1,7 +1,5 @@
# TransponderReport (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TransponderReport.msg)
```c
@@ -11,7 +9,7 @@ float64 lat # Latitude, expressed as degrees
float64 lon # Longitude, expressed as degrees
uint8 altitude_type # Type from ADSB_ALTITUDE_TYPE enum
float32 altitude # Altitude(ASL) in meters
float32 heading # Course over ground in radians, -pi to +pi, 0 is north
float32 heading # Course over ground in radians, 0 to 2pi, 0 is north
float32 hor_velocity # The horizontal velocity in m/s
float32 ver_velocity # The vertical velocity in m/s, positive is up
char[9] callsign # The callsign, 8+null

View File

@@ -96,9 +96,10 @@ uint8 HIL_STATE_ON = 1
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
uint8 vehicle_type
uint8 VEHICLE_TYPE_ROTARY_WING = 0
uint8 VEHICLE_TYPE_FIXED_WING = 1
uint8 VEHICLE_TYPE_ROVER = 2
uint8 VEHICLE_TYPE_UNSPECIFIED = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1

View File

@@ -16,65 +16,65 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [ActuatorMotors](ActuatorMotors.md) — Motor control message
- [ActuatorServos](ActuatorServos.md) — Servo control message
- [AirspeedValidated](AirspeedValidated.md)
- [ArmingCheckReply](ArmingCheckReply.md)
- [ArmingCheckRequest](ArmingCheckRequest.md)
- [BatteryStatus](BatteryStatus.md)
- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply.
- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request.
- [BatteryStatus](BatteryStatus.md) — Battery status
- [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors
- [Event](Event.md) — Events interface
- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message
Used by the fw_lateral_longitudinal_control module
At least one of course, airspeed_direction, or lateral_acceleration must be finite.
Used by the fw_lateral_longitudinal_control module
At least one of course, airspeed_direction, or lateral_acceleration must be finite.
- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message
Used by the fw_lateral_longitudinal_control module
If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion.
If both altitude and height_rate are NAN, the controller maintains the current altitude.
Used by the fw_lateral_longitudinal_control module
If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion.
If both altitude and height_rate are NAN, the controller maintains the current altitude.
- [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints
Setpoints are intended as inputs to position and heading smoothers, respectively
Setpoints do not need to be kinematically consistent
Optional heading setpoints may be specified as controlled by the respective flag
Unset optional setpoints are not controlled
Unset optional constraints default to vehicle specifications
Setpoints are intended as inputs to position and heading smoothers, respectively
Setpoints do not need to be kinematically consistent
Optional heading setpoints may be specified as controlled by the respective flag
Unset optional setpoints are not controlled
Unset optional constraints default to vehicle specifications
- [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates.
- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message
Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages.
Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages.
- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message
Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages
and configure the resultant setpoints.
Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages
and configure the resultant setpoints.
- [ManualControlSetpoint](ManualControlSetpoint.md)
- [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode.
The possible values of nav_state are defined in the VehicleStatus msg.
Note that this is not always published (e.g. when a user switches modes or on
failsafe activation)
The possible values of nav_state are defined in the VehicleStatus msg.
Note that this is not always published (e.g. when a user switches modes or on
failsafe activation)
- [RegisterExtComponentReply](RegisterExtComponentReply.md)
- [RegisterExtComponentRequest](RegisterExtComponentRequest.md) — Request to register an external component
- [TrajectorySetpoint](TrajectorySetpoint.md) — Trajectory setpoint in NED frame
Input to PID position controller.
Needs to be kinematically consistent and feasible for smooth flight.
setting a value to NaN means the state should not be controlled
Input to PID position controller.
Needs to be kinematically consistent and feasible for smooth flight.
setting a value to NaN means the state should not be controlled
- [UnregisterExtComponent](UnregisterExtComponent.md)
- [VehicleAngularVelocity](VehicleAngularVelocity.md)
- [VehicleAttitude](VehicleAttitude.md) — This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
The quaternion uses the Hamilton convention, and the order is q(w, x, y, z)
The quaternion uses the Hamilton convention, and the order is q(w, x, y, z)
- [VehicleAttitudeSetpoint](VehicleAttitudeSetpoint.md)
- [VehicleCommand](VehicleCommand.md) — Vehicle Command uORB message. Used for commanding a mission / action / etc.
Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
- [VehicleCommandAck](VehicleCommandAck.md) — Vehicle Command Ackonwledgement uORB message.
Used for acknowledging the vehicle command being received.
Follows the MAVLink COMMAND_ACK message definition
Used for acknowledging the vehicle command being received.
Follows the MAVLink COMMAND_ACK message definition
- [VehicleControlMode](VehicleControlMode.md)
- [VehicleGlobalPosition](VehicleGlobalPosition.md) — Fused global position in WGS84.
This struct contains global position estimation. It is not the raw GPS
measurement (@see vehicle_gps_position). This topic is usually published by the position
estimator, which will take more sources of information into account than just GPS,
e.g. control inputs of the vehicle in a Kalman-filter implementation.
This struct contains global position estimation. It is not the raw GPS
measurement (@see vehicle_gps_position). This topic is usually published by the position
estimator, which will take more sources of information into account than just GPS,
e.g. control inputs of the vehicle in a Kalman-filter implementation.
- [VehicleLandDetected](VehicleLandDetected.md)
- [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED.
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
- [VehicleRatesSetpoint](VehicleRatesSetpoint.md)
- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander
- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE
## Unversioned Messages
- [ActionRequest](ActionRequest.md)
@@ -84,9 +84,10 @@ The coordinate system origin is the vehicle position at the time when the EKF2-m
- [ActuatorServosTrim](ActuatorServosTrim.md) — Servo trims, added as offset to servo outputs
- [ActuatorTest](ActuatorTest.md)
- [AdcReport](AdcReport.md)
- [Airspeed](Airspeed.md)
- [Airspeed](Airspeed.md) — Airspeed data from sensors
- [AirspeedWind](AirspeedWind.md)
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md)
- [BatteryInfo](BatteryInfo.md) — Battery information
- [ButtonEvent](ButtonEvent.md)
- [CameraCapture](CameraCapture.md)
- [CameraStatus](CameraStatus.md)
@@ -94,7 +95,7 @@ The coordinate system origin is the vehicle position at the time when the EKF2-m
- [CanInterfaceStatus](CanInterfaceStatus.md)
- [CellularStatus](CellularStatus.md) — Cellular status
- [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame
setting something to NaN means that no limit is provided
setting something to NaN means that no limit is provided
- [ControlAllocatorStatus](ControlAllocatorStatus.md)
- [Cpuload](Cpuload.md)
- [DatamanRequest](DatamanRequest.md)
@@ -106,8 +107,9 @@ setting something to NaN means that no limit is provided
- [DifferentialPressure](DifferentialPressure.md)
- [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data
- [DistanceSensorModeChangeRequest](DistanceSensorModeChangeRequest.md)
- [DronecanNodeStatus](DronecanNodeStatus.md)
- [Ekf2Timestamps](Ekf2Timestamps.md) — this message contains the (relative) timestamps of the sensor inputs used by EKF2.
It can be used for reproducible replay.
It can be used for reproducible replay.
- [EscReport](EscReport.md)
- [EscStatus](EscStatus.md)
- [EstimatorAidSource1d](EstimatorAidSource1d.md)
@@ -120,18 +122,17 @@ It can be used for reproducible replay.
- [EstimatorInnovations](EstimatorInnovations.md)
- [EstimatorSelectorStatus](EstimatorSelectorStatus.md)
- [EstimatorSensorBias](EstimatorSensorBias.md) — Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets,
scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available).
scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available).
- [EstimatorStates](EstimatorStates.md)
- [EstimatorStatus](EstimatorStatus.md)
- [EstimatorStatusFlags](EstimatorStatusFlags.md)
- [Event](Event.md) — Events interface
- [FailsafeFlags](FailsafeFlags.md) — Input flags for the failsafe state machine set by the arming & health checks.
- [FailureDetectorStatus](FailureDetectorStatus.md)
- [FigureEightStatus](FigureEightStatus.md)
- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message
Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs
Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs
- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message
Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint
Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint
- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing
- [FlightPhaseEstimation](FlightPhaseEstimation.md)
- [FollowTarget](FollowTarget.md)
@@ -170,7 +171,7 @@ Published by the fw_lateral_longitudinal_control module to report the resultant
- [LandingTargetPose](LandingTargetPose.md) — Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames
- [LaunchDetectionStatus](LaunchDetectionStatus.md) — Status of the launch detection state machine (fixed-wing only)
- [LedControl](LedControl.md) — LED control: control a single or multiple LED's.
These are the externally visible LED's, not the board LED's
These are the externally visible LED's, not the board LED's
- [LogMessage](LogMessage.md) — A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO
- [LoggerStatus](LoggerStatus.md)
- [MagWorkerData](MagWorkerData.md)
@@ -185,7 +186,7 @@ These are the externally visible LED's, not the board LED's
- [MountOrientation](MountOrientation.md)
- [NavigatorMissionItem](NavigatorMissionItem.md)
- [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode
The possible values of nav_state are defined in the VehicleStatus msg.
The possible values of nav_state are defined in the VehicleStatus msg.
- [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md)
- [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor.
- [OffboardControlMode](OffboardControlMode.md) — Off-board control mode
@@ -208,11 +209,11 @@ The possible values of nav_state are defined in the VehicleStatus msg.
- [PositionControllerStatus](PositionControllerStatus.md)
- [PositionSetpoint](PositionSetpoint.md) — this file is only used in the position_setpoint triple as a dependency
- [PositionSetpointTriplet](PositionSetpointTriplet.md) — Global position setpoint triplet in WGS84 coordinates.
This are the three next waypoints (or just the next two or one).
This are the three next waypoints (or just the next two or one).
- [PowerButtonState](PowerButtonState.md) — power button state notification message
- [PowerMonitor](PowerMonitor.md) — power monitor message
- [PpsCapture](PpsCapture.md)
- [PurePursuitStatus](PurePursuitStatus.md)
- [PurePursuitStatus](PurePursuitStatus.md) — Pure pursuit status
- [PwmInput](PwmInput.md)
- [Px4ioStatus](Px4ioStatus.md)
- [QshellReq](QshellReq.md)
@@ -221,15 +222,15 @@ This are the three next waypoints (or just the next two or one).
- [RateCtrlStatus](RateCtrlStatus.md)
- [RcChannels](RcChannels.md)
- [RcParameterMap](RcParameterMap.md)
- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md)
- [RoverAttitudeStatus](RoverAttitudeStatus.md)
- [RoverPositionSetpoint](RoverPositionSetpoint.md)
- [RoverRateSetpoint](RoverRateSetpoint.md)
- [RoverRateStatus](RoverRateStatus.md)
- [RoverSteeringSetpoint](RoverSteeringSetpoint.md)
- [RoverThrottleSetpoint](RoverThrottleSetpoint.md)
- [RoverVelocitySetpoint](RoverVelocitySetpoint.md)
- [RoverVelocityStatus](RoverVelocityStatus.md)
- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) — Rover Attitude Setpoint
- [RoverAttitudeStatus](RoverAttitudeStatus.md) — Rover Attitude Status
- [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint
- [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint
- [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status
- [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint
- [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint
- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) — Rover Velocity Setpoint
- [RoverVelocityStatus](RoverVelocityStatus.md) — Rover Velocity Status
- [Rpm](Rpm.md)
- [RtlStatus](RtlStatus.md)
- [RtlTimeEstimate](RtlTimeEstimate.md)
@@ -239,12 +240,12 @@ This are the three next waypoints (or just the next two or one).
- [SensorAirflow](SensorAirflow.md)
- [SensorBaro](SensorBaro.md)
- [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form.
These fields are scaled and offset-compensated where possible and do not
change with board revisions and sensor updates.
These fields are scaled and offset-compensated where possible and do not
change with board revisions and sensor updates.
- [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor
- [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station.
- [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates.
the field 'timestamp' is for the position & velocity (microseconds)
the field 'timestamp' is for the position & velocity (microseconds)
- [SensorGyro](SensorGyro.md)
- [SensorGyroFft](SensorGyroFft.md)
- [SensorGyroFifo](SensorGyroFifo.md)
@@ -252,11 +253,11 @@ the field 'timestamp' is for the position & velocity (microseconds)
- [SensorMag](SensorMag.md)
- [SensorOpticalFlow](SensorOpticalFlow.md)
- [SensorPreflightMag](SensorPreflightMag.md) — Pre-flight sensor check metrics.
The topic will not be updated when the vehicle is armed
The topic will not be updated when the vehicle is armed
- [SensorSelection](SensorSelection.md) — Sensor ID's for the voted sensors output on the sensor_combined topic.
Will be updated on startup of the sensor module and when sensor selection changes
Will be updated on startup of the sensor module and when sensor selection changes
- [SensorUwb](SensorUwb.md) — UWB distance contains the distance information measured by an ultra-wideband positioning system,
such as Pozyx or NXP Rddrone.
such as Pozyx or NXP Rddrone.
- [SensorsStatus](SensorsStatus.md) — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated.
- [SensorsStatusImu](SensorsStatusImu.md) — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated.
- [SystemPower](SystemPower.md)
@@ -267,26 +268,26 @@ such as Pozyx or NXP Rddrone.
- [TiltrotorExtraControls](TiltrotorExtraControls.md)
- [TimesyncStatus](TimesyncStatus.md)
- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame
Input to position controller.
Input to position controller.
- [TransponderReport](TransponderReport.md)
- [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM
then the frequency, duration are used otherwise those values are ignored.
then the frequency, duration are used otherwise those values are ignored.
- [UavcanParameterRequest](UavcanParameterRequest.md) — UAVCAN-MAVLink parameter bridge request type
- [UavcanParameterValue](UavcanParameterValue.md) — UAVCAN-MAVLink parameter bridge response type
- [UlogStream](UlogStream.md) — Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA
mavlink message
mavlink message
- [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had
the NEED_ACK flag set
the NEED_ACK flag set
- [VehicleAcceleration](VehicleAcceleration.md)
- [VehicleAirData](VehicleAirData.md)
- [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md)
- [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame
setting something to NaN means that no limit is provided
setting something to NaN means that no limit is provided
- [VehicleImu](VehicleImu.md) — IMU readings in SI-unit form.
- [VehicleImuStatus](VehicleImuStatus.md)
- [VehicleLocalPositionSetpoint](VehicleLocalPositionSetpoint.md) — Local position setpoint in NED frame
Telemetry of PID position controller to monitor tracking.
NaN means the state was not controlled
Telemetry of PID position controller to monitor tracking.
NaN means the state was not controlled
- [VehicleMagnetometer](VehicleMagnetometer.md)
- [VehicleOpticalFlow](VehicleOpticalFlow.md) — Optical flow in XYZ body frame in SI units.
- [VehicleOpticalFlowVel](VehicleOpticalFlowVel.md)
@@ -298,5 +299,10 @@ NaN means the state was not controlled
- [Wind](Wind.md)
- [YawEstimatorStatus](YawEstimatorStatus.md)
- [AirspeedValidatedV0](AirspeedValidatedV0.md)
- [ArmingCheckReplyV0](ArmingCheckReplyV0.md)
- [BatteryStatusV0](BatteryStatusV0.md) — Battery status
- [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it
Events interface
- [HomePositionV0](HomePositionV0.md) — GPS home position in WGS84 coordinates.
- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md)
- [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander