15#include "auto_apms_px4/vehicle_command_client.hpp"
19#include "px4_ros2/utils/message_version.hpp"
24std::string toStr(VehicleCommandClient::SendCommandResult result)
27 case VehicleCommandClient::SendCommandResult::ACCEPTED:
29 case VehicleCommandClient::SendCommandResult::REJECTED:
31 case VehicleCommandClient::SendCommandResult::TIMEOUT:
38VehicleCommandClient::VehicleCommandClient(rclcpp::Node & node,
const std::chrono::milliseconds & command_timeout)
39: node_{node}, logger_{node.get_logger().get_child(
"vehicle_command_client")}, command_timeout_{command_timeout}
42 vehicle_command_pub_ = node_.create_publisher<px4_msgs::msg::VehicleCommand>(
43 "/fmu/in/vehicle_command" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleCommand>(), 10);
45 vehicle_command_ack_sub_ = node_.create_subscription<px4_msgs::msg::VehicleCommandAck>(
46 "/fmu/out/vehicle_command_ack" + px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleCommandAck>(),
47 rclcpp::QoS(1).best_effort(), [](px4_msgs::msg::VehicleCommandAck::UniquePtr msg) { (void)msg; });
50VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
51 uint32_t command,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
54 px4_msgs::msg::VehicleCommand cmd{};
55 cmd.command = command;
63 cmd.timestamp = node_.get_clock()->now().nanoseconds() / 1000;
65 return syncSendVehicleCommand(cmd);
68VehicleCommandClient::SendCommandResult VehicleCommandClient::syncSendVehicleCommand(
69 const px4_msgs::msg::VehicleCommand & cmd)
const
71 SendCommandResult result = SendCommandResult::REJECTED;
72 using AckWaitSet = rclcpp::StaticWaitSet<1, 0, 0, 0, 0, 0>;
73 AckWaitSet wait_set({{{vehicle_command_ack_sub_}}});
75 bool got_reply =
false;
76 auto start_time = std::chrono::steady_clock::now();
77 vehicle_command_pub_->publish(cmd);
80 auto now = std::chrono::steady_clock::now();
82 if (now >= start_time + command_timeout_) {
86 rclcpp::WaitResult<AckWaitSet> wait_ret = wait_set.wait(command_timeout_ - (now - start_time));
88 if (wait_ret.kind() == rclcpp::WaitResultKind::Ready) {
89 px4_msgs::msg::VehicleCommandAck ack;
90 rclcpp::MessageInfo info;
92 if (vehicle_command_ack_sub_->take(ack, info)) {
93 if (ack.command == cmd.command && ack.target_component == cmd.source_component) {
95 logger_,
"syncSendVehicleCommand: Command %i - Received acknowledgement %i", cmd.command, ack.result);
96 if (ack.result == px4_msgs::msg::VehicleCommandAck::VEHICLE_CMD_RESULT_ACCEPTED) {
97 result = SendCommandResult::ACCEPTED;
102 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - Acknowledgement message not valid", cmd.command);
108 result = SendCommandResult::TIMEOUT;
109 RCLCPP_WARN(logger_,
"syncSendVehicleCommand: Command %i - Timeout, no acknowledgement received", cmd.command);
112 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - Result code: %s", cmd.command,
toStr(result).c_str());
117bool VehicleCommandClient::arm()
const
119 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1);
122bool VehicleCommandClient::disarm()
const
124 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0);
129 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_MISSION_START, 0);
132bool VehicleCommandClient::takeoff(
float altitude_amsl_m,
float heading_rad)
const
134 RCLCPP_DEBUG(logger_,
"Takeoff parameters: altitude_amsl_m=%f heading_rad=%f", altitude_amsl_m, heading_rad);
135 return !syncSendVehicleCommand(
136 VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, NAN, NAN, NAN, heading_rad, NAN, NAN, altitude_amsl_m);
139bool VehicleCommandClient::land()
const {
return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_NAV_LAND); }
141bool VehicleCommandClient::syncActivateFlightMode(uint8_t mode_id)
const
143 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_SET_NAV_STATE, mode_id);
146bool VehicleCommandClient::syncActivateFlightMode(
const FlightMode & mode)
const
148 return syncActivateFlightMode(
static_cast<uint8_t
>(mode));
151bool VehicleCommandClient::syncActivateFlightMode(
const px4_ros2::ModeBase *
const mode_ptr)
const
153 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.