-
Notifications
You must be signed in to change notification settings - Fork 15
/
takeoff_n_land.cpp
176 lines (149 loc) · 5.06 KB
/
takeoff_n_land.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
/**
* @file offb_node.cpp
* @brief offboard example node, written with mavros version 0.14.2, px4 flight
* stack and tested in Gazebo SITL
*/
#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/CommandTOL.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
#define FLIGHT_ALTITUDE 1.5f
mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr& msg){
current_state = *msg;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "offb_node");
ros::NodeHandle nh;
ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>
("mavros/state", 10, state_cb);
ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>
("mavros/setpoint_position/local", 10);
ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>
("mavros/cmd/arming");
ros::ServiceClient land_client = nh.serviceClient<mavros_msgs::CommandTOL>
("mavros/cmd/land");
ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
("mavros/set_mode");
//the setpoint publishing rate MUST be faster than 2Hz
ros::Rate rate(20.0);
// wait for FCU connection
while(ros::ok() && current_state.connected){
ros::spinOnce();
rate.sleep();
ROS_INFO("connecting to FCT...");
}
geometry_msgs::PoseStamped pose;
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = FLIGHT_ALTITUDE;
//send a few setpoints before starting
for(int i = 100; ros::ok() && i > 0; --i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
mavros_msgs::SetMode offb_set_mode;
offb_set_mode.request.custom_mode = "OFFBOARD";
mavros_msgs::CommandBool arm_cmd;
arm_cmd.request.value = true;
mavros_msgs::CommandTOL land_cmd;
land_cmd.request.yaw = 0;
land_cmd.request.latitude = 0;
land_cmd.request.longitude = 0;
land_cmd.request.altitude = 0;
ros::Time last_request = ros::Time::now();
// change to offboard mode and arm
while(ros::ok() && !current_state.armed){
if( current_state.mode != "OFFBOARD" &&
(ros::Time::now() - last_request > ros::Duration(5.0))){
ROS_INFO(current_state.mode.c_str());
if( set_mode_client.call(offb_set_mode) &&
offb_set_mode.response.mode_sent){
ROS_INFO("Offboard enabled");
}
last_request = ros::Time::now();
} else {
if( !current_state.armed &&
(ros::Time::now() - last_request > ros::Duration(5.0))){
if( arming_client.call(arm_cmd) &&
arm_cmd.response.success){
ROS_INFO("Vehicle armed");
}
last_request = ros::Time::now();
}
}
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
// go to the first waypoint
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = FLIGHT_ALTITUDE;
ROS_INFO("going to the first way point");
for(int i = 0; ros::ok() && i < 10*20; ++i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("first way point finished!");
// go to the second waypoint
pose.pose.position.x = 0;
pose.pose.position.y = 1;
pose.pose.position.z = FLIGHT_ALTITUDE;
//send setpoints for 10 seconds
ROS_INFO("going to second way point");
for(int i = 0; ros::ok() && i < 10*20; ++i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("second way point finished!");
// go to the third waypoint
pose.pose.position.x = 1;
pose.pose.position.y = 1;
pose.pose.position.z = FLIGHT_ALTITUDE;
//send setpoints for 10 seconds
ROS_INFO("going to third way point");
for(int i = 0; ros::ok() && i < 10*20; ++i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("third way point finished!");
// go to the forth waypoint
pose.pose.position.x = 1;
pose.pose.position.y = 0;
pose.pose.position.z = FLIGHT_ALTITUDE;
//send setpoints for 10 seconds
ROS_INFO("going to forth way point");
for(int i = 0; ros::ok() && i < 10*20; ++i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("forth way point finished!");
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = FLIGHT_ALTITUDE;
ROS_INFO("going back to the first point!");
//send setpoints for 10 seconds
for(int i = 0; ros::ok() && i < 10*20; ++i){
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("tring to land");
while (!(land_client.call(land_cmd) &&
land_cmd.response.success)){
//local_pos_pub.publish(pose);
ROS_INFO("tring to land");
ros::spinOnce();
rate.sleep();
}
return 0;
}