AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
arm_disarm.cpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#include "auto_apms_interfaces/action/arm_disarm.hpp"
16
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"
20
21namespace auto_apms_px4
22{
23
24class ArmDisarmSkill : public auto_apms_util::ActionWrapper<auto_apms_interfaces::action::ArmDisarm>
25{
26 enum State
27 {
28 WAIT_FOR_READY_TO_ARM,
29 SEND_COMMAND,
30 WAIT_FOR_ARMING_STATE_REACHED
31 };
32
33 rclcpp::Subscription<px4_msgs::msg::VehicleStatus>::SharedPtr vehicle_status_sub_ptr_;
34 State state_;
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_;
40
41public:
42 explicit ArmDisarmSkill(const rclcpp::NodeOptions & options)
43 : ActionWrapper{_AUTO_APMS_PX4__ARM_DISARM_ACTION_NAME, options}, vehicle_command_client_{*this->node_ptr_}
44 {
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;
49 });
50 }
51
52private:
53 bool onGoalRequest(std::shared_ptr<const Goal> goal_ptr) override final
54 {
55 // Reject goal if goal wants to arm, but UAV is not ready to arm and it is not requested to wait for ready to
56 // arm
57 if (goal_ptr->arming_state == Goal::ARMING_STATE_ARM && !goal_ptr->wait_until_ready_to_arm && !ready_to_arm_) {
58 RCLCPP_ERROR(
59 this->node_ptr_->get_logger(), "UAV can currently not be armed and wait_until_ready_to_arm is false.");
60 return false;
61 }
62
63 if (goal_ptr->arming_state == Goal::ARMING_STATE_ARM) {
64 // If goal is to 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(); };
68 } else {
69 // If goal is to disarm
70 state_ = SEND_COMMAND;
71 is_arming_state_reached_check__ = [this]() { return !is_armed_; };
72 send_command_callback_ = [this]() { return vehicle_command_client_.disarm(); };
73 }
74
75 // Succeed directly if arming state is already reached
76 if (
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;
80 }
81
82 return true;
83 }
84
85 Status executeGoal(
86 std::shared_ptr<const Goal> goal_ptr, std::shared_ptr<Feedback> feedback_ptr,
87 std::shared_ptr<Result> result_ptr) override final
88 {
89 (void)goal_ptr;
90 (void)feedback_ptr;
91
92 switch (state_) {
93 case WAIT_FOR_READY_TO_ARM:
94 if (ready_to_arm_) {
95 state_ = SEND_COMMAND;
96 }
97 break;
98 case SEND_COMMAND:
99 if (send_command_callback_()) {
100 state_ = WAIT_FOR_ARMING_STATE_REACHED;
101 } else {
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;
105 }
106 break;
107 case WAIT_FOR_ARMING_STATE_REACHED:
108 if (is_arming_state_reached_check__()) {
109 result_ptr->state_changed = true;
110 return Status::SUCCESS;
111 }
112 break;
113 }
114
115 return Status::RUNNING;
116 }
117};
118
119} // namespace auto_apms_px4
120
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.
Definition mode.hpp:26