8#include <px4_msgs/msg/vehicle_command.hpp>
9#include <px4_msgs/msg/vehicle_command_ack.hpp>
10#include <px4_ros2/components/mode.hpp>
11#include <px4_ros2/utils/message_version.hpp>
12#include <rclcpp/rclcpp.hpp>
36 const std::string& command_topic =
"fmu/in/vehicle_command");
51 std::string _topic_namespace_prefix;
52 rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
Sends a VehicleCommand and waits synchronously for an ACK from PX4.
Definition vehicle_command_sender.hpp:27
Result sendCommandSync(px4_msgs::msg::VehicleCommand cmd)
Publish cmd and wait for a matching VehicleCommandAck.
VehicleCommandSender(rclcpp::Node &node, std::string topic_namespace_prefix, const std::string &command_topic="fmu/in/vehicle_command")
Result
Definition mode.hpp:29