Skip to content

Повідомлення uORB

Введення

The uORB is an asynchronous publish() / subscribe() messaging API used for inter-thread/inter-process communication.

uORB is implemented in the uorb module. It is started automatically (with uorb start) early in the PX4 boot sequence, as many applications depend on it. Unit tests can be started with uorb_tests.

This document explains how to add uORB message definitions and their corresponding topic(s), how to use reference a topic in code, and how to view topics as they change in PX4. The First Application Tutorial (Hello Sky) provides more comprehensive instructions for how to use topics in C++.

Adding a New Topic

New uORB topics can be added either within the main PX4/PX4-Autopilot repository, or can be added in an out-of-tree message definition.

To add new topics, you need to create a new .msg "message definition file" in the msg/ directory, and add the file name to the msg/CMakeLists.txt list. The new file name should follow the CamelCase convention.

A message definition file can define one or more topics, which all have the same fields and structure. By default a definition maps to a single topic that is named using a snake_case version of the message definition file name (for example, TopicName.msg would define a topic topic_name). You can also specify multiple topics to be created by the message definition, which is useful when you need several topics that have the same fields and structure (see Multi-Topic Messages below).

The section Message Definitions below describes the message format.

From the message definitions, the needed C/C++ code is automatically generated.

To use the topic in the code, first include the generated header, which will be named using the snake_case version of the (CamelCase) message definition file name. For example, for a message named VelocityLimits you would include velocity_limits.h as shown:

cpp
#include <uORB/topics/velocity_limits.h>

In code you refer to the topic using its id, which in this example would be: ORB_ID(velocity_limits).

Message Definitions

The message definition should start with a descriptive comment that outlines its purpose (a comment starts with the # symbol and goes to the end of the line). The message will then define one or more fields, which are defined with a type, such as bool, uint8, and float32, followed by a name. By convention, each field is followed by a descriptive comment, which is any text from the # symbol to the end of the line.

WARNING

All message definitions must include the uint64_t timestamp field, and this should be filled in when publishing the associated topic(s). This field is needed in order for the logger to be able to record UORB topics.

For example the VelocityLimits message definition shown below has a descriptive comment, followed by a number of fields, which each have a comment.

text
# Velocity and yaw rate limits for a multicopter position slow mode only

uint64 timestamp # time since system start (microseconds)

# absolute speeds, NAN means use default limit
float32 horizontal_velocity # [m/s]
float32 vertical_velocity # [m/s]
float32 yaw_rate # [rad/s]

By default this message definition will be compiled to a single topic with an id velocity_limits, a direct conversion from the CamelCase name to a snake_case version.

This is the simplest form of a message. See the existing msg files for other examples of how messages are defined.

Multi-Topic Messages

Sometimes it is useful to use the same message definition for multiple topics. This can be specified at the end of the message using a line prefixed with # TOPICS , followed by space-separated topic ids. For example, the ActuatorOutputs message definition is used to define the topic ids as shown:

text
# TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug

Nested Messages

Message definitions can be nested within other messages to create complex data structures.

To nest a message, simply include the nested message type in the parent message definition. For example, PositionSetpoint.msg is used as a nested message in the PositionSetpointTriplet.msg topic message definition.

text
# Global position setpoint triplet in WGS84 coordinates.
# This are the three next waypoints (or just the next two or one).

uint64 timestamp		# time since system start (microseconds)

PositionSetpoint previous
PositionSetpoint current
PositionSetpoint next

Публікація

Publishing a topic can be done from anywhere in the system, including interrupt context (functions called by the hrt_call API). Однак, перш ніж публікувати тему в контексті переривання, її потрібно оголосити і опублікувати поза контекстом переривання (принаймні, один раз).

Перелік тем та їх прослуховування

INFO

The listener command available on most boards after FMUv4. You can check for a particular board by searching for the CONFIG_SYSTEMCMDS_TOPIC_LISTENER key in the kconfig board configuration (for example, see the FMUv6 default.px4board file).

Щоб перерахувати всі теми, перерахуйте файлові дескриптори:

sh
ls /obj

Щоб прослухати зміст однієї теми з 5 повідомлень, запустіть команду прослуховувач:

sh
listener sensor_accel 5

На виході виводиться n-кратний вміст теми:

sh
TOPIC: sensor_accel #3
timestamp: 84978861
integral_dt: 4044
error_count: 0
x: -1
y: 2
z: 100
x_integral: -0
y_integral: 0
z_integral: 0
temperature: 46
range_m_s2: 78
scaling: 0

TOPIC: sensor_accel #4
timestamp: 85010833
integral_dt: 3980
error_count: 0
x: -1
y: 2
z: 100
x_integral: -0
y_integral: 0
z_integral: 0
temperature: 46
range_m_s2: 78
scaling: 0

TIP

On NuttX-based systems (Pixhawk, Pixracer, etc) the listener command can be called from within the QGroundControl MAVLink Console to inspect the values of sensors and other topics. Це потужний інструмент для відлагодження, оскільки його можна використовувати навіть тоді, коли QGC підключений через бездротове з'єднання (наприклад, коли транспортний засіб летить). For more information see: Sensor/Topic Debugging.

Команда uorb top

The command uorb top shows the publishing frequency of each topic in real-time:

sh
update: 1s, num topics: 77
TOPIC NAME                        INST #SUB #MSG #LOST #QSIZE
actuator_armed                       0    6    4     0 1
actuator_controls_0                  0    7  242  1044 1
battery_status                       0    6  500  2694 1
commander_state                      0    1   98    89 1
control_state                        0    4  242   433 1
ekf2_innovations                     0    1  242   223 1
ekf2_timestamps                      0    1  242    23 1
estimator_status                     0    3  242   488 1
mc_att_ctrl_status                   0    0  242     0 1
sensor_accel                         0    1  242     0 1
sensor_accel                         1    1  249    43 1
sensor_baro                          0    1   42     0 1
sensor_combined                      0    6  242   636 1

Колонки: назва теми, індекс, кількість підписників, частота публікації в Гц, кількість втрачених повідомлень за секунду (для всіх підписників разом) і розмір черги.

Plotting Changes in Topics

Topic changes can be plotted in realtime using PlotJuggler and the PX4 ROS 2 integration (note that this actually plots ROS topics that correspond to uORB topics, but the effect is the same).

For more information see: Plotting uORB Topic Data in Real Time using PlotJuggler.

Багатоекземплярний режим

uORB provides a mechanism to publish multiple independent instances of the same topic. This is useful, for example, if the system has several sensors of the same type.

INFO

This differs from Multi-Topic Messages, where we create different topics that happen to have the same structure.

A publisher can call orb_advertise_multi to create a new topic instance and get its instance index. A subscriber will then have to choose to which instance to subscribe to using orb_subscribe_multi (orb_subscribe subscribes to the first instance).

Make sure not to mix orb_advertise_multi and orb_advertise for the same topic!

The full API is documented in platforms/common/uORB/uORBManager.hpp.

Message/Field Deprecation

As there are external tools using uORB messages from log files, such as Flight Review, certain aspects need to be considered when updating existing messages:

  • Зміна існуючих полів або повідомлень, на які покладаються зовнішні інструменти, зазвичай є прийнятною, якщо для оновлення є вагомі причини. In particular for breaking changes to Flight Review, Flight Review must be updated before code is merged to master.
  • Для того, щоб зовнішні інструменти могли надійно розрізняти дві версії повідомлень, необхідно виконати наступні кроки:
    • Removed or renamed messages must be added to the deprecated_msgs list in msg/CMakeLists.txt and the .msg file needs to be deleted.
    • Видалені або перейменовані поля повинні бути закоментовані та позначені як застарілі. For example uint8 quat_reset_counter would become # DEPRECATED: uint8 quat_reset_counter. Це робиться для того, щоб гарантувати, що видалені поля (або повідомлення) не будуть додані повторно в майбутньому.
    • У разі семантичної зміни (наприклад, одиниця виміру змінюється з градусів на радіани), поле також має бути перейменоване, а попереднє позначене як застаріле, як зазначено вище.

Дивіться також