AutoAPMS
Streamlining behaviors in ROS 2
Loading...
Searching...
No Matches
takeoff_and_land.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// http://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_px4_interfaces/action/arm_disarm.hpp"
16#include "auto_apms_px4_interfaces/action/land.hpp"
17#include "auto_apms_px4_interfaces/action/takeoff.hpp"
18#include "auto_apms_util/action_client_wrapper.hpp"
19
20using namespace std::chrono_literals;
21using ArmDisarmAction = auto_apms_px4_interfaces::action::ArmDisarm;
22using TakeoffAction = auto_apms_px4_interfaces::action::Takeoff;
23using LandAction = auto_apms_px4_interfaces::action::Land;
24
25int main(int argc, char * argv[])
26{
27 rclcpp::init(argc, argv);
28
29 // Create vehicle_command_client
30 auto node_ptr = std::make_shared<rclcpp::Node>("takeoff_and_land_example");
31
32 auto arm_disarm_client = auto_apms_util::ActionClientWrapper<ArmDisarmAction>(node_ptr, "arm_disarm");
33 auto takeoff_client = auto_apms_util::ActionClientWrapper<TakeoffAction>(node_ptr, "takeoff");
34 auto land_client = auto_apms_util::ActionClientWrapper<LandAction>(node_ptr, "land");
35
36 RCLCPP_INFO(node_ptr->get_logger(), "Arming ...");
37
38 ArmDisarmAction::Goal arm_goal;
39 arm_goal.arming_state = arm_goal.ARMING_STATE_ARM;
40 auto arm_future = arm_disarm_client.syncSendGoal(arm_goal);
41
42 if (arm_future.wait_for(0s) == std::future_status::ready && !arm_future.get()) {
43 std::cerr << "Arming goal was rejected\n";
44 rclcpp::shutdown();
45 return EXIT_FAILURE;
46 }
47
48 while (rclcpp::spin_until_future_complete(node_ptr, arm_future, 1s) != rclcpp::FutureReturnCode::SUCCESS) {
49 RCLCPP_INFO(node_ptr->get_logger(), "Waiting for the vehicle to be armed");
50 if (!rclcpp::ok()) {
51 rclcpp::shutdown();
52 return EXIT_FAILURE;
53 }
54 }
55
56 auto arm_result = arm_future.get();
57
58 if (!arm_result) {
59 std::cerr << "Arm result is nullptr\n";
60 rclcpp::shutdown();
61 return EXIT_FAILURE;
62 }
63
64 if ((*arm_result).code == rclcpp_action::ResultCode::SUCCEEDED) {
65 RCLCPP_INFO(node_ptr->get_logger(), "Arming succeeded");
66 } else {
67 std::cerr << "Arming did not succeed\n";
68 rclcpp::shutdown();
69 return EXIT_FAILURE;
70 }
71
72 RCLCPP_INFO(node_ptr->get_logger(), "Taking off ...");
73
74 TakeoffAction::Goal takeoff_goal;
75 takeoff_goal.altitude_amsl_m = 1e9;
76 auto takeoff_future = takeoff_client.syncSendGoal(takeoff_goal);
77
78 if (takeoff_future.wait_for(0s) == std::future_status::ready && !takeoff_future.get()) {
79 std::cerr << "Takeoff goal was rejected\n";
80 rclcpp::shutdown();
81 return EXIT_FAILURE;
82 }
83
84 // Wait for a few seconds here before aborting the takeoff task
85 rclcpp::sleep_for(5s);
86
87 RCLCPP_INFO(node_ptr->get_logger(), "Canceling takeoff ...");
88
89 if (!takeoff_client.syncCancelLastGoal()) {
90 std::cerr << "Cancellation of takeoff was rejected\n";
91 rclcpp::shutdown();
92 return EXIT_FAILURE;
93 }
94
95 RCLCPP_INFO(node_ptr->get_logger(), "Landing ...");
96
97 auto land_future = land_client.syncSendGoal();
98
99 if (land_future.wait_for(0s) == std::future_status::ready && !land_future.get()) {
100 std::cerr << "Landing goal was rejected\n";
101 rclcpp::shutdown();
102 return EXIT_FAILURE;
103 }
104
105 while (rclcpp::spin_until_future_complete(node_ptr, land_future, 1s) != rclcpp::FutureReturnCode::SUCCESS) {
106 RCLCPP_INFO(node_ptr->get_logger(), "Waiting for landing");
107 if (!rclcpp::ok()) {
108 rclcpp::shutdown();
109 return EXIT_FAILURE;
110 }
111 }
112
113 auto land_result = land_future.get();
114
115 if (!land_result) {
116 std::cerr << "Land result is nullptr\n";
117 rclcpp::shutdown();
118 return EXIT_FAILURE;
119 }
120
121 if ((*land_result).code == rclcpp_action::ResultCode::SUCCEEDED) {
122 RCLCPP_INFO(node_ptr->get_logger(), "Landing succeeded");
123 } else {
124 std::cerr << "Landing did not succeed\n";
125 rclcpp::shutdown();
126 return EXIT_FAILURE;
127 }
128
129 rclcpp::shutdown();
130 return EXIT_SUCCESS;
131}
Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.