-
Notifications
You must be signed in to change notification settings - Fork 0
/
s.py
364 lines (296 loc) · 10.9 KB
/
s.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
from SimpleXMLRPCServer import SimpleXMLRPCServer
from SimpleXMLRPCServer import SimpleXMLRPCRequestHandler
import serial
import param_vars
import sys
from time import sleep
from time import time
ser_x80 = serial.Serial('/dev/ttyPCH1', param_vars.baud_rate)
ser_x81 = serial.Serial('/dev/ttyPCH2', param_vars.baud_rate)
start_const = 25000
k_const = 10000
class RequestHandler(SimpleXMLRPCRequestHandler):
rpc_paths = ('/RPC2',)
# Create server
server = SimpleXMLRPCServer(("localhost", 8000),
requestHandler=RequestHandler, logRequests = False, allow_none = True)
# logRequests = False suppresses all output from the server about date and host location.
server.register_introspection_functions()
# Functions such as system.listMethods()
def derp():
sleep(3)
server.register_function(derp)
################
def drive_motor(board_num, motor, speed):
if (board_num == 0x80):
ser = ser_x80
else:
ser = ser_x81
if ((board_num > 0x87) or (board_num < 0x80)):
print "Roboclaw board number is out of the scope of possible addresses."
return param_vars.e_code
if ((motor != 0) and (motor != 1)):
print "Please select motor 0 or 1. Yes, I know the boards say 1 and 2. Yes, I know that doesn't make any sense."
return param_vars.e_code
command = (35 - param_vars.motor_min + motor) # In case I decide to go with a 1-2 schema.
speed_byte3 = speed & 0xff #Least significant bit
speed = speed >> 8
speed_byte2 = speed & 0xff
speed = speed >> 8
speed_byte1 = speed & 0xff
speed = speed >> 8
speed_byte0 = speed & 0xff # Most significant bit
checksum = (board_num + command + speed_byte0 + speed_byte1 + speed_byte2 + speed_byte3) & 0x7f
cmdList = [board_num, command, speed_byte0, speed_byte1, speed_byte2, speed_byte3, checksum]
# Written MSB to LSB, per the spec sheet.
for i in range(len(cmdList)):
ser.write(chr(cmdList[i]))
#print cmdList[i]
return 0;
server.register_function(drive_motor, 'drive_motor')
################
def read_encoder(board_num, motor):
if (board_num == 0x80):
ser = ser_x80
else:
ser = ser_x81
if ((board_num > 0x87) or (board_num < 0x80)):
print "Roboclaw board number is out of the scope of possible addresses."
return param_vars.e_code
if ((motor != 0) and (motor != 1)):
print "Please select motor 0 or 1. Yes, I know the boards say 1 and 2. Yes, I know that doesn't make any sense."
return param_vars.e_code
command = (30 - param_vars.motor_min + motor) # In case I decide to go with a 1-2 schema.
data = [] # Declared before doing the serial just in case it would mess up timing otherwise.
ser.write(chr(board_num)) # Write a command to read motor speed, 32 bit resolution.
ser.write(chr(command)) # See roboclaw documentation for further detail
#Since the serial data is kind of touchy, we NEED to implement a mutex flag for accessing the roboc1law: otherwise, our data will get corrupted and we won't be able to command the motors as we need to.
for i in range(6):
data.append(ser.read())
speed = (data[0].encode("hex")) + (data[1].encode("hex")) + (data[2].encode("hex")) + (data[3].encode("hex"))
#print speed ## Hex value
speed = int(speed, 16)
if ((ord(data[4]) == 1) and (speed != 0)):
speed = ~(0xffffffff - speed) + 1
# print speed #Signed ticks/125th seconde value
rotations_per_second = float(speed) * 125 / 8192 # *125/8192 --> resolution in 125ths of a second, and then (apparently) 8192 ticks per rotation.
return rotations_per_second
server.register_function(read_encoder, 'read_encoder')
#######################
def stop():
stop_1 = [0x80, 35, 0, 0, 0, 0, 0x23]
stop_2 = [0x80, 36, 0, 0, 0, 0, 0x24]
stop_3 = [0x81, 35, 0, 0, 0, 0, 0x24]
stop_4 = [0x81, 36, 0, 0, 0, 0, 0x25]
for i in range(len(stop_1)):
ser_x80.write(chr(stop_1[i]))
for i in range(len(stop_2)):
ser_x80.write(chr(stop_2[i]))
#ser_x81.write(chr(stop_3[i]))
for i in range(len(stop_4)):
ser_x81.write(chr(stop_4[i]))
return 0
server.register_function(stop, 'stop')
#######################
def p_control(s_command1, s_command2, s_command3, rps_d1, rps_d2, rps_d3, k1, k2, k3):
start_time = time()
rotations_per_second1 = read_speed(1)
rotations_per_second2 = read_speed(2)
rotations_per_second3 = read_speed(3)
diff1 = abs(rps_d1 - rotations_per_second1)
diff2 = abs(rps_d2 - rotations_per_second2)
diff3 = abs(rps_d3 - rotations_per_second3)
if (diff1 > diff2 and diff1 > diff3):
# Change speed 1
change_speed(1, s_command1)
if (diff2 > diff3):
# Change speed 2
# Change speed 3
change_speed(2, s_command2)
change_speed(3, s_command3)
else:
#Change speed 3
#Change speed 2
change_speed(3, s_command3)
change_speed(2, s_command2)
elif (diff2 > diff3 and diff2 > diff1):
#Change speed 2
change_speed(2, s_command2)
if (diff1 > diff3):
#change speed 1
#change speed 3
change_speed(1, s_command1)
change_speed(3, s_command3)
else:
#change speed 3
#change speed 1
change_speed(3, s_command3)
change_speed(1, s_command1)
elif (diff3 > diff1 and diff3 > diff2):
#Change speed 3
change_speed(3, s_command3)
if (diff1 > diff2):
#Change speed 1
#Change speed 2
change_speed(1, s_command1)
change_speed(2, s_command2)
else:
#Change speed 2
#Change speed 1
change_speed(2, s_command2)
change_speed(1, s_command1)
count = 0
mdiff_1 = abs(float(int(rps_d1)) * 125/8192)
mdiff_2 = abs(float(int(rps_d2)) * 125/8192)
mdiff_3 = abs(float(int(rps_d3)) * 125/8192) #Maximum differences between speed desired and actual speed
print mdiff_1
print mdiff_2
print mdiff_3
while((count < 10) and ((abs(diff1) > mdiff_1) or (abs(diff2) > mdiff_2) or (abs(diff3) > mdiff_3))):
count = count + 1
sleep(0.15) #Kind of arbitrary
rotations_per_second1 = read_speed(1)
rotations_per_second2 = read_speed(2)
rotations_per_second3 = read_speed(3)
diff1 = rps_d1 - rotations_per_second1
diff2 = rps_d2 - rotations_per_second2
diff3 = rps_d3 - rotations_per_second3 # Differences for the proportional loop
# print diff1
# print diff2
# print diff3
# print "****************"
s_command1 = s_command1 + k1 * diff1
s_command2 = s_command2 + k2 * diff2
s_command3 = s_command3 + k3 * diff3
change_speed(1, s_command1)
change_speed(2, s_command2)
change_speed(3, s_command3)
stop_time = time()
time_elapsed = stop_time - start_time
return time_elapsed
def change_speed(motor_num, speed):
speed = int(speed)
if (motor_num == 1):
board_num = 0x80
command = 35
serial = ser_x80
elif (motor_num == 2):
board_num = 0x81
command = 36
serial = ser_x81
elif (motor_num == 3):
board_num = 0x80
command = 36
serial = ser_x80
else:
print "Not a possibility."
speed_byte3 = speed & 0xff #Least significant bit
speed = speed >> 8
speed_byte2 = speed & 0xff
speed = speed >> 8
speed_byte1 = speed & 0xff
speed = speed >> 8
speed_byte0 = speed & 0xff # Most significant bit
checksum = (board_num + command + speed_byte0 + speed_byte1 + speed_byte2 + speed_byte3) & 0x7f
cmdList = [board_num, command, speed_byte0, speed_byte1, speed_byte2, speed_byte3, checksum]
for i in range(len(cmdList)):
serial.write(chr(cmdList[i]))
# print cmdList[i]
return 0;
def read_speed(motor_num):
if (motor_num == 1):
board_num = 0x80
command = 30
serial = ser_x80
elif (motor_num == 2):
board_num = 0x81
command = 30
serial = ser_x81
elif (motor_num == 3):
board_num = 0x80
command = 31 ## OK, this is seriously a major WTF here. I need to see if the board is wired wrong or something.
serial = ser_x80
data = []
serial.write(chr(board_num))
serial.write(chr(command))
for i in range(6):
data.append(serial.read())
speed = (data[0].encode("hex")) + (data[1].encode("hex")) + (data[2].encode("hex")) + (data[3].encode("hex"))
speed = int(speed, 16)
if ((ord(data[4]) == 1) and (speed != 0)):
speed = ~(0xffffffff - speed) + 1
rotations_per_second = float(speed) * 125 / 8192
return rotations_per_second
server.register_function(p_control)
###################################
def spin(time, bogo):
time_passed = p_control(start_const, start_const, start_const, 3, 3, 3, k_const, k_const, k_const)
sleep(time - time_passed)
print read_speed(1)
print read_speed(2)
print read_speed(3)
stop()
return 0
server.register_function(spin)
###################################
def square(side_length): # In feet
sleep_time = (side_length * 0.3048) / 0.15 ## Assuming driving 0.15 m/s
time_passed = p_control(start_const * 2, -1*start_const, -1*start_const, 1.1423, -0.57, -0.57, k_const, k_const, k_const) # 0.15 m/s in X
sleep(sleep_time - time_passed)
time_passed = p_control(0, start_const*1.5, start_const*-1.5, 0, 0.98, -0.98, k_const, k_const, k_const) # 0.15 m/s in X
sleep(sleep_time - time_passed)
time_passed = p_control(start_const * -2, start_const, start_const, -1.1423, 0.57, 0.57, k_const, k_const, k_const) # 0.15 m/s in X
sleep(sleep_time - time_passed)
time_passed = p_control(0, start_const*-1.5, start_const*1.5, 0, -0.98, 0.98, k_const, k_const, k_const) # 0.15 m/s in X
sleep(sleep_time - time_passed)
stop()
return 0
server.register_function(square)
###################################
def drive_forward(distance): ## at 15 cm/sec
time = float(distance) * 0.3048 / 0.19 * 0.75
#time_passed = p_control(2*start_const, -1 * start_const, -1 *start_const, 1.14, -0.57, -0.57, k_const, k_const, k_const)
change_speed(1, -80000)
change_speed(2, 68000)
sleep(time)
stop()
server.register_function(drive_forward)
##################################
def rotate_one_sixth(): ## Left
time_final = 1 # Designed for a rotation of 1/6th circle/sec
mult = 0.5
time_p = p_control(start_const * mult, start_const * mult, start_const * mult, 0.2941, 0.2941, 0.2941, k_const, k_const, k_const) ## Primed for 20 degrees/sec rotation
stop()
return 0
server.register_function(rotate_one_sixth)
##################################
def rotate_one_sixth_dir(direction):
#Left = 0, right = 1
#Right is positive
time_final = 1
mult = 0.5
if (direction == 0):
time_p = p_control(start_const * mult * -1, start_const * mult * -1, start_const * mult * -1, -0.2941, -0.2941, -0.2941, k_const, k_const, k_const)
stop()
return 0
else:
time_p = p_control(start_const * mult, start_const * mult, start_const * mult, 0.2941, 0.2941, 0.2941, k_const, k_const, k_const)
stop()
return 0
server.register_function(rotate_one_sixth_dir)
##################################
def rotate_degrees(degrees):
if (degrees > 0):
time_final = degrees/20
time_p = p_control(start_const / 2, start_const /2, start_const / 2, 0.1485, 0.1485, 0.1485, k_const, k_const, k_const) ## Primed for 20 degrees/sec rotation
sleep (time_final - time_p)
stop()
else:
time_final = degrees / -20
time_p = p_control(start_const / -2, start_const /-2, start_const / -2, -0.1485, -0.1485, -0.1485, k_const, k_const, k_const)
sleep (time_final - time_p)
stop()
server.register_function(rotate_degrees)
###################################
# Run the server's main loop
server.serve_forever()