PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Components

Classes

class  px4_ros2::ManualControlInput
 Provides access to manually input control setpoints. More...
 
struct  px4_ros2::MessageCompatibilityTopic
 
class  px4_ros2::ModeBase
 Base class for a mode. More...
 
class  px4_ros2::ModeExecutorBase
 Base class for a mode executor. More...
 
class  px4_ros2::NodeWithMode< ModeT >
 A ROS2 node which instantiates a control mode and handles its registration with PX4. More...
 
class  px4_ros2::NodeWithModeExecutor< ModeExecutorT, OwnedModeT, OtherModesT >
 A ROS2 node which instantiates a mode executor and its owned mode, and handles their registration with PX4. More...
 
enum class  px4_ros2::Result {
  Success = 0 , Rejected , Interrupted , Timeout ,
  Deactivated , ModeFailureOther = 100
}
 
constexpr const char * px4_ros2::resultToString (Result result) noexcept
 
bool px4_ros2::messageCompatibilityCheck (rclcpp::Node &node, const std::vector< MessageCompatibilityTopic > &messages_to_check, const std::string &topic_namespace_prefix="")
 Check for a set of messages that match the definitions used by PX4. More...
 
bool px4_ros2::waitForFMU (rclcpp::Node &node, const rclcpp::Duration &timeout=30s, const std::string &topic_namespace_prefix="")
 

Detailed Description

Enumeration Type Documentation

◆ Result

enum px4_ros2::Result
strong
Enumerator
Rejected 

The request was rejected.

Interrupted 

Ctrl-C or another error (from ROS)

Deactivated 

Mode or executor got deactivated.

Function Documentation

◆ messageCompatibilityCheck()

bool px4_ros2::messageCompatibilityCheck ( rclcpp::Node &  node,
const std::vector< MessageCompatibilityTopic > &  messages_to_check,
const std::string &  topic_namespace_prefix = "" 
)

Check for a set of messages that match the definitions used by PX4.

This function verifies that the message definitions are compatible with those expected by the PX4 ROS 2 interface library. It returns true if all definitions match.

Note
Compared to rmw_fastrtps_cpp, rmw_zenoh_cpp behaves differently. PX4 Zenoh allows flexible topic name mapping, so topic names are not fixed. In this case, the function only verifies the hashes of the message types to ensure binary compatibility between the FMU and ROS 2.

ROS 2 Humble does not support type hash, so no type checking will occur when using Zenoh. It is recommended to use Zenoh with ROS 2 Jazzy or later to ensure proper type compatibility verification.

Returns
true on success

◆ waitForFMU()

bool px4_ros2::waitForFMU ( rclcpp::Node &  node,
const rclcpp::Duration &  timeout = 30s,
const std::string &  topic_namespace_prefix = "" 
)

Wait for a heartbeat/status message from the FMU

Returns
true on success