ROS 2 User Guide
Last updated
Last updated
The ROS 2-PX4 architecture provides a deep integration between ROS 2 and PX4, allowing ROS 2 subscribers or publisher nodes to interface directly with PX4 uORB topics.
This topic provides an overview of the architecture and application pipeline, and explains how to setup and use ROS 2 with PX4.
:::note From PX4 v1.14, ROS 2 uses middleware, replacing the FastRTPS middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS).
The explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14.
If you're still working on PX4 v1.13, please follow the instructions in the .
:::
The application pipeline for ROS 2 is very straightforward, thanks to the use of the communications middleware.
The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space.
You will normally need to start both the client and agent when using ROS 2. Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds.
The supported ROS 2 platforms for PX4 development are ROS 2 "Humble" on Ubuntu 22.04, and ROS 2 "Foxy" on Ubuntu 20.04.
ROS 2 "Humble" is recommended because it is the current ROS 2 LTS distribution. ROS 2 "Foxy" reached end-of-life in May 2023, but is still stable and works with PX4.
To setup ROS 2 for use with PX4:
Other dependencies of the architecture that are installed automatically, such as Fast DDS, are not covered.
You need to install the PX4 development toolchain in order to use the simulator.
Set up a PX4 development environment on Ubuntu in the normal way:
Note that the above commands will install the recommended simulator for your version of Ubuntu. If you want to install PX4 but keep your existing simulator installation, run ubuntu.sh
above with the --no-sim-tools
flag.
To install ROS 2 and its dependencies:
Install ROS 2.
:::: tabs
::: tab humble To install ROS 2 "Humble" on Ubuntu 22.04:
::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04:
You can install either the desktop (ros-foxy-desktop
) or bare-bones versions (ros-foxy-ros-base
), and the development tools (ros-dev-tools
). :::
::::
Some Python dependencies must also be installed (using pip
or apt
):
To setup and start the agent:
Open a terminal.
Enter the following commands to fetch and build the agent from source:
Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator:
The agent is now running, but you won't see much until we start PX4 (in the next step).
:::note You can leave the agent running in this terminal! Note that only one agent is allowed per connection channel. :::
The PX4 simulator starts the uXRCE-DDS client automatically, connecting to UDP port 8888 on the local host.
To start the simulator (and client):
Open a new terminal in the root of the PX4 Autopilot repo that was installed above.
:::: tabs
::: tab humble
:::
::: tab foxy
:::
::::
The agent and client are now running they should connect.
The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network:
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).
To create and build the workspace:
Open a new terminal.
Create and navigate into a new workspace directory using:
:::note A naming convention for workspace folders can make it easier to manage workspaces. :::
Source the ROS 2 development environment into the current terminal and compile the workspace using colcon
:
:::: tabs
::: tab humble
:::
::: tab foxy
:::
::::
This builds all the folders under /src
using the sourced toolchain.
To run the executables that you just built, you need to source local_setup.bash
. This provides access to the "environment hooks" for the current workspace. In other words, it makes the executables that were just built available in the current terminal.
In a new terminal:
Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"):
:::: tabs
::: tab humble
:::
::: tab foxy
:::
::::
Source the local_setup.bash
.
Now launch the example. Note here that we use ros2 launch
, which is described below.
If this is working you should see data being printed on the terminal/console where you launched the ROS listener:
To control applications, ROS 2 applications:
subscribe to (listen to) telemetry topics published by PX4
publish to topics that cause PX4 to perform some action.
This section contains information that may affect how you write your ROS code.
The local/world and body frames used by ROS and PX4 are different.
Body
FRD (X Forward, Y Right, Z Down)
FLU (X Forward, Y Left, Z Up)
World
FRD or NED (X North, Y East, Z Down)
FLU or ENU (X East, Y North, Z Up)
Both frames are shown in the image below (FRD on the left/FLU on the right).
The FRD (NED) conventions are adopted on all PX4 topics unless explicitly specified in the associated message definition. Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions.
To rotate a vector from ENU to NED two basic rotations must be performed:
first a pi/2 rotation around the Z
-axis (up),
then a pi rotation around the X
-axis (old East/new North).
To rotate a vector from NED to ENU two basic rotations must be performed:
first a pi/2 rotation around the Z
-axis (down),
then a pi rotation around the X
-axis (old North/new East). Note that the two resulting operations are mathematically equivalent.
To rotate a vector from FLU to FRD a pi rotation around the X
-axis (front) is sufficient.
To rotate a vector from FRD to FLU a pi rotation around the X
-axis (front) is sufficient.
Examples of vectors that require rotation are:
Similarly to vectors, also quanternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion.
The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the SensorCombined
message to which the node subscribes:
Then it creates a SensorCombinedListener
class that subclasses the generic rclcpp::Node
base class.
This creates a callback function for when the SensorCombined
uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received.
The lines below create a publisher to the SensorCombined
uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the fmu/sensor_combined/out
ROS 2 topic.
The instantiation of the SensorCombinedListener
class as a ROS node is done on the main
function.
A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot).
Taking as an example the debug_vect_advertiser.cpp
under px4_ros_com/src/advertisers
, first we import required headers, including the debug_vect
msg header.
Then the code creates a DebugVectAdvertiser
class that subclasses the generic rclcpp::Node
base class.
The code below creates a function for when messages are to be sent. The messages are sent based on a timed callback, which sends two messages per second based on a timer.
The instantiation of the DebugVectAdvertiser
class as a ROS node is done on the main
function.
ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. The only difference is that you need to start both the agent and the client, with settings appropriate for the communication channel.
A custom namespace can be provided for simulations (only) by setting the environment variable PX4_UXRCE_DDS_NS
before starting the simulation.
or
will generate topics under the namespaces:
:::
Use ros2 topic list
to list the topics visible to ROS 2:
If PX4 is connected to the agent, the result will be a list of topic types:
Note that the workspace does not need to build with px4_msgs
for this to succeed; topic type information is part of the message payload.
Use ros2 topic echo
to show the details of a particular topic.
Unlike with ros2 topic list
, for this to work you must be in a workspace has built the px4_msgs
and sourced local_setup.bash
so that ROS can interpret the messages.
The command will echo the topic details as they update.
You can get statistics about the rates of messages using ros2 topic hz
. For example, to get the rates for SensorCombined
:
The output will look something like:
The ros2 launch
command is used to start a ROS 2 launch file. For example, above we used ros2 launch px4_ros_com sensor_combined_listener.launch.py
to start the listener example.
You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components.
The standard installation should include all the tools needed by ROS 2.
If any are missing, they can be added separately:
colcon
build tools should be in the development tools. It can be installed using:
The Eigen3 library used by the transforms library should be in the both the desktop and base packages. It should be installed as shown:
:::: tabs
::: tab humble
:::
::: tab foxy
:::
::::
The PX4 is generated at build time and included in PX4 firmware by default. It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. The subset of uORB messages that are generated into the client are listed in . The generator uses the uORB message definitions in the source tree: to create the code for sending ROS 2 messages.
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 into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases).
Note that the micro XRCE-DDS agent itself has no dependency on client-side code. It can be built from either standalone or as part of a ROS build, or installed as a snap.
:::note In PX4v1.13 and earlier, ROS 2 was dependent on definitions in . This repo is no longer needed, but does contain useful examples. :::
:::note PX4 is not as well tested on Ubuntu 22.04 as it is on Ubuntu 20.04 (at time of writing), and Ubuntu 20.04 is needed if you want to use . :::
(to use the PX4 simulator)
:::note The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from . You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics. :::
For more information and troubleshooting see: and .
The instructions above are reproduced from the official installation guide: . You can install either the desktop (ros-humble-desktop
) or bare-bones versions (ros-humble-ros-base
), and the development tools (ros-dev-tools
). :::
Follow the official installation guide: .
For ROS 2 to communicate with PX4, must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer.
The agent can be installed onto the companion computer in a . Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator.
Start a PX4 simulation using:
Start a PX4 simulation using:
The PX4 terminal displays the output as PX4 boots and runs. As soon as the agent connects the output should include INFO
messages showing creation of data writers:
The and 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
.
:::note The example builds the example application, located in . is needed too so that the example can interpret PX4 ROS 2 topics. :::
Clone the example repository and to the /src
directory (the main
branch is cloned by default, which corresponds to the version of PX4 we are running):
:::note The recommend that you open a new terminal for running your executables. :::
The topics that you can use are defined in , and you can get more information about their data in the . For example, can be used to get the vehicle global position, while can be used to command actions such as takeoff and land.
The examples below provide concrete examples of how to use these topics.
ROS 2 code that subscribes to topics published by PX4 must specify a appropriate (compatible) QoS setting in order to listen to topics. Specifically, nodes should subscribe using the ROS 2 predefined QoS sensor data (from the ):
This is needed because the ROS 2 default are different from the settings used by PX4. Not all combinations of publisher-subscriber , and it turns out that the default ROS 2 settings for subscribing are not! Note that ROS code does not have to set QoS settings when publishing (the PX4 settings are compatible with ROS defaults in this case).
:::tip See for more information about ROS frames. :::
all fields in message; ENU to NED conversion is required before sending them.
all fields in message; FLU to FRD conversion is required before sending them.
provides the shared library to easily perform such conversions.
The ROS 2 in the repo demonstrate how to write ROS nodes to listen to topics published by PX4.
Here we consider the node under px4_ros_com/src/examples/listeners
, which subscribes to the message.
:::note shows how to build and run this example. :::
:::note The subscription sets a QoS profile based on rmw_qos_profile_sensor_data
. This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. For more information see: , :::
This particular example has an associated launch file at . This allows it to be launched using the command.
For a complete reference example on how to use Offboard control with PX4, see: .
For more information see .
ROS 2 needs to have the same message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The definition are stored in the ROS 2 interface package and they are automatically synchronized by CI on the main
and release branches. Note that all the messages from PX4 source code are present in the repository, but only those listed in dds_topics.yaml
will be available as ROS 2 topics. Therefore,
If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package into your workspace.
If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. Generally this means that you would update , clone the interface package, and then manually synchronize it by copying the new/modified message definitions from to its msg
folders. Assuming that PX4-Autopilot is in your home directory ~
, while px4_msgs
is in ~/px4_ros_com/src/
, then the command might be:
:::note Technically, completely defines the relationship between PX4 uORB topics and ROS 2 messages. For more information see . :::
Custom topic namespaces can be applied at build time (changing ) or at runtime (useful for multi vehicle operations):
One possibility is to use the -n
option when starting the from command line. This technique can be used both in simulation and real vehicles.
:::note Changing the namespace at runtime will append the desired namespace as a prefix to all topic
fields in . Therefore, commands like:
The is a useful tool for working with ROS. You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have px4_msg
in the workspace. The command also lets you launch more complex ROS systems via a launch file. A few possibilities are demonstrated below.
For information about launch files see
- Pablo Garrido & Nuno Marques (youtube)