15#include "auto_apms_interfaces/action/arm_disarm.hpp"
17#include "auto_apms_px4/vehicle_command_client.hpp"
18#include "auto_apms_util/action_wrapper.hpp"
19#include "px4_msgs/msg/vehicle_status.hpp"
24class ArmDisarmSkill :
public auto_apms_util::ActionWrapper<auto_apms_interfaces::action::ArmDisarm>
28 WAIT_FOR_READY_TO_ARM,
30 WAIT_FOR_ARMING_STATE_REACHED
33 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr vehicle_status_sub_ptr_;
35 bool ready_to_arm_{
false};
36 bool is_armed_{
false};
37 std::function<bool()> is_arming_state_reached_check__;
38 std::function<bool()> send_command_callback_;
39 const VehicleCommandClient vehicle_command_client_;
42 explicit ArmDisarmSkill(
const rclcpp::NodeOptions & options)
43 :
ActionWrapper{_AUTO_APMS_PX4__ARM_DISARM_ACTION_NAME, options}, vehicle_command_client_{*this->node_ptr_}
45 vehicle_status_sub_ptr_ = this->node_ptr_->create_subscription<px4_msgs::msg::VehicleStatus>(
46 "/fmu/out/vehicle_status", rclcpp::QoS(1).best_effort(), [
this](px4_msgs::msg::VehicleStatus::UniquePtr msg) {
47 is_armed_ = msg->arming_state == px4_msgs::msg::VehicleStatus::ARMING_STATE_ARMED;
48 ready_to_arm_ = msg->pre_flight_checks_pass;
53 bool onGoalRequest(std::shared_ptr<const Goal> goal_ptr)
override final
57 if (goal_ptr->arming_state == Goal::ARMING_STATE_ARM && !goal_ptr->wait_until_ready_to_arm && !ready_to_arm_) {
59 this->node_ptr_->get_logger(),
"UAV can currently not be armed and wait_until_ready_to_arm is false.");
63 if (goal_ptr->arming_state == Goal::ARMING_STATE_ARM) {
65 state_ = ready_to_arm_ ? SEND_COMMAND : WAIT_FOR_READY_TO_ARM;
66 is_arming_state_reached_check__ = [
this]() {
return is_armed_; };
67 send_command_callback_ = [
this]() {
return vehicle_command_client_.arm(); };
70 state_ = SEND_COMMAND;
71 is_arming_state_reached_check__ = [
this]() {
return !is_armed_; };
72 send_command_callback_ = [
this]() {
return vehicle_command_client_.disarm(); };
77 (goal_ptr->arming_state == Goal::ARMING_STATE_ARM && is_armed_) ||
78 (goal_ptr->arming_state == Goal::ARMING_STATE_DISARM && !is_armed_)) {
79 state_ = WAIT_FOR_ARMING_STATE_REACHED;
86 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
87 std::shared_ptr<Result> result_ptr)
override final
93 case WAIT_FOR_READY_TO_ARM:
95 state_ = SEND_COMMAND;
99 if (send_command_callback_()) {
100 state_ = WAIT_FOR_ARMING_STATE_REACHED;
102 RCLCPP_ERROR(this->node_ptr_->get_logger(),
"Couldn't send arm/disarm command. Aborting...");
103 result_ptr->state_changed =
false;
104 return Status::FAILURE;
107 case WAIT_FOR_ARMING_STATE_REACHED:
108 if (is_arming_state_reached_check__()) {
109 result_ptr->state_changed =
true;
110 return Status::SUCCESS;
115 return Status::RUNNING;
121#include "rclcpp_components/register_node_macro.hpp"
122RCLCPP_COMPONENTS_REGISTER_NODE(auto_apms_px4::ArmDisarmSkill)
ActionWrapper(const std::string &action_name, rclcpp::Node::SharedPtr node_ptr, std::shared_ptr< ActionContextType > action_context_ptr)
Implementation of PX4 mode peers offered by px4_ros2_cpp enabling integration with AutoAPMS.