PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
px4_ros2::VehicleCommandSender Class Reference

Sends a VehicleCommand and waits synchronously for an ACK from PX4. More...

#include <px4_ros2/utils/vehicle_command_sender.hpp>

Public Member Functions

 VehicleCommandSender (rclcpp::Node &node, std::string topic_namespace_prefix, const std::string &command_topic="fmu/in/vehicle_command")
 
Result sendCommandSync (px4_msgs::msg::VehicleCommand cmd)
 Publish cmd and wait for a matching VehicleCommandAck.
 

Detailed Description

Sends a VehicleCommand and waits synchronously for an ACK from PX4.

This helper can be reused by any component that needs to send one-shot vehicle commands with acknowledgement (e.g. HomePositionSetter, ModeExecutorBase).

Constructor & Destructor Documentation

◆ VehicleCommandSender()

px4_ros2::VehicleCommandSender::VehicleCommandSender ( rclcpp::Node &  node,
std::string  topic_namespace_prefix,
const std::string &  command_topic = "fmu/in/vehicle_command" 
)
explicit
Parameters
nodeROS 2 node used for creating publishers/subscriptions
topic_namespace_prefixtopic namespace (e.g. "" or "/my_ns/")
command_topiccommand topic name without prefix/version suffix (default: "fmu/in/vehicle_command")

Member Function Documentation

◆ sendCommandSync()

Result px4_ros2::VehicleCommandSender::sendCommandSync ( px4_msgs::msg::VehicleCommand  cmd)

Publish cmd and wait for a matching VehicleCommandAck.

Retries up to 3 times with a 300 ms timeout per attempt. The ACK is matched on (command, target_component == cmd.source_component).

Returns
Result::Success on ACK accepted, Result::Rejected on ACK rejected, Result::Timeout if no ACK is received.

The documentation for this class was generated from the following file: