Skip to content

Commit

Permalink
document message translation node
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine committed Dec 18, 2024
1 parent e468604 commit 41873cf
Show file tree
Hide file tree
Showing 6 changed files with 117 additions and 4 deletions.
1 change: 1 addition & 0 deletions en/SUMMARY.md
Original file line number Diff line number Diff line change
Expand Up @@ -808,6 +808,7 @@
- [PX4 ROS 2 Interface Library](ros2/px4_ros2_interface_lib.md)
- [Control Interface](ros2/px4_ros2_control_interface.md)
- [Navigation Interface](ros2/px4_ros2_navigation_interface.md)
- [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md)
- [ROS 1 (Deprecated)](ros/ros1.md)
- [ROS/MAVROS Installation Guide](ros/mavros_installation.md)
- [ROS/MAVROS Offboard Example (C++)](ros/mavros_offboard_cpp.md)
Expand Down
1 change: 1 addition & 0 deletions en/_sidebar.md
Original file line number Diff line number Diff line change
Expand Up @@ -797,6 +797,7 @@
- [PX4 ROS 2 Interface Library](/ros2/px4_ros2_interface_lib.md)
- [Control Interface](/ros2/px4_ros2_control_interface.md)
- [Navigation Interface](/ros2/px4_ros2_navigation_interface.md)
- [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md)
- [ROS 1 (Deprecated)](/ros/ros1.md)
- [ROS/MAVROS Installation Guide](/ros/mavros_installation.md)
- [ROS/MAVROS Offboard Example (C++)](/ros/mavros_offboard_cpp.md)
Expand Down
6 changes: 3 additions & 3 deletions en/middleware/uorb.md
Original file line number Diff line number Diff line change
Expand Up @@ -147,15 +147,15 @@ The full API is documented in [platforms/common/uORB/uORBManager.hpp](https://gi

Message versioning was introduced to address the challenges of maintaining compatibility across systems where different versions of message definitions may be in use, such as between PX4 and external systems like ROS 2 applications.

This versioning mechanism supports the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md), which enables seamless communication between PX4 and ROS 2 applications; when different versions of message definitions are in use, the ROS 2 translation node ensures that messages can be converted and exchanged correctly.

Versioned messages are stored in the `msg/versioned/` directory, distinct from their non-versioned counterparts, which reside directly in the `msg/` directory.
Each versioned message definition includes an additional field: `uint32 MESSAGE_VERSION = X`, where `X` corresponds to the current version of the message.
When a versioned message definition is modified, the version number should be incremented to reflect changes in its structure or semantics.
Additionally, [message translations](../ros2/px4_ros2_msg_translation_node.md#updating-a-message) must also be updated for versioned messages.

Versioned messages are designed to remain more stable over time compared to their non-versioned counterparts, as they are intended to be used across multiple releases of PX4 and external systems, ensuring greater compatibility over longer periods.

This versioning mechanism supports the ROS 2 message translation system (TODO: add link), which enables seamless communication between PX4 and ROS 2 applications.
When different versions of message definitions are in use, the ROS 2 translation system ensures that messages can be converted and exchanged correctly.

For the full list of versioned and non-versioned messages, refer to the full [uORB Message Reference](../msg_docs/index.md).

For more on PX4 and ROS 2 communication, refer to the page about the [PX4-ROS 2 Bridge](../ros/ros2_comm.md).
Expand Down
1 change: 1 addition & 0 deletions en/ros2/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ The main topics in this section are:
- [ROS 2 Multi Vehicle Simulation](../ros2/multi_vehicle.md): Instructions for connecting to multipole PX4 simulations via single ROS 2 agent.
- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md): A C++ library that simplies interacting with PX4 from ROS 2.
Can be used to create and register flight modes wrtten using ROS2 and send position estimates from ROS2 applications such as a VIO system.
- [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md): A ROS 2 message translation node that enables communcation between PX4 and ROS 2 applications that were compiled with different sets of messages versions.

## Further Information

Expand Down
110 changes: 110 additions & 0 deletions en/ros2/px4_ros2_msg_translation_node.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
# PX4 ROS 2 Message Translation Node

<Badge type="tip" text="main (PX4 v1.16+)" /> <Badge type="warning" text="Experimental" />

The message translation node allows to run applications that are compiled with one set of message versions against a PX4 with another set of message versions, without having to change either the application or the PX4 side.

Specifically for this to work, topic publication/subscription/service names contain a message version in the form of `<topic_name>_v<version>`.

The translation node knows about all existing message versions, and dynamically monitors the publications, subscriptions and services, and then creates translations as needed.

## Installation and First Test

Create a ROS 2 workspace in which to build the message translation node and its dependencies

```bash
mkdir -p /path/to/ros_ws/src
```

Run the following helper script, it will copy the message definitions and translation node to your ROS workspace directory.

```bash
cd /path/to/ros_ws
/path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh .
```

Build and source the workspace.

```bash
colcon build
source /path/to/ros_ws/install/setup.bash
```

Finally, run the translation node. You should see an output similar to:

```bash
ros2 run translation_node translation_node_bin
[INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions:
[INFO] [1734525720.729594413] [translation_node]: Registered services and versions:
```

## Updating a Message

When changing a message, a new version needs to be added.

The steps include:

- Copy the versioned message file (`.msg`/`.srv`) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`) and add the current version to the file name.
For example `msg/versioned/VehicleAttitude.msg` becomes `px4_msgs_old/msg/VehicleAttitudeV3.msg`.
Update the existing translations that use the current topic version to the now old version.
For example `px4_msgs::msg::VehicleAttitude` becomes `px4_msgs_old::msg::VehicleAttitudeV3`.
- Increment `MESSAGE_VERSION` and update the message fields as desired.
- Add a version translation by adding a new translation header. Examples: (TODO: update GitHub urls)
- [`translations/example_translation_direct_v1.h`](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_direct_v1.h)
- [`translations/example_translation_multi_v2.h`](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_multi_v2.h)
- [`translations/example_translation_service_v1.h`](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_service_v1.h)
- Include the added header in [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/all_translations.h).

For the second last step and for topics, there are two options:

1. Direct translations: these translate a single topic between two different versions.
This is the simpler case and should be preferred if possible.
2. Generic case: this allows a translation between N input topics and M output topics.
This can be used for merging or splitting a message.
Or for example when moving a field from one message to another, a single translation should be added with the two older message versions as input and the two newer versions as output.
This way there is no information lost when translating forward or backward.

::: info
If a nested message definition changes, all messages including that message also require a version update.
This is primarily important for services.
:::

## Usage in ROS

The message version can be added generically to a topic like this:

```c++
topic_name + "_v" + std::to_string(T::MESSAGE_VERSION)
```

Where `T` is the message type, e.g. `px4_msgs::msg::VehicleAttitude`.

The DDS client in PX4 automatically adds the version suffix if a message contains the field `uint32 MESSAGE_VERSION = x`.

::: info Version 0 of a topic means that no `_v<version>` suffix should be added.
:::

## Implementation Details

The translation node dynamically monitors the topics and services.
It then instantiates the countersides of the publications and subscribers as required.
For example if there is an external publisher for version 1 of a topic and subscriber for version 2.

Internally, it maintains a graph of all known topic and version tuples (which are the graph nodes).
The graph is connected by the message translations.
As arbitrary message translations can be registered, the graph can have cycles and multiple paths from one node to another.
Therefore on a topic update, the graph is traversed using a shortest path algorithm.
When moving from one node to the next, the message translation method is called with the current topic data.
If a node contains an instantiated publisher (because it previously detected an external subscriber), the data is published.
Thus, multiple subscribers of any version of the topic can be updated with the correct version of the data.

For translations with multiple input topics, the translation continues once all input messages are available.

## Limitations

- The current implementation depends on a service API that is not yet available in ROS Humble, and therefore does not support services when built for ROS Humble.
- Services only support a linear history, i.e. no message splitting or merging
- Having both publishers and subscribers for two different versions of a topic is currently not handled by the translation node and would trigger infinite circular publications.
This could be extended if required.

Original document with requirements: https://docs.google.com/document/d/18_RxV1eEjt4haaa5QkFZAlIAJNv9w5HED2aUEiG7PVQ/edit?usp=sharing
2 changes: 1 addition & 1 deletion en/ros2/user_guide.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ ROS 2 applications need to be built in a workspace that has the _same_ message d
You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).

Starting from PX4 x.x.x in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4.
However this will require the ROS 2 translation node (TODO: add link) to be running to ensure that messages can be converted and exchanged correctly.
This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly.

Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code.
It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap.
Expand Down

0 comments on commit 41873cf

Please sign in to comment.