-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathforwardv2.py
178 lines (145 loc) · 4.87 KB
/
forwardv2.py
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
#!/usr/bin/env python
import math
import rospy
import time
from mavros_msgs.msg import MountControl
from geometry_msgs.msg import PoseStamped, Quaternion, TwistStamped, Twist
from std_msgs.msg import Header
from std_msgs.msg import String
offset_data = [0.0, 0.0, 0, 0.0]
search=0
alphadrone=0
betadrone=0
alphagimbal=0
betagimbal=0
def callback1(data):
global offset_data
global search
searchold=offset_data[0]
new_offset_data= True
offset_data[0] = float(data.data.split(' ')[0])
offset_data[1] = float(data.data.split(' ')[1])
offset_data[2] = float(data.data.split(' ')[2])
if(searchold==offset_data[0]):
search=search+1
else:
search=0
def callpose(data1):
global alphadrone
global betadrone
wdegree=2*math.acos(data1.pose.orientation.w)
zdegree=2*math.asin(data1.pose.orientation.z)
k=0
alphadrone=math.cos(wdegree)
if((math.degrees(wdegree)<180 and zdegree<0) or (math.degrees(wdegree)>180 and zdegree>0)):
betadrone=-1*math.sqrt(1-(alphadrone*alphadrone))
else:
betadrone=math.sqrt(1-(alphadrone*alphadrone))
def callpose1(data2):
global alphagimbal
global betagimbal
wdegree=2*math.acos(data2.w)
zdegree=2*math.asin(data2.z)
k=0
alphagimbal=math.cos(wdegree)
if((math.degrees(wdegree)<180 and zdegree<0) or (math.degrees(wdegree)>180 and zdegree>0)):
betagimbal=-1*math.sqrt(1-(alphagimbal*alphagimbal))
else:
betagimbal=math.sqrt(1-(alphagimbal*alphagimbal))
def move_forward():
searched_angle = 0
pub = rospy.Publisher('/uav1/mavros/setpoint_velocity/cmd_vel', TwistStamped, queue_size=10)
gimbal_setangle_pub = rospy.Publisher('/uav1/mavros/mount_control/command', MountControl, queue_size=10)
rospy.init_node('velocity', anonymous=True)
rospy.Subscriber('/uav1/mavros/local_position/pose', PoseStamped, callpose)
rospy.Subscriber("twistexample", String, callback1)
rospy.Subscriber('/uav1/mavros/mount_control/orientation', Quaternion, callpose1)
msg = TwistStamped()
rate = rospy.Rate(10) # 10hz
msg.header=Header()
msg.twist=Twist()
gimbal_message = MountControl()
gimbal_message.header = Header()
gimbal_message.mode = 2
a=0
I=0.0
Mv_bar=0.0
e_prev=0
Mv=0.0
Iang=0
eang_prev=0
Mvang=0
t=0
gimbal_yaw=0
gimbal_pitch=0
while not rospy.is_shutdown():
msg.header.stamp= rospy.Time.now()
msg.header.seq=1
gimbal_message.header.stamp= rospy.Time.now()
gimbal_message.header.seq=1
gimbal_message.roll = 0.0
rospy.loginfo("%f %f %f %f %f %f",alphadrone,betadrone,alphagimbal,betagimbal, (alphadrone*alphagimbal-betadrone*betagimbal),-1*(alphadrone*betagimbal+betadrone*alphagimbal))
if(search>10):
rospy.loginfo("search")
msg.twist.linear.x=0.0
msg.twist.linear.y=0.0
msg.twist.linear.z=0.0
I=0
Iang=0
t=0
elif(offset_data[0]!=0.0):
e=gimbal_pitch
P=0.08*e
I=I+0.003*e*(0.33)
D=0.001*(e-e_prev)/0.33
Mv=Mv_bar + P + I + D
gimbal_pitch+=(offset_data[1]-0.5)*-30
msg.twist.linear.x = 20*(alphadrone*alphagimbal-betadrone*betagimbal);
msg.twist.linear.y = -20*(alphadrone*betagimbal+betadrone*alphagimbal);
msg.twist.linear.z = Mv;
rospy.loginfo("%f %f %f %f",Mv,P,I,D)
e_prev=e
if(search>10):
msg.twist.angular.x = 0.0;
msg.twist.angular.y = 0.0;
msg.twist.angular.z = 0.0;
gimbal_yaw+=10
searched_angle+=10
if(searched_angle%1080<360):
gimbal_pitch = 0
pass
elif(searched_angle%1080<720):
gimbal_pitch = -45;
pass
else:
gimbal_pitch = 0
#TODO yukari tasi
pass
elif(offset_data[0]!=0.0):
searched_angle = 0
eang=(180-gimbal_yaw%360)
Pang=0.01*eang
Iang=Iang+0.001*eang*0.2
Dang=0.001*(eang-eang_prev)
Mvang=Pang+Iang+Dang
gimbal_yaw+=(offset_data[0]-0.5)*50
msg.twist.angular.x = 0.0;
msg.twist.angular.y = 0.0;
msg.twist.angular.z = Mvang;
eang_prev=eang
else:
searched_angle = 0
msg.twist.angular.x = 0.0;
msg.twist.angular.y = 0.0;
msg.twist.angular.z = 0.0;
gimbal_message.pitch = gimbal_pitch
gimbal_message.yaw = gimbal_yaw
gimbal_setangle_pub.publish(gimbal_message)
pub.publish(msg)
time.sleep(0.5)
rate.sleep()
if __name__ == '__main__':
try:
move_forward()
except rospy.ROSInterruptException:
pass