forked from LiHongbo97/ROS-formation-and-attacker
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathattacker
302 lines (277 loc) · 10.2 KB
/
attacker
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
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
#!/usr/bin/env python
####################################################################
#This is attacker#
# Author: Hongbo Li 2019.05.09#
import rospy
import time
from geometry_msgs.msg import Twist, Point, Quaternion
import tf
from math import radians, copysign, sqrt, pow, pi, atan2,sin,cos
from tf.transformations import euler_from_quaternion
import numpy as np
from sensor_msgs.msg import LaserScan
msg = """
control your Turtlebot3!
-----------------------
this is attacker
-----------------------
"""
binge=1
follower1_pos=Point()
follower2_pos=Point()
follower3_pos=Point()
follower4_pos=Point()
leader_pos=Point()
follower1_vel=Twist()
follower2_vel=Twist()
follower3_vel=Twist()
follower4_vel=Twist()
leader_vel=Twist()
attacker_vel=Twist()
K1=0.2
K2=0.1
K3=1
alpha=0
detect_R=0.8
safe_r1=0.2
safe_r2=0.4
ID=0
posex=[0,0]
posey=[0,0]
ideal_posx=[0,0]
ideal_posy=[0,0]
attmse=[0,0,0]
class GotoPoint():
def __init__(self):
rospy.init_node('attacker', anonymous=False)
rospy.on_shutdown(self.shutdown)
self.cmd_vel = rospy.Publisher('cmd_vel', Twist, queue_size=5)#5
self.attacker_positon=rospy.Publisher('/attacker_pos',Point,queue_size=5)#5
position = Point()
move_cmd = Twist()
r = rospy.Rate(10)
self.tf_listener = tf.TransformListener()
self.odom_frame = '/attacker/odom'
# self.base_frame = '/follower2/base_footprint'
try:
self.tf_listener.waitForTransform(self.odom_frame, '/attacker/base_footprint', rospy.Time(), rospy.Duration(1.0))
self.base_frame = '/attacker/base_footprint'
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
try:
self.tf_listener.waitForTransform(self.odom_frame, '/attacker/base_link', rospy.Time(), rospy.Duration(1.0))
self.base_frame = '/attacker/base_link'
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("Cannot find transform between odom and base_link or base_footprint")
rospy.signal_shutdown("tf Exception")
global follower1_pos
global follower2_pos
global leader_pos
global follower1_vel
global follower2_vel
global leader_vel
(position, rotation) = self.get_odom()
rospy.Subscriber('/follower1_pos',Point,point_callback_1)
# rospy.Subscriber('/follower2_pos',Point,point_callback_2)
# rospy.Subscriber('/follower3_pos',Point,point_callback_3)
# rospy.Subscriber('/follower4_pos',Point,point_callback_4)
rospy.Subscriber('/leader_pos',Point,point_callback_5)
rospy.Subscriber('/follower1/cmd_vel',Twist,vel_callback_1)
# rospy.Subscriber('/follower2/cmd_vel',Twist,vel_callback_2)
# rospy.Subscriber('/follower3/cmd_vel',Twist,vel_callback_3)
# rospy.Subscriber('/follower4/cmd_vel',Twist,vel_callback_4)
rospy.Subscriber('/leader/cmd_vel',Twist,vel_callback_5)
avo=1
self.attacker_positon.publish(position)
if leader_pos.x==0:
print "wrong"
leader_pos.x=leader_pos.x+1
leader_pos.y=leader_pos.y
#wirte here
sum_posex=0
sum_posey=0
attmse[2]=0
posex=[follower1_pos.x-1.0,leader_pos.x-0.5]
posey=[follower1_pos.y+1,leader_pos.y+1]
vx=[follower1_vel.linear.x,leader_vel.linear.x]
vz=[follower1_vel.angular.z,leader_vel.angular.z]
print (posex)
print (posey)
for i in range(1,3):
ideal_posx[i-1]=posex[i-1]+vx[i-1]*0.1*cos(vz[i-1])
ideal_posy[i-1]=posey[i-1]+vx[i-1]*0.1*sin(vz[i-1])
sum_posex=sum_posex+posex[i-1]
sum_posey=sum_posey+posey[i-1]
attmse[i-1]=sqrt(pow(posex[i-1]-ideal_posx[i-1], 2) + pow(posey[i-1]-ideal_posy[i-1], 2))
attmse[2]=attmse[2]+attmse[i-1]
print ('the sum_posex=%f'%(sum_posex))
# print ('the sum_posey=%f'%(sum_posey))
print ('the attmse[2]=%f'%(attmse[2]))
if attmse[2]>0.3:
att_posex=sum_posex/2
att_posey=sum_posey/2
else:
att_posex=ideal_posx[1]
att_posey=ideal_posy[1]
att_delta_x=att_posex-position.x
att_delta_y=att_posey-position.y
if abs(att_delta_x)<0.05:
att_delta_x=0
if abs(att_delta_y)<0.05:
att_delta_y=0
att_goal_z=atan2(att_delta_y,att_delta_x)
if att_delta_x==0 and att_delta_y==0:
att_goal_z=0
dist_att=sqrt(pow(att_delta_x, 2) + pow(att_delta_y, 2))
angular_now=rotation
phi=att_goal_z
pos_nodes=[follower1_pos,leader_pos]
# lidar_nodes=self.lidar(position)
# if lidar_nodes.x!=10 and abs(lidar_nodes.x-position.x)>0.1:
# #pos_nodes=[follower1_pos,follower2_pos,follower3_pos,follower4_pos,leader_pos,lidar_nodes]
# pos_nodes=[follower1_pos,follower2_pos,leader_pos]
# else:
# pos_nodes=[follower1_pos,follower2_pos,leader_pos]
temp_x_sum=0
temp_y_sum=0
for i in range(len(pos_nodes)):
r=sqrt(pow(pos_nodes[i].x-position.x,2)+pow(pos_nodes[i].y-position.y,2))
print ('distance between %d is %f'%(i,r))
if r<detect_R:
temp_x=(1/r-1/detect_R)*(pos_nodes[ID].x-pos_nodes[i].x)
temp_y=(1/r-1/detect_R)*(pos_nodes[ID].y-pos_nodes[i].y)
temp_fenmu=pow(r,3)
temp_x=temp_x/temp_fenmu
temp_y=temp_y/temp_fenmu
temp_x_sum=temp_x_sum+temp_x
temp_y_sum=temp_y_sum+temp_y
if r>safe_r2:
avo=10
elif r<safe_r1:
avo=50
else:
avo=25
avoid_delta=temp_x_sum*abs(cos(angular_now))+temp_y_sum*abs(sin(angular_now))
delta_theta=self.compute_theta(phi,angular_now)
if abs(delta_theta)>0.5:
attacker_vel.linear.x=0.1+avo*avoid_delta
# attacker_vel.linear.x=0
attacker_vel.angular.z=delta_theta
else:
attacker_vel.linear.x=dist_att*0.3+K1*(att_delta_x*cos(angular_now)+att_delta_y*sin(angular_now))+avo*avoid_delta
# attacker_vel.linear.x=0
attacker_vel.angular.z=0.5*delta_theta
# attacker_vel.linear.x=dist_att*0.6+K1*(att_delta_x*sin(angular_now)+att_delta_y*cos(angular_now))+avo*avoid_delta
# delta_theta=self.compute_theta(phi,angular_nxow)
# attacker_vel.angular.z=delta_theta
print ('the att_delta_x=%f'%(att_delta_x))
print ('the att_delta_y=%f'%(att_delta_y))
print ('the distant=%f'%(dist_att))
print ('the vel=%f'%(attacker_vel.linear.x))
print ('the delta_ang=%f'%(delta_theta))
self.cmd_vel.publish(attacker_vel)
# (position, rotation) = self.get_odom()
msgs ="""this is attacker_theta"""
print msgs
def lidar(self,tb_pos):
#print 12
msg = rospy.wait_for_message("scan", LaserScan)
#print (msg)
LIDAR_ERR = 0.05
LIDAR_MAX = 2
obstacle=[]
min_dis=3
min_ang=0
min_point=Point()
for i in range(360):
if i <= 90 or i > 270 and i!=0:
obstacle_pos=Point()
if msg.ranges[i] >= LIDAR_ERR and msg.ranges[i]<=LIDAR_MAX and msg.ranges[i]>0.17:
obstacle_pos.x=tb_pos.x+msg.ranges[i]*cos(i*2*pi/360)
obstacle_pos.y=tb_pos.y+msg.ranges[i]*sin(i*2*pi/360)
obstacle.append(obstacle_pos)
if msg.ranges[i] < min_dis:
min_dis = msg.ranges[i]
min_ang = i
if min_dis<3:
min_point.x=tb_pos.x+min_dis*cos(i*2*pi/360)
min_point.y=tb_pos.y+min_dis*sin(i*2*pi/360)
min_point.z=min_ang
else:
min_point.x=-1000
min_point.y=-1000
return min_point
def compute_theta(self,theta,rotation1):
if theta*rotation1<0:
if theta>0:
if abs(rotation1)+theta<=pi:
w=abs(rotation1)+theta
else:
w=-(2*pi+rotation1-theta)
else:
if rotation1+abs(theta)<=pi:
w=-(abs(theta)+rotation1)
else:
w=(2*pi-rotation1+theta)
else:
w=theta-rotation1
return w
def get_odom(self):
try:
(trans, rot) = self.tf_listener.lookupTransform(self.odom_frame, self.base_frame, rospy.Time(0))
rotation = euler_from_quaternion(rot)
except (tf.Exception, tf.ConnectivityException, tf.LookupException):
rospy.loginfo("TF Exception")
return
return (Point(*trans), rotation[2])
def shutdown(self):
self.cmd_vel.publish(Twist())
rospy.sleep(1)
def point_callback_1(data):
global follower1_pos
follower1_pos.x=data.x
follower1_pos.y=data.y
def point_callback_2(data):
global follower2_pos
follower2_pos.x=data.x
follower2_pos.y=data.y
def point_callback_3(data):
global follower3_pos
follower3_pos.x=data.x
follower3_pos.y=data.y
def point_callback_4(data):
global follower4_pos
follower4_pos.x=data.x
follower4_pos.y=data.y
def point_callback_5(data):
global leader_pos
leader_pos.x=data.x
leader_pos.y=data.y
def vel_callback_1(data):
global follower1_vel
follower1_vel.linear.x=data.linear.x
follower1_vel.angular.z=data.angular.z
def vel_callback_2(data):
global follower2_vel
follower2_vel.linear.x=data.linear.x
follower2_vel.angular.z=data.angular.z
def vel_callback_3(data):
global follower3_vel
follower3_vel.linear.x=data.linear.x
follower3_vel.angular.z=data.angular.z
def vel_callback_4(data):
global follower4_vel
follower4_vel.linear.x=data.linear.x
follower4_vel.angular.z=data.angular.z
def vel_callback_5(data):
global leader_vel
leader_vel.linear.x=data.linear.x
leader_vel.angular.z=data.angular.z
if __name__ == '__main__':
try:
while not rospy.is_shutdown():
print(msg)
binge=binge+1
GotoPoint()
except:
rospy.loginfo("shutdown program.")
# print bingg