-
Notifications
You must be signed in to change notification settings - Fork 9
Expand file tree
/
Copy pathrect_with_yaw.cpp
More file actions
188 lines (158 loc) · 6.5 KB
/
Copy pathrect_with_yaw.cpp
File metadata and controls
188 lines (158 loc) · 6.5 KB
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
177
178
179
180
181
182
183
184
185
186
187
188
#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
#include <math.h>
#include "common/printf_utils.h"
using namespace std;
mavros_msgs::State current_state;
geometry_msgs::PoseStamped curr_pos; // 无人机当前位置
geometry_msgs::PoseStamped aim_pos; // 无人机目标位置
geometry_msgs::TwistStamped curr_vel; // 无人机当前速度
void printf_info();
bool is_arrive(geometry_msgs::PoseStamped pos1, geometry_msgs::PoseStamped pos2);
void state_cb(const mavros_msgs::State::ConstPtr& msg){
current_state = *msg;
//ROS_INFO("current mode: %s",current_state.mode.c_str());
//ROS_INFO("system_status: %d",current_state.system_status);
}
void arrive_pos(const geometry_msgs::PoseStamped::ConstPtr& msg){
curr_pos = *msg;
//cout <<GREEN <<fabs((*msg).pose.position.z - aim_pos.pose.position.z) <<endl;
}
void velocityCallback(const geometry_msgs::TwistStamped::ConstPtr& msg)
{
curr_vel = *msg;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "rect");
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 set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
("mavros/set_mode");
ros::Subscriber local_pos_sub = nh.subscribe<geometry_msgs::PoseStamped>
("mavros/local_position/pose",10,arrive_pos);
ros::Subscriber vel_sub = nh.subscribe<geometry_msgs::TwistStamped>
("/mavros/local_position/velocity_local", 10, velocityCallback);
//the setpoint publishing rate MUST be faster than 2Hz
ros::Rate rate(20.0); // 20Hz
// wait for FCU connection
while(ros::ok() && !current_state.connected){
ros::spinOnce();
rate.sleep();
}
//geometry_msgs::PoseStamped aim_pos;
aim_pos.pose.position.x = 0;
aim_pos.pose.position.y = 0;
aim_pos.pose.position.z = 2;
//send a few setpoints before starting
for(int i = 100; ros::ok() && i > 0; --i){
local_pos_pub.publish(aim_pos);
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;
ros::Time last_request = ros::Time::now();
int count = 0;
double yaw = 0.0;
while(ros::ok()){
if( current_state.mode != "OFFBOARD" &&
(ros::Time::now() - last_request > ros::Duration(5.0))){
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();
}
else{
if(is_arrive(aim_pos,curr_pos)){
count++;
if(count == 20) // 10s
{
aim_pos.pose.position.x = 20;
aim_pos.pose.position.y = 0;
aim_pos.pose.position.z = 2;
}
if(count == 40) // 30s
{
aim_pos.pose.position.x = 20;
aim_pos.pose.position.y = 20;
aim_pos.pose.position.z = 2;
yaw = M_PI / 2;
}
if(count == 60) // 45s
{
aim_pos.pose.position.x = 0;
aim_pos.pose.position.y = 20;
aim_pos.pose.position.z = 2;
yaw = M_PI;
}
if(count == 80) // 60s
{
aim_pos.pose.position.x = 0;
aim_pos.pose.position.y = 0;
aim_pos.pose.position.z = 2;
yaw = -M_PI / 2;
}
if(count >= 100) // 75s
{
mavros_msgs::SetMode land_set_mode;
land_set_mode.request.custom_mode = "AUTO.LAND"; // 发送降落命令
if( current_state.mode != "AUTO.LAND" && set_mode_client.call(land_set_mode) && land_set_mode.response.mode_sent){
ROS_INFO("land enabled");
}
//任务结束,关闭该节点
ros::shutdown();
}
}
} // else
}
aim_pos.pose.orientation.w = cos(yaw/2);
aim_pos.pose.orientation.x = 0.0;
aim_pos.pose.orientation.y = 0.0;
aim_pos.pose.orientation.z = sin(yaw/2);
local_pos_pub.publish(aim_pos);
ros::spinOnce();
printf_info();
rate.sleep();
}
return 0;
}
void printf_info(){
cout<<YELLOW<<"<<<<<<<<<<<<< Uav Info <<<<<<<<<<<<<<<<\n";
cout<<GREEN<<"current mode: "<< current_state.mode <<endl;
cout<<GREEN<<"system status: "<< current_state.system_status <<endl;
cout<<GREEN<<"uav pos [x,y,z]: "<< curr_pos.pose.position.x <<"[m] "
<< curr_pos.pose.position.y <<"[m] "<< curr_pos.pose.position.z <<"[m]"<<endl;
cout<<GREEN<<"Linear Vel [x, y, z]: "<< curr_vel.twist.linear.x <<"[m/s] "
<< curr_vel.twist.linear.y <<"[m/s] "<< curr_vel.twist.linear.z <<"[m/s]"<<endl;
cout<<GREEN<<"Angular Vel [x, y, z]: "<< curr_vel.twist.angular.x <<"[rad/s] "
<< curr_vel.twist.angular.y <<"[rad/s] "<< curr_vel.twist.angular.z <<"[rad/s]"<<endl;
}
bool is_arrive(geometry_msgs::PoseStamped pos1, geometry_msgs::PoseStamped pos2){
if(fabs(pos1.pose.position.x - pos2.pose.position.x) < 0.1 &&
fabs(pos1.pose.position.y - pos2.pose.position.y) < 0.1 &&
fabs(pos1.pose.position.z - pos2.pose.position.z) < 0.1){
return true;
}
return false;
}