Library to interface with PX4 from a companion computer using ROS 2. It provides some tooling used to write external modes that are dynamically registered with PX4 and behave the same way as internal ones. A mode can send different types of setpoints, ranging from high-level navigation tasks all the way down to direct actuator controls.
Documentation:
- High-level: https://docs.px4.io/main/en/ros2/px4_ros2_interface_lib.html
- API: https://auterion.github.io/px4-ros2-interface-lib/topics.html
The library interacts with PX4 by using its uORB messages, and thus requires a matching set of message definitions on the ROS 2 side. To ensure compatibility, you must either:
- Use latest
main
on the PX4 and px4_ros2/px4_msgs sides, which should define matching messages - (Experimental) Run the PX4 message translation node, which dynamically monitors and translates PX4 messages when different message version are used within the same ROS 2 domain
The library checks for message compatibility on startup when registering a mode.
ALL_PX4_ROS2_MESSAGES
defines the set of checked messages. If you use other messages, you can check them using:
if (!px4_ros2::messageCompatibilityCheck(node, {{"fmu/in/vehicle_rates_setpoint"}})) {
throw std::runtime_error("Messages incompatible");
}
To manually verify that two local versions of PX4 and px4_msgs have matching message sets, you can use the following script:
./scripts/check-message-compatibility.py -v path/to/px4_msgs/ path/to/PX4-Autopilot/
If you intend to run the message translation node to use mismatching message versions in PX4 and px4_ros2/px4_msgs, then you must manually disable the message compatibility check that runs when registering a mode. This can be done the following way:
class CustomMode : public px4_ros2::ModeBase
{
public:
CustomMode(rclcpp::Node & node)
: ModeBase(node, "node_name")
{
setSkipMessageCompatibilityCheck(); // Disables compatibility check
...
}
...
};
There are code examples under examples/cpp/modes.
For development, install the pre-commit scripts:
pre-commit install
CI runs a number of checks which can be executed locally with the following commands. Make sure you have the ROS workspace sourced.
./scripts/run-clang-tidy-on-project.sh
You can either run the unit tests through colcon:
colcon test --packages-select px4_ros2_cpp --ctest-args -R unit_tests
colcon test-result --verbose
Or directly from the build directory, which allows to filter by individual tests:
./build/px4_ros2_cpp/px4_ros2_cpp_unit_tests --gtest_filter='xy*'
These run automatically when committing code. To manually run them, use:
pre-commit run -a