This repository has been archived by the owner on Mar 4, 2019. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathactuator.py
348 lines (272 loc) · 9.76 KB
/
actuator.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
"""
actuators.py
Classes to control the motors and servos. These classes
are wrapped in a mixer class before being used in the drive loop.
"""
import time
import donkeycar as dk
import serial
import struct
ser = serial.Serial("/dev/ttyUSB0", 9600)
ser.baudrate = 9600
ser.flushInput()
print("initialized serial")
class two_wheel_arduino:
def __init__(self, channel, frequency=60):
print("sending ready code to arduino")
time.sleep(1)
self.sendcode(224)
self.channel = channel
#self.prevSendCode = 50
def set_pulse(self, pulse):
self.sendcode(pulse)
def run(self, pulse):
self.set_pulse(pulse)
def sendcode(self, code):
#if self.prevSendCode != code:
print("sendcode %s" % code)
#self.prevSendCode = code
ser.write(struct.pack('>B', code))
'''
class PCA9685:
PWM motor controler using PCA9685 boards.
This is used for most RC Cars
def __init__(self, channel, frequency=60):
import Adafruit_PCA9685
# Initialise the PCA9685 using the default address (0x40).
#self.pwm = Adafruit_PCA9685.PCA9685()
#self.pwm.set_pwm_freq(frequency)
#self.channel = channel
#`def set_pulse(self, pulse):
#self.pwm.set_pwm(self.channel, 0, pulse)
#print("pulse " + str(pulse))
def run(self, pulse):
self.set_pulse(pulse)
'''
class PWMSteering:
"""
Wrapper over a PWM motor cotnroller to convert angles to PWM pulses.
"""
LEFT_ANGLE = -1
RIGHT_ANGLE = 1
def __init__(self, controller=None,
left_pulse=0,
right_pulse=100):
self.controller = controller
self.left_pulse = left_pulse
self.right_pulse = right_pulse
def run(self, angle):
#map absolute angle to angle that vehicle can implement.
pulse = dk.utils.map_range(angle,
self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
self.controller.set_pulse(pulse)
def shutdown(self):
self.run(0) #set steering straight
class PWMThrottle:
"""
Wrapper over a PWM motor cotnroller to convert -1 to 1 throttle
values to PWM pulses.
"""
MIN_THROTTLE = -1
MAX_THROTTLE = 1
def __init__(self, controller=None,
max_pulse=300,
min_pulse=490,
zero_pulse=350):
self.controller = controller
self.max_pulse = max_pulse
self.min_pulse = min_pulse
self.zero_pulse = zero_pulse
#send zero pulse to calibrate ESC
self.controller.set_pulse(self.zero_pulse)
time.sleep(1)
def run(self, throttle):
if throttle > 0:
pulse = dk.utils.map_range(throttle,
0, self.MAX_THROTTLE,
self.zero_pulse, self.max_pulse)
else:
pulse = dk.utils.map_range(throttle,
self.MIN_THROTTLE, 0,
self.min_pulse, self.zero_pulse)
self.controller.set_pulse(pulse)
def shutdown(self):
self.run(0) #stop vehicle
class Adafruit_DCMotor_Hat:
'''
Adafruit DC Motor Controller
Used for each motor on a differential drive car.
'''
def __init__(self, motor_num):
from Adafruit_MotorHAT import Adafruit_MotorHAT, Adafruit_DCMotor
import atexit
self.FORWARD = Adafruit_MotorHAT.FORWARD
self.BACKWARD = Adafruit_MotorHAT.BACKWARD
self.mh = Adafruit_MotorHAT(addr=0x60)
self.motor = self.mh.getMotor(motor_num)
self.motor_num = motor_num
atexit.register(self.turn_off_motors)
self.speed = 0
self.throttle = 0
def run(self, speed):
'''
Update the speed of the motor where 1 is full forward and
-1 is full backwards.
'''
if speed > 1 or speed < -1:
raise ValueError( "Speed must be between 1(forward) and -1(reverse)")
self.speed = speed
self.throttle = int(dk.utils.map_range(abs(speed), -1, 1, -255, 255))
if speed > 0:
self.motor.run(self.FORWARD)
else:
self.motor.run(self.BACKWARD)
self.motor.setSpeed(self.throttle)
def shutdown(self):
self.mh.getMotor(self.motor_num).run(Adafruit_MotorHAT.RELEASE)
class Maestro:
'''
Pololu Maestro Servo controller
Use the MaestroControlCenter to set the speed & acceleration values to 0!
'''
import threading
maestro_device = None
astar_device = None
maestro_lock = threading.Lock()
astar_lock = threading.Lock()
def __init__(self, channel, frequency = 60):
import serial
if Maestro.maestro_device == None:
Maestro.maestro_device = serial.Serial('/dev/ttyACM0', 115200)
self.channel = channel
self.frequency = frequency
self.lturn = False
self.rturn = False
self.headlights = False
self.brakelights = False
if Maestro.astar_device == None:
Maestro.astar_device = serial.Serial('/dev/ttyACM2', 115200, timeout= 0.01)
def set_pulse(self, pulse):
# Recalculate pulse width from the Adafruit values
w = pulse * (1 / (self.frequency * 4096)) # in seconds
w *= 1000 * 1000 # in microseconds
w *= 4 # in quarter microsenconds the maestro wants
w = int(w)
with Maestro.maestro_lock:
Maestro.maestro_device.write(bytearray([ 0x84,
self.channel,
(w & 0x7F),
((w >> 7) & 0x7F)]))
def set_turn_left(self, v):
if self.lturn != v:
self.lturn = v
b = bytearray('L' if v else 'l', 'ascii')
with Maestro.astar_lock:
Maestro.astar_device.write(b)
def set_turn_right(self, v):
if self.rturn != v:
self.rturn = v
b = bytearray('R' if v else 'r', 'ascii')
with Maestro.astar_lock:
Maestro.astar_device.write(b)
def set_headlight(self, v):
if self.headlights != v:
self.headlights = v
b = bytearray('H' if v else 'h', 'ascii')
with Maestro.astar_lock:
Maestro.astar_device.write(b)
def set_brake(self, v):
if self.brakelights != v:
self.brakelights = v
b = bytearray('B' if v else 'b', 'ascii')
with Maestro.astar_lock:
Maestro.astar_device.write(b)
def readline(self):
ret = None
with Maestro.astar_lock:
# expecting lines like
# E n nnn n
if Maestro.astar_device.inWaiting() > 8:
ret = Maestro.astar_device.readline()
if ret != None:
ret = ret.rstrip()
return ret
class Teensy:
'''
Teensy Servo controller
'''
import threading
teensy_device = None
astar_device = None
teensy_lock = threading.Lock()
astar_lock = threading.Lock()
def __init__(self, channel, frequency = 60):
import serial
if Teensy.teensy_device == None:
Teensy.teensy_device = serial.Serial('/dev/teensy', 115200, timeout = 0.01)
self.channel = channel
self.frequency = frequency
self.lturn = False
self.rturn = False
self.headlights = False
self.brakelights = False
if Teensy.astar_device == None:
Teensy.astar_device = serial.Serial('/dev/astar', 115200, timeout = 0.01)
def set_pulse(self, pulse):
# Recalculate pulse width from the Adafruit values
w = pulse * (1 / (self.frequency * 4096)) # in seconds
w *= 1000 * 1000 # in microseconds
with Teensy.teensy_lock:
Teensy.teensy_device.write(("%c %.1f\n" % (self.channel, w)).encode('ascii'))
def set_turn_left(self, v):
if self.lturn != v:
self.lturn = v
b = bytearray('L' if v else 'l', 'ascii')
with Teensy.astar_lock:
Teensy.astar_device.write(b)
def set_turn_right(self, v):
if self.rturn != v:
self.rturn = v
b = bytearray('R' if v else 'r', 'ascii')
with Teensy.astar_lock:
Teensy.astar_device.write(b)
def set_headlight(self, v):
if self.headlights != v:
self.headlights = v
b = bytearray('H' if v else 'h', 'ascii')
with Teensy.astar_lock:
Teensy.astar_device.write(b)
def set_brake(self, v):
if self.brakelights != v:
self.brakelights = v
b = bytearray('B' if v else 'b', 'ascii')
with Teensy.astar_lock:
Teensy.astar_device.write(b)
def teensy_readline(self):
ret = None
with Teensy.teensy_lock:
# expecting lines like
# E n nnn n
if Teensy.teensy_device.inWaiting() > 8:
ret = Teensy.teensy_device.readline()
if ret != None:
ret = ret.rstrip()
return ret
def astar_readline(self):
ret = None
with Teensy.astar_lock:
# expecting lines like
# E n nnn n
if Teensy.astar_device.inWaiting() > 8:
ret = Teensy.astar_device.readline()
if ret != None:
ret = ret.rstrip()
return ret
class MockController(object):
def __init__(self):
pass
def run(self, pulse):
pass
def shutdown(self):
pass