uORB Message Reference
:::note This list is auto-generated from the source code. :::
This topic lists the UORB messages available in PX4 (some of which may be may be shared by the PX4-ROS 2 Bridge). Graphs showing how these are used can be found here.
- ActuatorMotors — Motor control message 
- ActuatorServos — Servo control message 
- ActuatorServosTrim — Servo trims, added as offset to servo outputs 
- CollisionConstraints — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided 
- DistanceSensor — DISTANCE_SENSOR message data 
- Ekf2Timestamps — this message contains the (relative) timestamps of the sensor inputs used by EKF2. It can be used for reproducible replay. 
- EstimatorSensorBias — 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). 
- Event — Events interface 
- FailsafeFlags — Input flags for the failsafe state machine set by the arming & health checks. 
- GpioConfig — GPIO configuration 
- GpioIn — GPIO mask and state 
- GpioOut — GPIO mask and state 
- GpioRequest — Request GPIO mask to be read 
- GpsDump — This message is used to dump the raw gps communication to the log. Set the parameter GPS_DUMP_COMM to 1 to use this. 
- Gripper — # Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module 
- HomePosition — GPS home position in WGS84 coordinates. 
- IrlockReport — IRLOCK_REPORT message data 
- LandingTargetPose — Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames 
- LaunchDetectionStatus — Status of the launch detection state machine (fixed-wing only) 
- LedControl — LED control: control a single or multiple LED's. These are the externally visible LED's, not the board LED's 
- LogMessage — A logging message, output with PX4_{WARN,ERR,INFO} 
- MavlinkTunnel — MAV_TUNNEL_PAYLOAD_TYPE enum 
- ModeCompleted — Mode completion result, published by an active mode. Note that this is not always published (e.g. when a user switches modes or on failsafe activation) 
- ObstacleDistance — Obstacle distances in front of the sensor. 
- OffboardControlMode — Off-board control mode 
- OnboardComputerStatus — ONBOARD_COMPUTER_STATUS message data 
- OrbitStatus — ORBIT_YAW_BEHAVIOUR 
- ParameterUpdate — This message is used to notify the system about one or more parameter changes 
- PositionSetpoint — this file is only used in the position_setpoint triple as a dependency 
- PositionSetpointTriplet — Global position setpoint triplet in WGS84 coordinates. This are the three next waypoints (or just the next two or one). 
- PowerButtonState — power button state notification message 
- PowerMonitor — power monitor message 
- SensorCombined — 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. 
- SensorCorrection — Sensor corrections in SI-unit form for the voted sensor 
- SensorGnssRelative — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. 
- SensorGps — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) 
- SensorPreflightMag — Pre-flight sensor check metrics. The topic will not be updated when the vehicle is armed 
- SensorSelection — 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 
- SensorUwb — UWB distance contains the distance information measured by an ultra-wideband positioning system, such as Pozyx or NXP Rddrone. 
- SensorsStatus — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. 
- SensorsStatusImu — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. 
- TakeoffStatus — Status of the takeoff state machine currently just available for multicopters 
- TaskStackInfo — stack information for a single running process 
- TrajectoryBezier — Bezier Trajectory description. See also Mavlink TRAJECTORY msg The topic trajectory_bezier describe each waypoint defined in vehicle_trajectory_bezier 
- TrajectorySetpoint — 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 
- TrajectoryWaypoint — Waypoint Trajectory description. See also Mavlink TRAJECTORY msg The topic trajectory_waypoint describe each waypoint defined in vehicle_trajectory_waypoint 
- TuneControl — 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. 
- UavcanParameterRequest — UAVCAN-MAVLink parameter bridge request type 
- UavcanParameterValue — UAVCAN-MAVLink parameter bridge response type 
- UlogStream — Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA mavlink message 
- UlogStreamAck — Ack a previously sent ulog_stream message that had the NEED_ACK flag set 
- VehicleAttitude — This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use 
- VehicleCommand — Vehicle Command uORB message. Used for commanding a mission / action / etc. Follows the MAVLink COMMAND_INT / COMMAND_LONG definition 
- VehicleCommandAck — Vehicle Command Ackonwledgement uORB message. Used for acknowledging the vehicle command being received. Follows the MAVLink COMMAND_ACK message definition 
- VehicleConstraints — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided 
- VehicleGlobalPosition — 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. 
- VehicleImu — IMU readings in SI-unit form. 
- VehicleLocalPosition — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. 
- VehicleLocalPositionSetpoint — Local position setpoint in NED frame Telemetry of PID position controller to monitor tracking. NaN means the state was not controlled 
- VehicleOdometry — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles 
- VehicleOpticalFlow — Optical flow in XYZ body frame in SI units. 
- VehicleRoi — Vehicle Region Of Interest (ROI) 
- VehicleStatus — Encodes the system state of the vehicle published by commander 
- VehicleTrajectoryBezier — Vehicle Waypoints Trajectory description. See also MAVLink MAV_TRAJECTORY_REPRESENTATION msg The topic vehicle_trajectory_bezier is used to send a smooth flight path from the companion computer / avoidance module to the position controller. 
- VehicleTrajectoryWaypoint — Vehicle Waypoints Trajectory description. See also MAVLink MAV_TRAJECTORY_REPRESENTATION msg The topic vehicle_trajectory_waypoint_desired is used to send the user desired waypoints from the position controller to the companion computer / avoidance module. The topic vehicle_trajectory_waypoint is used to send the adjusted waypoints from the companion computer / avoidance module to the position controller. 
- VtolVehicleStatus — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE 
Last updated
