diff --git a/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.drawio b/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.drawio new file mode 100644 index 000000000000..267e415997b8 --- /dev/null +++ b/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.drawio @@ -0,0 +1,189 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg b/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg new file mode 100644 index 000000000000..03ed903e2961 --- /dev/null +++ b/assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg @@ -0,0 +1,4 @@ + + + +

FAST-DDS

uORB topic

μXRCE-DDS
client

uORB topic
uORB topic
μXRCE-DDS
agent
ROS 2
Message
Translation
Node
ROS 2
Application Node
ROS 2
Application Node
FAST-DDS
μXRCE-DDS
agent
ROS 2
Message
Translation
Node
ROS 2
Application Node
(msgs ver: a.b.2)
msg: VehicleAttitudeV3
topic: /fmu/out/vehicle_attitude_v3
ROS 2
Application Node
(msgs ver: a.b.1)
msg: VehicleCommandV2
topic: /fmu/out/vehicle_command_v2
msg: VehicleAttitudeV5
topic: /fmu/out/vehicle_attitude_v5
msg: VehicleAttitudeV4
topic: /fmu/out/vehicle_attitude_v4
msg: VehicleCommandV3
topic: /fmu/out/vehicle_command_v3
PX4
(msgs ver: a.b.3)
\ No newline at end of file diff --git a/en/SUMMARY.md b/en/SUMMARY.md index ea0ad4fdac8d..039d8f9b6ca8 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -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) diff --git a/en/_sidebar.md b/en/_sidebar.md index 001b27d44194..279112e3a3c4 100644 --- a/en/_sidebar.md +++ b/en/_sidebar.md @@ -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) diff --git a/en/middleware/uorb.md b/en/middleware/uorb.md index 93a43ca716af..892e2e84a4f8 100644 --- a/en/middleware/uorb.md +++ b/en/middleware/uorb.md @@ -141,7 +141,33 @@ Make sure not to mix `orb_advertise_multi` and `orb_advertise` for the same topi The full API is documented in [platforms/common/uORB/uORBManager.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/uORB/uORBManager.hpp). +## Message Versioning + + +Message versioning has been in introduced in PX4 v1.16 (main) to make it easier to maintain compatibility between PX4 and ROS 2 versions. + +Versioned messages include an additional field `uint32 MESSAGE_VERSION = x`, where `x` corresponds to the current version of the message. +Versioned message files are stored separetly from their non-versioned counterpart. +Topic message files are located under `msg/versioned` and service message files are located under `srv/versioned`. +Non-versioned messages remain in the `msg/` and `srv/` directories respectively. + +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 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. + +Updating a versioned message involves more steps compared to updating a non-versioned one. +Please see the section on [Updating a Versioned Message](../ros2/px4_ros2_msg_translation_node.md#updating-a-versioned-message). + +For the full list of versioned and non-versioned messages, refer to the [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). + +::: note +ROS 2 plans to natively support message versioning in the future, but this is not implmemented yet. +See the related ROS Enhancement Proposal ([REP 2011](https://github.com/ros-infrastructure/rep/pull/358)). +See also this [Foxglove post](https://foxglove.dev/blog/sending-ros2-message-types-over-the-wire) on message hashing and type fetching. +::: ## Message/Field Deprecation {#deprecation} diff --git a/en/releases/main.md b/en/releases/main.md index fcc8ecfe23ba..3b981fdc959c 100644 --- a/en/releases/main.md +++ b/en/releases/main.md @@ -41,6 +41,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. ([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)). +- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850)) ### Control @@ -75,7 +76,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 -- TBD +- **[Feature]** [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one defintion version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113)) ### MAVLink diff --git a/en/ros2/index.md b/en/ros2/index.md index fc35b40ffd26..64b8ae76fd03 100644 --- a/en/ros2/index.md +++ b/en/ros2/index.md @@ -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 diff --git a/en/ros2/px4_ros2_msg_translation_node.md b/en/ros2/px4_ros2_msg_translation_node.md new file mode 100644 index 000000000000..d495188de143 --- /dev/null +++ b/en/ros2/px4_ros2_msg_translation_node.md @@ -0,0 +1,424 @@ +# PX4 ROS 2 Message Translation Node + + + +The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. + +## Overview + +The translation of messages from one definition version to another is possbile thanks to the introduction of [message versioning](../middleware/uorb.md#message-versioning). + +The translation node has access to all message versions previously defined by PX4. It dynamically observes the DDS data space, monitoring the publications, subscriptions and services originating from either PX4 via the [uXRCE-DDS Bridge](../middleware/uxrce_dds.md), or ROS2 applications. When necessary, it converts messages to the current versions expected by both applications and PX4, ensuring compatibility. + +![Overview ROS 2 Message Translation Node](../../assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg) + + + +To support the coexistence of different versions of the same messages within the ROS 2 domain, the ROS 2 topic-names for publications, subscriptions, and services include their respective message version as a suffix. This naming convention takes the form `_v`, as shown in the diagram above. + +## Usage + +### Installation + +The following steps describe how to install and run the translation node on your machine. + +1. (Optional) Create a new ROS 2 workspace in which to build the message translation node and its dependencies: + + ```sh + mkdir -p /path/to/ros_ws/src + ``` + +1. Run the following helper script to copy the message definitions and translation node into your ROS workspace directory. + + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` + +1. Build and source the workspace. + + ```sh + colcon build + source /path/to/ros_ws/install/setup.bash + ``` + +1. Finally, run the translation node. + + ```sh + ros2 run translation_node translation_node_bin + ``` + + You should see an output similar to: + + ```sh + [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: + [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: + ``` + +With the translation node running, any simultaneously running ROS 2 application designed to communicate with PX4 can do so, as long as it uses message versions recognized by the node. + +::: note +After making a modification in PX4 to the message defintions and/or translation node code, you will need to rerun the steps above from point 2. to update your ROS workspace accordingly. +::: + +### In ROS Applications + +While developing a ROS 2 application that communicates with PX4, it is not necessary to know the specific version of a message being used. +The message version can be added generically to a topic name like this: + +:::: tabs + +::: tab C++ + +```c++ +topic_name + "_v" + std::to_string(T::MESSAGE_VERSION) +``` + +::: + +::: tab Python + +```python +topic_name + "_v" + VehicleAttitude.MESSAGE_VERSION +``` + +::: + +:::: + +where `T` is the message type, e.g. `px4_msgs::msg::VehicleAttitude`. + +For example, the following implements a minimal subscriber and publisher node that uses two versioned PX4 messages and topics: + +:::: tabs + +::: tab C++ + +```c++ +#include +#include +#include +#include + +class MinimalPubSub : public rclcpp::Node { + public: + MinimalPubSub() : Node("minimal_pub_sub") { + // Define the topics to publish and subscribe to + // The correct message version is directly inferred from the message defintion + const std::string sub_topic = + "/fmu/out/vehicle_attitude_v" + std::to_string(px4_msgs::msg::VehicleAttitude::MESSAGE_VERSION); + const std::string pub_topic = + "/fmu/in/vehicle_command_v" + std::to_string(px4_msgs::msg::VehicleCommand::MESSAGE_VERSION); + + _subscription = this->create_subscription( + sub_topic, 10, + std::bind(&MinimalPubSub::attitude_callback, this, std::placeholders::_1)); + _publisher = this->create_publisher(pub_topic, 10); + } + + private: + void attitude_callback(const px4_msgs::msg::VehicleAttitude::SharedPtr msg) { + RCLCPP_INFO(this->get_logger(), "Received attitude message."); + } + + rclcpp::Publisher::SharedPtr _publisher; + rclcpp::Subscription::SharedPtr _subscription; +}; +``` + +::: + +::: tab Python + +```python +import rclpy +from rclpy.node import Node +from px4_msgs.msg import VehicleCommand, VehicleAttitude + +class MinimalPubSub(Node): + def __init__(self): + super().__init__('minimal_pub_sub') + + # Define the topics to publish and subscribe to + # The correct message version is directly inferred from the message definition + sub_topic = f"/fmu/out/vehicle_attitude_v{VehicleAttitude.MESSAGE_VERSION}" + pub_topic = f"/fmu/in/vehicle_command_v{VehicleCommand.MESSAGE_VERSION}" + + # Create subscription + self._subscription = self.create_subscription( + VehicleAttitude, + sub_topic, + self.attitude_callback, + 10 + ) + + # Create publisher + self._publisher = self.create_publisher( + VehicleCommand, + pub_topic, + 10 + ) + + def attitude_callback(self, msg): + self.get_logger().info("Received attitude message.") +``` + +::: + +:::: + +On the PX4 side, the DDS client automatically adds the version suffix if a message definition contains the field `uint32 MESSAGE_VERSION = x`. + +::: info +Version 0 of a topic means that no `_v` suffix should be added. +::: + +## Development + +### Definitions + +A __message__ defines the data format used for communication, whether over a topic or a service. +Therefore a message can be either a _topic_ message defined by a `.msg` file, or a _service_ message defined by a `.srv` file. + +A __versioned message__ is a message for which changes are tracked and each change results in a version bump, with the previous state of the definition being stored in history. +The latest version of every message is stored in `msg/versioned/` for topics (or `srv/versioned` for services), and all older versions are stored in `msg/px4_msgs_old/msg/` (or `msg/px4_msgs_old/srv/`). + +A __version translation__ defines a bidrectional mapping of the contents of one or more message definition across different versions. +Each translation is stored as a separate `.h` header file under `msg/translation_node/translations/`. +Message translations can be either _direct_ or _generic_. +- A __direct translation__ defines a bidirectional mapping of the contents of a _single_ message between two of its versions. + This is the simpler case and should be preferred if possible. +- A __generic translation__ defines a bidirectional mapping of the contents of `n` input messages to `m` output messages across different versions. +This can be used for merging or splitting a message, or when moving a field from one message to another. + +### File Structure + +Starting from PX4 v1.16 (main), the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: + +``` +PX4-Autopilot +├── ... +├── msg/ + ├── *.msg # Non-versioned topic message files + ├── versioned/ # Latest versioned topic message files + ├── px4_msgs_old/ # History of versioned messages (.msg + .srv) [ROS 2 package] + └── translation_node/ # Translation node and translation headers [ROS 2 package] +└── srv/ + ├── *.srv # Non-versioned service message files + └── versioned/ # Latest versioned service message files +``` + +This structure introduces new directories: `versioned/`, `px4_msgs_old/`, and `translation_node/`. + +#### Directories `msg/versioned/` and `srv/versioned/` + +- Contain the current latest version of each message. +- Files in these directories must include a `MESSAGE_VERSION` field to indicate that they are versioned. +- File names follow the conventional naming scheme (without a version suffix). + +Example directory structure: + +``` +PX4-Autopilot +├── ... +├── msg/ + └── versioned/ + ├── VehicleAttitude.msg # e.g. MESSAGE_VERSION = 3 + └── VehicleGlobalPosition.msg # e.g. MESSAGE_VERSION = 2 +└── srv/ + └── versioned/ + └── VehicleCommand.srv # e.g. MESSAGE_VERSION = 2 +``` + +#### Directory `px4_msgs_old/` + +- Archives the history of all versioned messages, including both topic and service messages (resp. under `msg/` and `srv/` subdirectories). +- Each file includes a `MESSAGE_VERSION` field. +- File names reflect the message's version with a suffix (e.g., `V1`, `V2`). + +Example directory structure (coherant with example above): + +``` + ... + msg/ + └── px4_msgs_old/ + ├── msg/ + ├── VehicleAttitudeV1.msg + ├── VehicleAttitudeV2.msg + └── VehicleGlobalPositionV1.msg + └── srv/ + └── VehicleCommandV1.srv +``` + +#### Directory `translation_node/` + +- Contains headers for translating between all different versions of messages. +- Each translation (direct or generic) is a single `.h` header file. +- The header `all_translation.h` acts as the main header, and includes all subsequent translation headers. + +Example directory structure (coherant with example above): + +``` + ... + msg/ + └── translation_node/ + └── translations/ + ├── all_translations.h # Main header + ├── translation_vehicle_attitude_v1.h # Direct translation v0 <-> v1 + ├── translation_vehicle_attitude_v2.h # Direct translation v1 <-> v2 + ├── translation_vehicle_attitude_v3.h # Direct translation v2 <-> latest (v3) + ├── translation_vehicle_global_position_v1.h # Direct translation v0 <-> v1 + ├── translation_vehicle_global_position_v2.h # Direct translation v1 <-> latest (v2) + ├── translation_vehicle_command_v1.h # Direct translation v0 <-> v1 + └── translation_vehicle_command_v2.h # Direct translation v1 <-> latest (v2) +``` + +### Updating a Versioned Message + +This section provides a step-by-step walkthrough and a basic working example of what the process of changing a versioned message looks like. + +When making changes to a versioned message, a new version of the message must be created and a translation from the older version must be added. + +The example describes the process of updating the `VehicleAttitude` message definition to contain an additional `new_field` entry, incrementing the message version from `3` to `4`, and creating a new direct translation in the process. + +1. **Archive the Current Definition** + + Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append the current version to the file name.
+ + For example:
+ Move `msg/versioned/VehicleAttitude.msg` → `px4_msgs_old/msg/VehicleAttitudeV3.msg` + +1. **Update Translation References to the Archived Definition** + + Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived version. + + For example, update references in those files:
+ - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` + - Replace `#include ` → `#include ` + +1. **Increment `MESSAGE_VERSION` and Modify Fields of the New Definition** + + Increment the `MESSAGE_VERSION` field in the new message definition and update the message fields that prompted the version change. + + For example, update `msg/versioned/VehicleAttitude.msg` from:
+ + ```c++ + uint32 MESSAGE_VERSION = 3 + uint64 timestamp + ... + ``` + + to + + ```c++ + uint32 MESSAGE_VERSION = 4 # Increment + uint64 timestamp + float32 new_field # Make definition changes + ... + ``` + +1. **Add a New Translation Header** + + Add a new version translation to bridge the archived version and the new version, by creating a new translation header. + + For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: + + ```c++ + // Translate VehicleAttitude v3 <--> v4 + #include + #include + + class VehicleAttitudeV4Translation { + public: + using MessageOlder = px4_msgs_old::msg::VehicleAttitudeV3; + static_assert(MessageOlder::MESSAGE_VERSION == 3); + + using MessageNewer = px4_msgs::msg::VehicleAttitude; + static_assert(MessageNewer::MESSAGE_VERSION == 4); + + static constexpr const char* kTopic = "fmu/out/vehicle_attitude"; + + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + msg_newer.timestamp = msg_older.timestamp; + msg_newer.timestamp_sample = msg_older.timestamp_sample; + msg_newer.q[0] = msg_older.q[0]; + msg_newer.q[1] = msg_older.q[1]; + msg_newer.q[2] = msg_older.q[2]; + msg_newer.q[3] = msg_older.q[3]; + msg_newer.delta_q_reset = msg_older.delta_q_reset; + msg_newer.quat_reset_counter = msg_older.quat_reset_counter; + + // Populate `new_field` with some value + msg_newer.new_field = -1; + } + + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + msg_older.timestamp = msg_newer.timestamp; + msg_older.timestamp_sample = msg_newer.timestamp_sample; + msg_older.q[0] = msg_newer.q[0]; + msg_older.q[1] = msg_newer.q[1]; + msg_older.q[2] = msg_newer.q[2]; + msg_older.q[3] = msg_newer.q[3]; + msg_older.delta_q_reset = msg_newer.delta_q_reset; + msg_older.quat_reset_counter = msg_newer.quat_reset_counter; + + // Discards `new_field` from MessageNewer + } + }; + + REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); + ``` + + Version translation templates are provided here: + - [Direct Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_direct_v1.h) + - [Generic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_multi_v2.h) + - [Direct Service Translation Template](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/example_translation_service_v1.h) + +1. **Include New Headers in `all_translations.h`** + + + Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/message_versioning_and_translation/msg/translation_node/translations/all_translations.h) so that the translation node can find them. + + For example, append the following line to `all_translation.h`: + + ```c++ + #include "translation_vehicle_attitude_v4.h" + ``` + +Note that in the example above and in most cases, step 4. only requires the developer to create a direct translation for the definition change. +This is because the changes only involved a single message. +In more complex cases of splitting, merging and/or moving definitions then a generic translation must be created. + +For example when moving a field from one message to another, a single generic translation should be added with the two older message versions as input, and the two newer versions as output. +This ensures there is no information lost when translating forward or backward. + +::: warning +If a nested message definition changes, all messages including that message also require a version update. +For example this would be the case for message [PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) if it were versioned. +This is primarily important for services which are more likely reference other message definitions. +::: + +## 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 diff --git a/en/ros2/user_guide.md b/en/ros2/user_guide.md index 6c3bd3f1684f..4f8ce2287193 100644 --- a/en/ros2/user_guide.md +++ b/en/ros2/user_guide.md @@ -34,6 +34,9 @@ The generator uses the uORB message definitions in the source tree: [PX4-Autopil ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. 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 v1.16 (main) 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. +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. @@ -231,7 +234,7 @@ The micro XRCE-DDS agent terminal should also start to show output, as equivalen ### Build ROS 2 Workspace -This section shows how create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere). +This section shows how to create a ROS 2 workspace hosted in your home directory (modify the commands as needed to put the source code elsewhere). The [px4_ros_com](https://github.com/PX4/px4_ros_com) and [px4_msgs](https://github.com/PX4/px4_msgs) packages are cloned to a workspace folder, and then the `colcon` tool is used to build the workspace. The example is run using `ros2 launch`. @@ -264,6 +267,13 @@ To create and build the workspace: git clone https://github.com/PX4/px4_ros_com.git ``` +1. __(Optional)__ From PX4 v1.16 (main), include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into your workspace by running the following script. +This step is useful only if using a PX4 and px4_msgs which contain different message versions. + + ```sh + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh ../ + ``` + 1. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`: :::: tabs @@ -334,6 +344,12 @@ In a new terminal: source install/local_setup.bash ``` +1. __(Optional)__ If the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) was added to the workspace in the previous steps, run the translation node: + + ```sh + ros2 run translation_node translation_node_bin + ``` + 1. Now launch the example. Note here that we use `ros2 launch`, which is described below.