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, ModeT >
 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="")
 
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 the definition matches with the one that PX4 is using.

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