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"
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;
25int main(
int argc,
char * argv[])
27 rclcpp::init(argc, argv);
30 auto node_ptr = std::make_shared<rclcpp::Node>(
"takeoff_and_land_example");
36 RCLCPP_INFO(node_ptr->get_logger(),
"Arming ...");
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);
42 if (arm_future.wait_for(0s) == std::future_status::ready && !arm_future.get()) {
43 std::cerr <<
"Arming goal was rejected\n";
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");
56 auto arm_result = arm_future.get();
59 std::cerr <<
"Arm result is nullptr\n";
64 if ((*arm_result).code == rclcpp_action::ResultCode::SUCCEEDED) {
65 RCLCPP_INFO(node_ptr->get_logger(),
"Arming succeeded");
67 std::cerr <<
"Arming did not succeed\n";
72 RCLCPP_INFO(node_ptr->get_logger(),
"Taking off ...");
74 TakeoffAction::Goal takeoff_goal;
75 takeoff_goal.altitude_amsl_m = 1e9;
76 auto takeoff_future = takeoff_client.syncSendGoal(takeoff_goal);
78 if (takeoff_future.wait_for(0s) == std::future_status::ready && !takeoff_future.get()) {
79 std::cerr <<
"Takeoff goal was rejected\n";
85 rclcpp::sleep_for(5s);
87 RCLCPP_INFO(node_ptr->get_logger(),
"Canceling takeoff ...");
89 if (!takeoff_client.syncCancelLastGoal()) {
90 std::cerr <<
"Cancellation of takeoff was rejected\n";
95 RCLCPP_INFO(node_ptr->get_logger(),
"Landing ...");
97 auto land_future = land_client.syncSendGoal();
99 if (land_future.wait_for(0s) == std::future_status::ready && !land_future.get()) {
100 std::cerr <<
"Landing goal was rejected\n";
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");
113 auto land_result = land_future.get();
116 std::cerr <<
"Land result is nullptr\n";
121 if ((*land_result).code == rclcpp_action::ResultCode::SUCCEEDED) {
122 RCLCPP_INFO(node_ptr->get_logger(),
"Landing succeeded");
124 std::cerr <<
"Landing did not succeed\n";
Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.