-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathControl.py
505 lines (488 loc) · 23.1 KB
/
Control.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
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
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
# -*- coding: utf-8 -*-
import time
import math
# import smbus
import copy
import threading
from IMU import *
from PID import *
import numpy as np
from Servo import *
from Command import COMMAND as cmd
class Control:
def __init__(self):
self.imu=IMU()
self.servo=Servo()
self.pid = Incremental_PID(0.5,0.0,0.0025)
self.speed = 8
self.height = 99
self.timeout = 0
self.move_flag = 0
self.move_count = 0
self.move_timeout = 0
self.order = ['','','','','']
self.point = [[0, 99, 10], [0, 99, 10], [0, 99, -10], [0, 99, -10]]
self.calibration_point = self.readFromTxt('point')
self.angle = [[90,0,0],[90,0,0],[90,0,0],[90,0,0]]
self.calibration_angle=[[0,0,0],[0,0,0],[0,0,0],[0,0,0]]
self.relax_flag=True
self.balance_flag=False
self.attitude_flag=False
self.Thread_conditiona=threading.Thread(target=self.condition)
self.calibration()
self.relax(True)
# Head
self.servo.setServoAngle(15,90)
# Tail Code
self.TailCorrection = -9
self.wagStep = 3 #how much angle changes per step
self.tailWagging = False
# self.wagCount = 0
self.tailLeft = True
self.tailAngle = 90 + self.TailCorrection
self.tailReset()
def tailThread(self):
# Tail Code
while self.tailWagging:
self.wagTail()
time.sleep(0.01)
def wagTail(self):
# # print("Tailstep: " + str(tailStep))
self.servo.setServoAngle(14, self.tailAngle)
if self.tailLeft:
self.tailAngle = self.tailAngle + self.wagStep
else:
self.tailAngle = self.tailAngle - self.wagStep
if self.tailAngle > 135 + self.TailCorrection:
self.tailAngle = self.tailAngle - self.wagStep
self.tailLeft = False
if self.tailAngle < 45 + self.TailCorrection:
self.tailAngle = self.tailAngle + self.wagStep
self.tailLeft = True
def tailReset(self):
if self.tailAngle > 90 + self.TailCorrection:
for i in range(self.tailAngle, 90 + self.TailCorrection, -1):
self.servo.setServoAngle(14, i)
time.sleep(0.003)
if self.tailAngle < 90 + self.TailCorrection:
for i in range(self.tailAngle, 90 + self.TailCorrection, 1):
self.servo.setServoAngle(14, i)
time.sleep(0.003)
self.tailAngle = 90 + self.TailCorrection
self.servo.setServoAngle(14, self.tailAngle)
def readFromTxt(self,filename):
file1 = open(filename + ".txt", "r")
list_row = file1.readlines()
list_source = []
for i in range(len(list_row)):
column_list = list_row[i].strip().split("\t")
list_source.append(column_list)
for i in range(len(list_source)):
for j in range(len(list_source[i])):
list_source[i][j] = int(list_source[i][j])
file1.close()
return list_source
def saveToTxt(self,list, filename):
file2 = open(filename + '.txt', 'w')
for i in range(len(list)):
for j in range(len(list[i])):
file2.write(str(list[i][j]))
file2.write('\t')
file2.write('\n')
file2.close()
def coordinateToAngle(self,x,y,z,l1=23,l2=55,l3=55):
a=math.pi/2-math.atan2(z,y)
x_3=0
x_4=l1*math.sin(a)
x_5=l1*math.cos(a)
l23=math.sqrt((z-x_5)**2+(y-x_4)**2+(x-x_3)**2)
w=(x-x_3)/l23
v=(l2*l2+l23*l23-l3*l3)/(2*l2*l23)
b=math.asin(round(w,2))-math.acos(round(v,2))
c=math.pi-math.acos(round((l2**2+l3**2-l23**2)/(2*l3*l2),2))
a=round(math.degrees(a))
b=round(math.degrees(b))
c=round(math.degrees(c))
return a,b,c
def angleToCoordinate(self,a,b,c,l1=23,l2=55,l3=55):
a=math.pi/180*a
b=math.pi/180*b
c=math.pi/180*c
x=l3*math.sin(b+c)+l2*math.sin(b)
y=l3*math.sin(a)*math.cos(b+c)+l2*math.sin(a)*math.cos(b)+l1*math.sin(a)
z=l3*math.cos(a)*math.cos(b+c)+l2*math.cos(a)*math.cos(b)+l1*math.cos(a)
return x,y,z
def calibration(self):
for i in range(4):
self.calibration_angle[i][0],self.calibration_angle[i][1],self.calibration_angle[i][2]=self.coordinateToAngle(self.calibration_point[i][0],
self.calibration_point[i][1],
self.calibration_point[i][2])
for i in range(4):
self.angle[i][0],self.angle[i][1],self.angle[i][2]=self.coordinateToAngle(self.point[i][0],
self.point[i][1],
self.point[i][2])
for i in range(4):
self.calibration_angle[i][0]=self.calibration_angle[i][0]-self.angle[i][0]
self.calibration_angle[i][1]=self.calibration_angle[i][1]-self.angle[i][1]
self.calibration_angle[i][2]=self.calibration_angle[i][2]-self.angle[i][2]
def run(self):
if self.checkPoint():
try:
for i in range(4): #we have 4 points each containing an xyz co-ord
#these are converted to angle sets where each set of co-ords becomes a set of 3 angles
self.angle[i][0],self.angle[i][1],self.angle[i][2]=self.coordinateToAngle(self.point[i][0],
self.point[i][1],
self.point[i][2])
#now we have 4 sets of 3 angles [0][0] to [3][2]
for i in range(2):
self.angle[i][0]=self.restriction(self.angle[i][0]+self.calibration_angle[i][0],0,180) #restriction keeps angle within range 0 to 180
self.angle[i][1]=self.restriction(90-(self.angle[i][1]+self.calibration_angle[i][1]),0,180) #FOR [0][1] and [1][1] we use 90 - the angle LEFT SHOULDER FB
self.angle[i][2]=self.restriction(self.angle[i][2]+self.calibration_angle[i][2],0,180)
self.angle[i+2][0]=self.restriction(self.angle[i+2][0]+self.calibration_angle[i+2][0],0,180)
self.angle[i+2][1]=self.restriction(90+self.angle[i+2][1]+self.calibration_angle[i+2][1],0,180) #FOR [2][1] and [3][1] we use 90 + the angle RIGHT SHOULDER FB
self.angle[i+2][2]=self.restriction(180-(self.angle[i+2][2]+self.calibration_angle[i+2][2]),0,180) #FOR [2][2] and [3][2] we use 180 - the angle RIGHT KNEE/ELBOW
for i in range(2): #these 4 sets of 3 angles (ie 12 angles) are now applied to the 12 leg servos
self.servo.setServoAngle(4+i*3,self.angle[i][0]) # 4 7 LF shoulder LR shoulder servo 4 gets angle [0][0] servo 7 gets [1][0]
self.servo.setServoAngle(3+i*3,self.angle[i][1]) # 3 6 LF elbow LR elbow [0][1] [1][1]
self.servo.setServoAngle(2+i*3,self.angle[i][2]) # 2 5 LF wrist LR wrist [0][2] [1][2]
self.servo.setServoAngle(8+i*3,self.angle[i+2][0]) # 8 11 RR FR shoulders [2][0] [3][0]
self.servo.setServoAngle(9+i*3,self.angle[i+2][1]) # 9 12 RR FR elbows [2][1] [3][1]
self.servo.setServoAngle(10+i*3,self.angle[i+2][2]) #10 13 RR FR wrists [2][2] [3][2]
except Exception as e:
pass
else:
print("\nThis coordinate point is out of the active range" + str(self.point) + "\n")
def checkPoint(self):
flag=True
leg_lenght=[0,0,0,0,0,0]
for i in range(4):
leg_lenght[i]=math.sqrt(self.point[i][0]**2+self.point[i][1]**2+self.point[i][2]**2)
for i in range(4):
if leg_lenght[i] > 130 or leg_lenght[i] < 25:
flag=False
return flag
def condition(self):
print("starting condition thread")
while True:
try:
if time.time()-self.move_timeout > 60 and self.move_timeout!=0 and self.relax_flag==True:
self.move_count=0
self.move_timeout=time.time()
if self.move_count < 180:
if (time.time()-self.timeout)>10 and self.timeout!=0 and self.relax_flag==False and self.order[0] == '':
self.timeout=time.time()
self.relax_flag=True
self.relax(True)
self.order=['','','','','']
if self.relax_flag==True and self.order[0] != '' and self.order[0] !=cmd.CMD_RELAX:
self.relax(False)
self.relax_flag=False
if self.attitude_flag==True and self.order[0] !=cmd.CMD_ATTITUDE and self.order[0] != '':
self.stop()
self.attitude_flag=False
if self.relax_flag==False:
self.move_count+=time.time()-self.move_timeout
self.move_timeout=time.time()
if self.order[0]==cmd.CMD_MOVE_STOP:
self.order=['','','','','']
self.stop()
elif self.order[0]==cmd.CMD_MOVE_FORWARD:
self.speed=int(self.order[1])
self.forWard()
elif self.order[0]==cmd.CMD_MOVE_BACKWARD:
self.speed=int(self.order[1])
self.backWard()
elif self.order[0]==cmd.CMD_MOVE_LEFT:
self.speed=int(self.order[1])
self.setpLeft()
elif self.order[0]==cmd.CMD_MOVE_RIGHT:
self.speed=int(self.order[1])
self.setpRight()
elif self.order[0]==cmd.CMD_TURN_LEFT:
self.speed=int(self.order[1])
self.turnLeft()
elif self.order[0]==cmd.CMD_TURN_RIGHT:
self.speed=int(self.order[1])
self.turnRight()
elif self.order[0]==cmd.CMD_RELAX:
if self.relax_flag:
self.relax_flag=False
self.relax(False)
else:
self.relax_flag=True
self.relax(True)
self.order=['','','','','']
elif self.order[0]==cmd.CMD_HEIGHT:
self.upAndDown(int(self.order[1]))
self.order=['','','','','']
elif self.order[0]==cmd.CMD_HORIZON:
self.beforeAndAfter(int(self.order[1]))
self.order=['','','','','']
elif self.order[0]==cmd.CMD_ATTITUDE:
self.attitude_flag=True
self.attitude(self.order[1],self.order[2],self.order[3])
elif self.order[0]==cmd.CMD_CALIBRATION:
self.move_count=0
if self.order[1]=="one":
self.calibration_point[0][0]=int(self.order[2])
self.calibration_point[0][1]=int(self.order[3])
self.calibration_point[0][2]=int(self.order[4])
self.calibration()
self.run()
elif self.order[1]=="two":
self.calibration_point[1][0]=int(self.order[2])
self.calibration_point[1][1]=int(self.order[3])
self.calibration_point[1][2]=int(self.order[4])
self.calibration()
self.run()
elif self.order[1]=="three":
self.calibration_point[2][0]=int(self.order[2])
self.calibration_point[2][1]=int(self.order[3])
self.calibration_point[2][2]=int(self.order[4])
self.calibration()
self.run()
elif self.order[1]=="four":
self.calibration_point[3][0]=int(self.order[2])
self.calibration_point[3][1]=int(self.order[3])
self.calibration_point[3][2]=int(self.order[4])
self.calibration()
self.run()
elif self.order[1]=="save":
self.saveToTxt(self.calibration_point,'point')
self.stop()
elif self.order[0]==cmd.CMD_BALANCE and self.order[1]=='1':
Thread_IMU=threading.Thread(target=self.IMU6050())
Thread_IMU.start()
break
elif self.move_count > 180 :
self.relax_flag=True
self.relax(True)
if self.move_flag!=1:
self.move_flag=1
if self.move_count > 240:
self.move_count=0
self.move_flag=0
self.order=['','','','','']
except Exception as e:
print(e)
def restriction(self,var,v_min,v_max):
if var < v_min:
return v_min
elif var > v_max:
return v_max
else:
return var
def map(self,value,fromLow,fromHigh,toLow,toHigh):
return (toHigh-toLow)*(value-fromLow) / (fromHigh-fromLow) + toLow
def changeCoordinates(self,move_order,X1=0,Y1=96,Z1=0,X2=0,Y2=96,Z2=0,pos=np.mat(np.zeros((3, 4)))):
if move_order == 'turnLeft':
for i in range(2):
self.point[2*i][0]=((-1)**(1+i))*X1+10
self.point[2*i][1]=Y1
self.point[2*i][2]=((-1)**(i))*Z1+((-1)**i)*10
self.point[1+2*i][0]=((-1)**(1+i))*X2+10
self.point[1+2*i][1]=Y2
self.point[1+2*i][2]=((-1)**(1+i))*Z2+((-1)**i)*10
elif move_order == 'turnRight':
for i in range(2):
self.point[2*i][0]=((-1)**(i))*X1+10
self.point[2*i][1]=Y1
self.point[2*i][2]=((-1)**(1+i))*Z1+((-1)**i)*10
self.point[1+2*i][0]=((-1)**(i))*X2+10
self.point[1+2*i][1]=Y2
self.point[1+2*i][2]=((-1)**(i))*Z2+((-1)**i)*10
elif (move_order == 'height') or (move_order == 'horizon'):
for i in range(2):
self.point[3*i][0]=X1+10
self.point[3*i][1]=Y1
self.point[1+i][0]=X2+10
self.point[1+i][1]=Y2
elif move_order == 'Attitude Angle':
for i in range(2):
self.point[3-i][0]=pos[0,1+2*i]+10
self.point[3-i][1]=pos[2,1+2*i]
self.point[3-i][2]=pos[1,1+2*i]
self.point[i][0]=pos[0,2*i]+10
self.point[i][1]=pos[2,2*i]
self.point[i][2]=pos[1,2*i]
else: #'backWard' 'forWard' 'setpRight' 'setpLeft'
for i in range(2):
self.point[i*2][0]=X1+10
self.point[i*2][1]=Y1
self.point[i*2+1][0]=X2+10
self.point[i*2+1][1]=Y2
self.point[i*2][2]=Z1+((-1)**i)*10
self.point[i*2+1][2]=Z2+((-1)**i)*10
self.run()
def backWard(self):
for i in range(450,89,-self.speed):
X1=12*math.cos(i*math.pi/180)
Y1=6*math.sin(i*math.pi/180)+self.height
X2=12*math.cos((i+180)*math.pi/180)
Y2=6*math.sin((i+180)*math.pi/180)+self.height
if Y2 > self.height:
Y2=self.height
if Y1 > self.height:
Y1=self.height
self.changeCoordinates('backWard',X1,Y1,0,X2,Y2,0)
#time.sleep(0.01)
def forWard(self):
for i in range(90,451,self.speed):
X1=12*math.cos(i*math.pi/180)
Y1=6*math.sin(i*math.pi/180)+self.height
X2=12*math.cos((i+180)*math.pi/180)
Y2=6*math.sin((i+180)*math.pi/180)+self.height
if Y2 > self.height:
Y2=self.height
if Y1 > self.height:
Y1=self.height
self.changeCoordinates('forWard',X1,Y1,0,X2,Y2,0)
#time.sleep(0.01)
def turnLeft(self):
for i in range(0,361,self.speed):
X1=3*math.cos(i*math.pi/180)
Y1=8*math.sin(i*math.pi/180)+self.height
X2=3*math.cos((i+180)*math.pi/180)
Y2=8*math.sin((i+180)*math.pi/180)+self.height
if Y2 > self.height:
Y2=self.height
if Y1 > self.height:
Y1=self.height
Z1=X1
Z2=X2
self.changeCoordinates('turnLeft',X1,Y1,Z1,X2,Y2,Z2)
#time.sleep(0.01)
def turnRight(self):
for i in range(0,361,self.speed):
X1=3*math.cos(i*math.pi/180)
Y1=8*math.sin(i*math.pi/180)+self.height
X2=3*math.cos((i+180)*math.pi/180)
Y2=8*math.sin((i+180)*math.pi/180)+self.height
if Y2 > self.height:
Y2=self.height
if Y1 > self.height:
Y1=self.height
Z1=X1
Z2=X2
self.changeCoordinates('turnRight',X1,Y1,Z1,X2,Y2,Z2)
#time.sleep(0.01)
def stop(self):
p=[[10, self.height, 10], [10, self.height, 10], [10, self.height, -10], [10, self.height, -10]]
for i in range(4):
p[i][0]=(p[i][0]-self.point[i][0])/50
p[i][1]=(p[i][1]-self.point[i][1])/50
p[i][2]=(p[i][2]-self.point[i][2])/50
for j in range(50):
for i in range(4):
self.point[i][0]+=p[i][0]
self.point[i][1]+=p[i][1]
self.point[i][2]+=p[i][2]
self.run()
def setpLeft(self):
for i in range(90,451,self.speed):
Z1=10*math.cos(i*math.pi/180)
Y1=5*math.sin(i*math.pi/180)+self.height
Z2=10*math.cos((i+180)*math.pi/180)
Y2=5*math.sin((i+180)*math.pi/180)+self.height
if Y1 > self.height:
Y1=self.height
if Y2 > self.height:
Y2=self.height
self.changeCoordinates('setpLeft',0,Y1,Z1,0,Y2,Z2)
#time.sleep(0.01)
def setpRight(self):
for i in range(450,89,-self.speed):
Z1=10*math.cos(i*math.pi/180)
Y1=5*math.sin(i*math.pi/180)+self.height
Z2=10*math.cos((i+180)*math.pi/180)
Y2=5*math.sin((i+180)*math.pi/180)+self.height
if Y1 > self.height:
Y1=self.height
if Y2 > self.height:
Y2=self.height
self.changeCoordinates('setpRight',0,Y1,Z1,0,Y2,Z2)
#time.sleep(0.01)
def relax(self,flag=False):
if flag==True:
p=[[55, 78, 0], [55, 78, 0], [55, 78, 0], [55, 78, 0]]
for i in range(4):
p[i][0]=(self.point[i][0]-p[i][0])/50
p[i][1]=(self.point[i][1]-p[i][1])/50
p[i][2]=(self.point[i][2]-p[i][2])/50
for j in range(1,51):
for i in range(4):
self.point[i][0]-=p[i][0]
self.point[i][1]-=p[i][1]
self.point[i][2]-=p[i][2]
self.run()
if self.move_timeout!=0:
self.move_count+=time.time()-self.move_timeout
self.move_timeout=time.time()
else:
self.stop()
self.move_timeout=time.time()
def upAndDown(self,var):
self.height=var+99
self.changeCoordinates('height',0,self.height,0,0,self.height,0)
def beforeAndAfter(self,var):
self.changeCoordinates('horizon',var,self.height,0,var,self.height,0)
def attitude(self,r,p,y):
r=self.map(int(r),-20,20,-10,10)
p=self.map(int(p),-20,20,-10,10)
y=self.map(int(y),-20,20,-10,10)
pos=self.postureBalance(r,p,y,0)
self.changeCoordinates('Attitude Angle',pos=pos)
def IMU6050(self):
self.balance_flag=True
self.order=['','','','','']
pos=self.postureBalance(0,0,0)
self.changeCoordinates('Attitude Angle',pos=pos)
time.sleep(2)
self.imu.Error_value_accel_data,self.imu.Error_value_gyro_data=self.imu.average_filter()
time.sleep(1)
while True:
self.move_count+=time.time()-self.move_timeout
self.move_timeout=time.time()
r,p,y=self.imu.imuUpdate()
r=self.pid.PID_compute(r)
p=self.pid.PID_compute(p)
pos=self.postureBalance(r,p,0)
self.changeCoordinates('Attitude Angle',pos=pos)
if (self.order[0]==cmd.CMD_BALANCE and self.order[1]=='0')or(self.balance_flag==True and self.order[0]!='')or(self.move_count>180):
Thread_conditiona=threading.Thread(target=self.condition)
Thread_conditiona.start()
self.balance_flag==False
break
def postureBalance(self,r,p,y,h=1):
b = 76
w = 76
l = 136
if h!=0:
h=self.height
pos = np.mat([0.0, 0.0, h ]).T
rpy = np.array([r, p, y]) * math.pi / 180
R, P, Y = rpy[0], rpy[1], rpy[2]
rotx = np.mat([[ 1, 0, 0 ],
[ 0, math.cos(R), -math.sin(R)],
[ 0, math.sin(R), math.cos(R)]])
roty = np.mat([[ math.cos(P), 0, -math.sin(P)],
[ 0, 1, 0 ],
[ math.sin(P), 0, math.cos(P)]])
rotz = np.mat([[ math.cos(Y), -math.sin(Y), 0 ],
[ math.sin(Y), math.cos(Y), 0 ],
[ 0, 0, 1 ]])
rot_mat = rotx * roty * rotz
body_struc = np.mat([[ l / 2, b / 2, 0],
[ l / 2, -b / 2, 0],
[-l / 2, b / 2, 0],
[-l / 2, -b / 2, 0]]).T
footpoint_struc = np.mat([[(l / 2), (w / 2)+10, self.height-h],
[ (l / 2), (-w / 2)-10, self.height-h],
[(-l / 2), (w / 2)+10, self.height-h],
[(-l / 2), (-w / 2)-10, self.height-h]]).T
AB = np.mat(np.zeros((3, 4)))
for i in range(4):
AB[:, i] = pos + rot_mat * footpoint_struc[:, i] - body_struc[:, i]
return (AB)
if __name__=='__main__':
pass