Skip to content

PX4 ROS 2 Interface Library

main (PX4 v1.15) Experimental

WARNING

Experimental At the time of writing, parts of the PX4 ROS 2 Interface Library are experimental, and hence subject to change.

The PX4 ROS 2 Interface Library is a C++ library that simplifies controlling and interacting with PX4 from ROS 2.

The library provides two high-level interfaces for developers:

  1. The Control Interface allows developers to create and dynamically register modes written using ROS 2. It provides classes for sending different types of setpoints, ranging from high-level navigation tasks all the way down to direct actuator controls.
  2. The Navigation Interface enables sending vehicle position estimates to PX4 from ROS 2 applications, such as a VIO system.

Installation in a ROS 2 Workspace

To get started using the library within an existing ROS 2 workspace:

  1. Make sure you have a working ROS 2 setup, with px4_msgs in the ROS 2 workspace.

  2. Clone the repository into the workspace:

    sh
    cd $ros_workspace/src
    git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib

    INFO

    To ensure compatibility, use the latest main branches for PX4, px4_msgs and the library. See also here.

:::

  1. Build the workspace:

    sh
    cd ..
    colcon build
    source install/setup.bash

CI: Integration Tests

When opening a pull request to PX4, CI runs the library integration tests. These test that mode registration, failsafes, and mode replacement, work as expected.

The tests can also be run locally from PX4:

sh
./test/ros_test_runner.py

And to run only a single case:

sh
./test/ros_test_runner.py --verbose --case <case>

You can list the available test cases with:

sh
./test/ros_test_runner.py --list-cases