15#include "auto_apms_px4/vehicle_command_client.hpp"
22std::string toStr(VehicleCommandClient::SendCommandResult result)
25 case VehicleCommandClient::SendCommandResult::ACCEPTED:
27 case VehicleCommandClient::SendCommandResult::REJECTED:
29 case VehicleCommandClient::SendCommandResult::TIMEOUT:
36VehicleCommandClient::VehicleCommandClient(rclcpp::Node & node,
const std::chrono::milliseconds & command_timeout)
37: node_{node}, logger_{node.get_logger().get_child(
"vehicle_command_client")}, command_timeout_{command_timeout}
40 vehicle_command_pub_ = node_.create_publisher<px4_msgs::msg::VehicleCommand>(
"/fmu/in/vehicle_command", 10);
42 vehicle_command_ack_sub_ = node_.create_subscription<px4_msgs::msg::VehicleCommandAck>(
43 "/fmu/out/vehicle_command_ack", rclcpp::QoS(1).best_effort(),
44 [](px4_msgs::msg::VehicleCommandAck::UniquePtr msg) { (void)msg; });
47VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
48 uint32_t command,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
51 px4_msgs::msg::VehicleCommand cmd{};
52 cmd.command = command;
60 cmd.timestamp = node_.get_clock()->now().nanoseconds() / 1000;
62 return syncSendVehicleCommand(cmd);
65VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
66 const px4_msgs::msg::VehicleCommand & cmd)
const
68 SendCommandResult result = SendCommandResult::REJECTED;
69 rclcpp::WaitSet wait_set;
70 wait_set.add_subscription(vehicle_command_ack_sub_);
72 bool got_reply =
false;
73 auto start_time = std::chrono::steady_clock::now();
74 vehicle_command_pub_->publish(cmd);
77 auto now = std::chrono::steady_clock::now();
79 if (now >= start_time + command_timeout_) {
83 auto wait_ret = wait_set.wait(command_timeout_ - (now - start_time));
85 if (wait_ret.kind() == rclcpp::WaitResultKind::Ready) {
86 px4_msgs::msg::VehicleCommandAck ack;
87 rclcpp::MessageInfo info;
89 if (vehicle_command_ack_sub_->take(ack, info)) {
90 if (ack.command == cmd.command && ack.target_component == cmd.source_component) {
91 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - received ack result %i", cmd.command, ack.result);
92 if (ack.result == px4_msgs::msg::VehicleCommandAck::VEHICLE_CMD_RESULT_ACCEPTED) {
93 result = SendCommandResult::ACCEPTED;
98 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - message not valid", cmd.command);
103 wait_set.remove_subscription(vehicle_command_ack_sub_);
106 result = SendCommandResult::TIMEOUT;
107 RCLCPP_WARN(logger_,
"syncSendVehicleCommand: Command %i - timeout, no ack received", cmd.command);
110 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - returned %s", cmd.command,
toStr(result).c_str());
115bool VehicleCommandClient::arm()
const
117 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1);
120bool VehicleCommandClient::disarm()
const
122 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0);
127 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_MISSION_START, 0);
130bool VehicleCommandClient::takeoff(
float altitude_amsl_m,
float heading_rad)
const
132 RCLCPP_DEBUG(logger_,
"Takeoff parameters: altitude_amsl_m=%f heading_rad=%f", altitude_amsl_m, heading_rad);
133 return !syncSendVehicleCommand(
134 VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, NAN, NAN, NAN, heading_rad, NAN, NAN, altitude_amsl_m);
137bool VehicleCommandClient::land()
const {
return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_NAV_LAND); }
139bool VehicleCommandClient::syncActivateFlightMode(uint8_t mode_id)
const
141 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_SET_NAV_STATE, mode_id);
144bool VehicleCommandClient::syncActivateFlightMode(
const FlightMode & mode)
const
146 return syncActivateFlightMode(
static_cast<uint8_t
>(mode));
149bool VehicleCommandClient::syncActivateFlightMode(
const px4_ros2::ModeBase *
const mode_ptr)
const
151 return syncActivateFlightMode(mode_ptr->id());
bool startMission() const
(Re)starts the uploaded mission plan.
const char * toStr(const ActionNodeErrorCode &err)
Convert the action error code to string.
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.