-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathactuator.py
923 lines (739 loc) · 28.8 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
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
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
"""
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
class PCA9685:
'''
PWM motor controler using PCA9685 boards.
This is used for most RC Cars
'''
def __init__(self, channel, address=0x40, frequency=60, busnum=None, init_delay=0.1):
self.default_freq = 60
self.pwm_scale = frequency / self.default_freq
import Adafruit_PCA9685
# Initialise the PCA9685 using the default address (0x40).
if busnum is not None:
from Adafruit_GPIO import I2C
# replace the get_bus function with our own
def get_bus():
return busnum
I2C.get_default_bus = get_bus
self.pwm = Adafruit_PCA9685.PCA9685(address=address)
self.pwm.set_pwm_freq(frequency)
self.channel = channel
time.sleep(init_delay) # "Tamiya TBLE-02" makes a little leap otherwise
def set_pulse(self, pulse):
try:
self.pwm.set_pwm(self.channel, 0, int(pulse * self.pwm_scale))
except:
self.pwm.set_pwm(self.channel, 0, int(pulse * self.pwm_scale))
def run(self, pulse):
self.set_pulse(pulse)
class PiGPIO_PWM():
'''
# Use the pigpio python module and daemon to get hardware pwm controls from
# a raspberrypi gpio pins and no additional hardware. Can serve as a replacement
# for PCA9685.
#
# Install and setup:
# sudo apt update && sudo apt install pigpio python3-pigpio
# sudo systemctl start pigpiod
#
# Note: the range of pulses will differ from those required for PCA9685
# and can range from 12K to 170K
#
# If you use a control circuit that inverts the steering signal, set inverted to True
# Default multipler for pulses from config etc is 100
'''
def __init__(self, pin, pgio=None, freq=75, inverted=False):
import pigpio
self.pin = pin
self.pgio = pgio or pigpio.pi()
self.freq = freq
self.inverted = inverted
self.pgio.set_mode(self.pin, pigpio.OUTPUT)
def __del__(self):
self.pgio.stop()
def set_pulse(self, pulse):
self.pgio.hardware_PWM(self.pin, self.freq, int(pulse if self.inverted == False else 1e6 - pulse))
def run(self, pulse):
self.set_pulse(pulse)
class JHat:
'''
PWM motor controler using Teensy emulating PCA9685.
'''
def __init__(self, channel, address=0x40, frequency=60, busnum=None):
print("Firing up the Hat")
import Adafruit_PCA9685
LED0_OFF_L = 0x08
# Initialise the PCA9685 using the default address (0x40).
if busnum is not None:
from Adafruit_GPIO import I2C
# replace the get_bus function with our own
def get_bus():
return busnum
I2C.get_default_bus = get_bus
self.pwm = Adafruit_PCA9685.PCA9685(address=address)
self.pwm.set_pwm_freq(frequency)
self.channel = channel
self.register = LED0_OFF_L+4*channel
# we install our own write that is more efficient use of interrupts
self.pwm.set_pwm = self.set_pwm
def set_pulse(self, pulse):
self.set_pwm(self.channel, 0, pulse)
def set_pwm(self, channel, on, off):
# sets a single PWM channel
self.pwm._device.writeList(self.register, [off & 0xFF, off >> 8])
def run(self, pulse):
self.set_pulse(pulse)
class JHatReader:
'''
Read RC controls from teensy
'''
def __init__(self, channel, address=0x40, frequency=60, busnum=None):
import Adafruit_PCA9685
self.pwm = Adafruit_PCA9685.PCA9685(address=address)
self.pwm.set_pwm_freq(frequency)
self.register = 0 #i2c read doesn't take an address
self.steering = 0
self.throttle = 0
self.running = True
#send a reset
self.pwm._device.writeRaw8(0x06)
def read_pwm(self):
'''
send read requests via i2c bus to Teensy to get
pwm control values from last RC input
'''
h1 = self.pwm._device.readU8(self.register)
# first byte of header must be 100, otherwize we might be reading
# in the wrong byte offset
while h1 != 100:
print("skipping to start of header")
h1 = self.pwm._device.readU8(self.register)
h2 = self.pwm._device.readU8(self.register)
# h2 ignored now
val_a = self.pwm._device.readU8(self.register)
val_b = self.pwm._device.readU8(self.register)
self.steering = (val_b << 8) + val_a
val_c = self.pwm._device.readU8(self.register)
val_d = self.pwm._device.readU8(self.register)
self.throttle = (val_d << 8) + val_c
# scale the values from -1 to 1
self.steering = (((float)(self.steering)) - 1500.0) / 500.0 + 0.158
self.throttle = (((float)(self.throttle)) - 1500.0) / 500.0 + 0.136
def update(self):
while(self.running):
self.read_pwm()
time.sleep(0.015)
def run_threaded(self):
return self.steering, self.throttle
def shutdown(self):
self.running = False
time.sleep(0.1)
class PWMSteering:
"""
Wrapper over a PWM motor controller to convert angles to PWM pulses.
"""
LEFT_ANGLE = -1
RIGHT_ANGLE = 1
def __init__(self,
controller=None,
left_pulse=290,
right_pulse=490):
self.controller = controller
self.left_pulse = left_pulse
self.right_pulse = right_pulse
self.pulse = dk.utils.map_range(0, self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
self.running = True
print('PWM Steering created')
def update(self):
while self.running:
self.controller.set_pulse(self.pulse)
def run_threaded(self, angle):
# map absolute angle to angle that vehicle can implement.
self.pulse = dk.utils.map_range(angle,
self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
def run(self, angle):
self.run_threaded(angle)
self.controller.set_pulse(self.pulse)
def shutdown(self):
# set steering straight
self.pulse = 0
time.sleep(0.3)
self.running = False
class PWMThrottle:
"""
Wrapper over a PWM motor controller 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
self.pulse = zero_pulse
# send zero pulse to calibrate ESC
print("Init ESC")
self.controller.set_pulse(self.max_pulse)
time.sleep(0.01)
self.controller.set_pulse(self.min_pulse)
time.sleep(0.01)
self.controller.set_pulse(self.zero_pulse)
time.sleep(1)
self.running = True
print('PWM Throttle created')
def update(self):
while self.running:
self.controller.set_pulse(self.pulse)
def run_threaded(self, throttle):
if throttle > 0:
self.pulse = dk.utils.map_range(throttle, 0, self.MAX_THROTTLE,
self.zero_pulse, self.max_pulse)
else:
self.pulse = dk.utils.map_range(throttle, self.MIN_THROTTLE, 0,
self.min_pulse, self.zero_pulse)
def run(self, throttle):
self.run_threaded(throttle)
self.controller.set_pulse(self.pulse)
def shutdown(self):
# stop vehicle
self.run(0)
self.running = False
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 is not 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
class L298N_HBridge_DC_Motor(object):
'''
Motor controlled with an L298N hbridge from the gpio pins on Rpi
'''
def __init__(self, pin_forward, pin_backward, pwm_pin, freq = 50):
import RPi.GPIO as GPIO
self.pin_forward = pin_forward
self.pin_backward = pin_backward
self.pwm_pin = pwm_pin
GPIO.setmode(GPIO.BOARD)
GPIO.setup(self.pin_forward, GPIO.OUT)
GPIO.setup(self.pin_backward, GPIO.OUT)
GPIO.setup(self.pwm_pin, GPIO.OUT)
self.pwm = GPIO.PWM(self.pwm_pin, freq)
self.pwm.start(0)
def run(self, speed):
import RPi.GPIO as GPIO
'''
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
max_duty = 90 #I've read 90 is a good max
self.throttle = int(dk.utils.map_range(speed, -1, 1, -max_duty, max_duty))
if self.throttle > 0:
self.pwm.ChangeDutyCycle(self.throttle)
GPIO.output(self.pin_forward, GPIO.HIGH)
GPIO.output(self.pin_backward, GPIO.LOW)
elif self.throttle < 0:
self.pwm.ChangeDutyCycle(-self.throttle)
GPIO.output(self.pin_forward, GPIO.LOW)
GPIO.output(self.pin_backward, GPIO.HIGH)
else:
self.pwm.ChangeDutyCycle(self.throttle)
GPIO.output(self.pin_forward, GPIO.LOW)
GPIO.output(self.pin_backward, GPIO.LOW)
def shutdown(self):
import RPi.GPIO as GPIO
self.pwm.stop()
GPIO.cleanup()
class TwoWheelSteeringThrottle(object):
def run(self, throttle, steering):
if throttle > 1 or throttle < -1:
raise ValueError( "throttle must be between 1(forward) and -1(reverse)")
if steering > 1 or steering < -1:
raise ValueError( "steering must be between 1(right) and -1(left)")
left_motor_speed = throttle
right_motor_speed = throttle
if steering < 0:
left_motor_speed *= (1.0 - (-steering))
elif steering > 0:
right_motor_speed *= (1.0 - steering)
return left_motor_speed, right_motor_speed
def shutdown(self):
pass
class Mini_HBridge_DC_Motor_PWM(object):
'''
Motor controlled with an mini hbridge from the gpio pins on Rpi
This can be using the L298N as above, but wired differently with only
two inputs and no enable line.
https://www.amazon.com/s/ref=nb_sb_noss?url=search-alias%3Dtoys-and-games&field-keywords=Mini+Dual+DC+Motor+H-Bridge+Driver
https://www.aliexpress.com/item/5-pc-2-DC-Motor-Drive-Module-Reversing-PWM-Speed-Dual-H-Bridge-Stepper-Motor-Mini
'''
def __init__(self, pin_forward, pin_backward, freq = 50, max_duty = 90):
'''
max_duy is from 0 to 100. I've read 90 is a good max.
'''
import RPi.GPIO as GPIO
self.pin_forward = pin_forward
self.pin_backward = pin_backward
self.max_duty = max_duty
GPIO.setmode(GPIO.BOARD)
GPIO.setup(self.pin_forward, GPIO.OUT)
GPIO.setup(self.pin_backward, GPIO.OUT)
self.pwm_f = GPIO.PWM(self.pin_forward, freq)
self.pwm_f.start(0)
self.pwm_b = GPIO.PWM(self.pin_backward, freq)
self.pwm_b.start(0)
def run(self, speed):
import RPi.GPIO as GPIO
'''
Update the speed of the motor where 1 is full forward and
-1 is full backwards.
'''
if speed is None:
return
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(speed, -1, 1, -self.max_duty, self.max_duty))
if self.throttle > 0:
self.pwm_f.ChangeDutyCycle(self.throttle)
self.pwm_b.ChangeDutyCycle(0)
elif self.throttle < 0:
self.pwm_f.ChangeDutyCycle(0)
self.pwm_b.ChangeDutyCycle(-self.throttle)
else:
self.pwm_f.ChangeDutyCycle(0)
self.pwm_b.ChangeDutyCycle(0)
def shutdown(self):
import RPi.GPIO as GPIO
self.pwm_f.ChangeDutyCycle(0)
self.pwm_b.ChangeDutyCycle(0)
self.pwm_f.stop()
self.pwm_b.stop()
GPIO.cleanup()
class RPi_GPIO_Servo(object):
'''
Servo controlled from the gpio pins on Rpi
'''
def __init__(self, pin, freq = 50, min=5.0, max=7.8):
import RPi.GPIO as GPIO
self.pin = pin
GPIO.setmode(GPIO.BOARD)
GPIO.setup(self.pin, GPIO.OUT)
self.pwm = GPIO.PWM(self.pin, freq)
self.pwm.start(0)
self.min = min
self.max = max
def run(self, pulse):
import RPi.GPIO as GPIO
'''
Update the speed of the motor where 1 is full forward and
-1 is full backwards.
'''
#I've read 90 is a good max
self.throttle = dk.map_frange(pulse, -1.0, 1.0, self.min, self.max)
#print(pulse, self.throttle)
self.pwm.ChangeDutyCycle(self.throttle)
def shutdown(self):
import RPi.GPIO as GPIO
self.pwm.stop()
GPIO.cleanup()
class ServoBlaster(object):
'''
Servo controlled from the gpio pins on Rpi
This uses a user space service to generate more efficient PWM via DMA control blocks.
Check readme and install here:
https://github.com/richardghirst/PiBits/tree/master/ServoBlaster
cd PiBits/ServoBlaster/user
make
sudo ./servod
will start the daemon and create the needed device file:
/dev/servoblaster
to test this from the command line:
echo P1-16=120 > /dev/servoblaster
will send 1200us PWM pulse to physical pin 16 on the pi.
If you want it to start on boot:
sudo make install
'''
def __init__(self, pin):
self.pin = pin
self.servoblaster = open('/dev/servoblaster', 'w')
self.min = min
self.max = max
def set_pulse(self, pulse):
s = 'P1-%d=%d\n' % (self.pin, pulse)
self.servoblaster.write(s)
self.servoblaster.flush()
def run(self, pulse):
self.set_pulse(pulse)
def shutdown(self):
self.run((self.max + self.min) / 2)
self.servoblaster.close()
class ArduinoFirmata:
'''
PWM controller using Arduino board.
This is particularly useful for boards like Latte Panda with built it Arduino.
Standard Firmata sketch needs to be loaded on Arduino side.
Refer to docs/parts/actuators.md for more details
'''
def __init__(self, servo_pin = 6, esc_pin = 5):
from pymata_aio.pymata3 import PyMata3
self.board = PyMata3()
self.board.sleep(0.015)
self.servo_pin = servo_pin
self.esc_pin = esc_pin
self.board.servo_config(servo_pin)
self.board.servo_config(esc_pin)
def set_pulse(self, pin, angle):
try:
self.board.analog_write(pin, int(angle))
except:
self.board.analog_write(pin, int(angle))
def set_servo_pulse(self, angle):
self.set_pulse(self.servo_pin, int(angle))
def set_esc_pulse(self, angle):
self.set_pulse(self.esc_pin, int(angle))
class ArdPWMSteering:
"""
Wrapper over a Arduino Firmata controller to convert angles to PWM pulses.
"""
LEFT_ANGLE = -1
RIGHT_ANGLE = 1
def __init__(self,
controller=None,
left_pulse=60,
right_pulse=120):
self.controller = controller
self.left_pulse = left_pulse
self.right_pulse = right_pulse
self.pulse = dk.utils.map_range(0, self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
self.running = True
print('Arduino PWM Steering created')
def run(self, angle):
# map absolute angle to angle that vehicle can implement.
self.pulse = dk.utils.map_range(angle,
self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
self.controller.set_servo_pulse(self.pulse)
def shutdown(self):
# set steering straight
self.pulse = dk.utils.map_range(0, self.LEFT_ANGLE, self.RIGHT_ANGLE,
self.left_pulse, self.right_pulse)
time.sleep(0.3)
self.running = False
class ArdPWMThrottle:
"""
Wrapper over Arduino Firmata controller to convert -1 to 1 throttle
values to PWM pulses.
"""
MIN_THROTTLE = -1
MAX_THROTTLE = 1
def __init__(self,
controller=None,
max_pulse=105,
min_pulse=75,
zero_pulse=90):
self.controller = controller
self.max_pulse = max_pulse
self.min_pulse = min_pulse
self.zero_pulse = zero_pulse
self.pulse = zero_pulse
# send zero pulse to calibrate ESC
print("Init ESC")
self.controller.set_esc_pulse(self.max_pulse)
time.sleep(0.01)
self.controller.set_esc_pulse(self.min_pulse)
time.sleep(0.01)
self.controller.set_esc_pulse(self.zero_pulse)
time.sleep(1)
self.running = True
print('Arduino PWM Throttle created')
def run(self, throttle):
if throttle > 0:
self.pulse = dk.utils.map_range(throttle, 0, self.MAX_THROTTLE,
self.zero_pulse, self.max_pulse)
else:
self.pulse = dk.utils.map_range(throttle, self.MIN_THROTTLE, 0,
self.min_pulse, self.zero_pulse)
self.controller.set_esc_pulse(self.pulse)
def shutdown(self):
# stop vehicle
self.run(0)
self.running = False
class RobocarsHat:
'''
Robocars Hat Servo controller
'''
MIN_THROTTLE = -1
MAX_THROTTLE = 1
MIN_STEERING = -1
MAX_STEERING = 1
import threading
robocarshat_device = None
robocarshat_lock = threading.Lock()
steeringTrim = None # common to the two instances
fixSteering = None # common to the two instances
def __init__(self, cfg):
import serial
self.cfg = cfg
self.buffer_string = ''
self.throttle = 0
self.steering = 0
if RobocarsHat.robocarshat_device == None:
RobocarsHat.robocarshat_device = serial.Serial(self.cfg.ROBOCARSHAT_SERIAL_PORT, 1000000, timeout = 0.01)
self.running = True
print('RobocarsHat drive train created')
def setSteeringTrim (self, steeringTrim) :
RobocarsHat.steeringTrim=steeringTrim
mylogger.info("Tx set Steering Trim to :{}".format(RobocarsHat.steeringTrim))
def setFixSteering (self, fixSteering) :
RobocarsHat.fixSteering=fixSteering
mylogger.info("Tx set FIxed Steering to :{}".format(RobocarsHat.fixSteering))
def set_pulse(self, throttle, steering):
if throttle > 0:
pulse_throttle = dk.utils.map_range(throttle, 0, self.MAX_THROTTLE,
self.cfg.ROBOCARSHAT_PWM_OUT_THROTTLE_IDLE, self.cfg.ROBOCARSHAT_PWM_OUT_THROTTLE_MAX)
elif throttle<0:
pulse_throttle = dk.utils.map_range(throttle, self.MIN_THROTTLE, 0,
self.cfg.ROBOCARSHAT_PWM_OUT_THROTTLE_MIN, self.cfg.ROBOCARSHAT_PWM_OUT_THROTTLE_IDLE)
else:
pulse_throttle = self.cfg.ROBOCARSHAT_PWM_OUT_THROTTLE_IDLE
steeringIdle = self.cfg.ROBOCARSHAT_PWM_OUT_STEERING_IDLE
if (RobocarsHat.steeringTrim != None):
steeringIdle = RobocarsHat.steeringTrim;
if steering > 0:
pulse_steering = dk.utils.map_range(steering, 0, self.MAX_STEERING,
steeringIdle, self.cfg.ROBOCARSHAT_PWM_OUT_STEERING_MAX)
elif steering<0 :
pulse_steering = dk.utils.map_range(steering, self.MIN_STEERING, 0,
self.cfg.ROBOCARSHAT_PWM_OUT_STEERING_MIN, steeringIdle)
else:
pulse_steering = steeringIdle
if (RobocarsHat.fixSteering != None):
pulse_steering = RobocarsHat.fixSteering
with RobocarsHat.robocarshat_lock:
cmd=("1,%d,%d\n" % (int(pulse_throttle), int(pulse_steering))).encode('ascii')
mylogger.debug("Tx CMD :{}".format(cmd))
RobocarsHat.robocarshat_device.write(cmd)
def run_threaded(self, throttle, steering):
# not implemented
pass
def run(self, throttle, steering):
self.throttle = throttle
self.steering = steering
self.set_pulse(self.throttle, self.steering)
def shutdown(self):
# set steering straight
self.throttle = 0
self.steering = 0
time.sleep(0.3)
self.running = False
def update(self):
# Not implemented
pass
def readline(self):
last_received = []
with RobocarsHat.robocarshat_lock:
while (RobocarsHat.robocarshat_device.inWaiting()>0):
self.buffer_string = self.buffer_string + RobocarsHat.robocarshat_device.read(RobocarsHat.robocarshat_device.inWaiting()).decode('ascii')
if '\n' in self.buffer_string:
lines = self.buffer_string.split('\n') # Guaranteed to have at least 2 entries
self.buffer_string = lines[-1]
drive = list(filter(lambda line: line.startswith('1'), lines[:-1]))
battery = list(filter(lambda line: line.startswith('0'), lines[:-1]))
sensors = list(filter(lambda line: line.startswith('2'), lines[:-1]))
calibration = list(filter(lambda line: line.startswith('3'), lines[:-1]))
if (len(drive)>0) :
last_received.append(drive[-1].rstrip())
if (len(calibration)>0) :
last_received.append(calibration[-1].rstrip())
#If the Arduino sends lots of empty lines, you'll lose the
#last filled line, so you could make the above statement conditional
#like so: if lines[-2]: last_received = lines[-2]
return last_received