|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
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. | |
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).
|
explicit |
| node | ROS 2 node used for creating publishers/subscriptions |
| topic_namespace_prefix | topic namespace (e.g. "" or "/my_ns/") |
| command_topic | command topic name without prefix/version suffix (default: "fmu/in/vehicle_command") |
| 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).