uORB Message Reference
Last updated
Last updated
:::note This list is from the source code. :::
This topic lists the UORB messages available in PX4 (some of which may be may be shared by the ). Graphs showing how these are used .
— Motor control message
— Servo control message
— Servo trims, added as offset to servo outputs
— Local setpoint constraints in NED frame setting something to NaN means that no limit is provided
— DISTANCE_SENSOR message data
— this message contains the (relative) timestamps of the sensor inputs used by EKF2. It can be used for reproducible replay.
— 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).
— Events interface
— Input flags for the failsafe state machine set by the arming & health checks.
— GPIO configuration
— GPIO mask and state
— GPIO mask and state
— Request GPIO mask to be read
— This message is used to dump the raw gps communication to the log. Set the parameter GPS_DUMP_COMM to 1 to use this.
— # Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module
— GPS home position in WGS84 coordinates.
— IRLOCK_REPORT message data
— Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames
— Status of the launch detection state machine (fixed-wing only)
— LED control: control a single or multiple LED's. These are the externally visible LED's, not the board LED's
— A logging message, output with PX4_{WARN,ERR,INFO}
— MAV_TUNNEL_PAYLOAD_TYPE enum
— 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)
— Obstacle distances in front of the sensor.
— Off-board control mode
— ONBOARD_COMPUTER_STATUS message data
— ORBIT_YAW_BEHAVIOUR
— This message is used to notify the system about one or more parameter changes
— this file is only used in the position_setpoint triple as a dependency
— Global position setpoint triplet in WGS84 coordinates. This are the three next waypoints (or just the next two or one).
— power button state notification message
— power monitor message
— 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.
— Sensor corrections in SI-unit form for the voted sensor
— GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station.
— GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds)
— Pre-flight sensor check metrics. The topic will not be updated when the vehicle is armed
— 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
— UWB distance contains the distance information measured by an ultra-wideband positioning system, such as Pozyx or NXP Rddrone.
— Sensor check metrics. This will be zero for a sensor that's primary or unpopulated.
— Sensor check metrics. This will be zero for a sensor that's primary or unpopulated.
— Status of the takeoff state machine currently just available for multicopters
— stack information for a single running process
— Bezier Trajectory description. See also Mavlink TRAJECTORY msg The topic trajectory_bezier describe each waypoint defined in vehicle_trajectory_bezier
— 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
— Waypoint Trajectory description. See also Mavlink TRAJECTORY msg The topic trajectory_waypoint describe each waypoint defined in vehicle_trajectory_waypoint
— 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.
— UAVCAN-MAVLink parameter bridge request type
— UAVCAN-MAVLink parameter bridge response type
— Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA mavlink message
— Ack a previously sent ulog_stream message that had the NEED_ACK flag set
— This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use
— Vehicle Command uORB message. Used for commanding a mission / action / etc. Follows the MAVLink COMMAND_INT / COMMAND_LONG definition
— Vehicle Command Ackonwledgement uORB message. Used for acknowledging the vehicle command being received. Follows the MAVLink COMMAND_ACK message definition
— Local setpoint constraints in NED frame setting something to NaN means that no limit is provided
— 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.
— IMU readings in SI-unit form.
— Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
— Local position setpoint in NED frame Telemetry of PID position controller to monitor tracking. NaN means the state was not controlled
— Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
— Optical flow in XYZ body frame in SI units.
— Vehicle Region Of Interest (ROI)
— Encodes the system state of the vehicle published by commander
— 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.
— 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.
— VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE