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
72 SendCommandResult result = SendCommandResult::REJECTED;
73 using AckWaitSet = rclcpp::StaticWaitSet<1, 0, 0, 0, 0, 0>;
74 AckWaitSet wait_set({{{vehicle_command_ack_sub_}}});
76 bool got_reply =
false;
77 auto start_time = std::chrono::steady_clock::now();
78 vehicle_command_pub_->publish(cmd);
81 auto now = std::chrono::steady_clock::now();
83 if (now >= start_time + command_timeout_) {
87 rclcpp::WaitResult<AckWaitSet> wait_ret = wait_set.wait(command_timeout_ - (now - start_time));
89 if (wait_ret.kind() == rclcpp::WaitResultKind::Ready) {
90 px4_msgs::msg::VehicleCommandAck ack;
91 rclcpp::MessageInfo info;
93 if (vehicle_command_ack_sub_->take(ack, info)) {
94 if (ack.command == cmd.command && ack.target_component == cmd.source_component) {
96 logger_,
"syncSendVehicleCommand: Command %i - Received acknowledgement %i", cmd.command, ack.result);
97 if (ack.result == px4_msgs::msg::VehicleCommandAck::VEHICLE_CMD_RESULT_ACCEPTED) {
98 result = SendCommandResult::ACCEPTED;
103 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - Acknowledgement message not valid", cmd.command);
109 result = SendCommandResult::TIMEOUT;
110 RCLCPP_WARN(logger_,
"syncSendVehicleCommand: Command %i - Timeout, no acknowledgement received", cmd.command);
113 RCLCPP_DEBUG(logger_,
"syncSendVehicleCommand: Command %i - Result code: %s", cmd.command,
toStr(result).c_str());
118bool VehicleCommandClient::arm()
const
120 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1);
123bool VehicleCommandClient::disarm()
const
125 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0);
130 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_MISSION_START, 0);
133bool VehicleCommandClient::takeoff(
float altitude_amsl_m,
float heading_rad)
const
135 RCLCPP_DEBUG(logger_,
"Takeoff parameters: altitude_amsl_m=%f heading_rad=%f", altitude_amsl_m, heading_rad);
136 return !syncSendVehicleCommand(
137 VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, NAN, NAN, NAN, heading_rad, NAN, NAN, altitude_amsl_m);
140bool VehicleCommandClient::land()
const {
return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_NAV_LAND); }
142bool VehicleCommandClient::syncActivateFlightMode(uint8_t mode_id)
const
144 return !syncSendVehicleCommand(VehicleCommand::VEHICLE_CMD_SET_NAV_STATE, mode_id);
147bool VehicleCommandClient::syncActivateFlightMode(
const FlightMode & mode)
const
149 return syncActivateFlightMode(
static_cast<uint8_t
>(mode));
152bool VehicleCommandClient::syncActivateFlightMode(
const px4_ros2::ModeBase *
const mode_ptr)
const
154 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.