-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathMotorModule.py
75 lines (62 loc) · 1.92 KB
/
MotorModule.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
import RPi.GPIO as GPIO
from time import sleep
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
class Motor():
def __init__(self, EnaA, In1A, In2A, EnaB, In1B, In2B):
self.EnaA = EnaA
self.In1A = In1A
self.In2A = In2A
self.EnaB = EnaB
self.In1B = In1B
self.In2B = In2B
GPIO.setup(self.EnaA, GPIO.OUT)
GPIO.setup(self.In1A, GPIO.OUT)
GPIO.setup(self.In2A, GPIO.OUT)
GPIO.setup(self.EnaB, GPIO.OUT)
GPIO.setup(self.In1B, GPIO.OUT)
GPIO.setup(self.In2B, GPIO.OUT)
self.pwmA = GPIO.PWM(self.EnaA, 100);
self.pwmA.start(0);
self.pwmB = GPIO.PWM(self.EnaB, 100);
self.pwmB.start(0);
def move(self, speed=0.5, turn=0, t=0):
speed *= 100
turn *= 100
leftSpeed = speed - turn
rightSpeed = speed + turn
if leftSpeed > 100:
leftSpeed = 100
elif leftSpeed < -100:
leftSpeed = -100
if rightSpeed > 100:
rightSpeed = 100
elif rightSpeed < -100:
rightSpeed = -100
self.pwmA.ChangeDutyCycle(abs(leftSpeed))
self.pwmB.ChangeDutyCycle(abs(rightSpeed))
if leftSpeed > 0:
GPIO.output(self.In1A, GPIO.HIGH)
GPIO.output(self.In2A, GPIO.LOW)
else:
GPIO.output(self.In1A, GPIO.LOW)
GPIO.output(self.In2A, GPIO.HIGH)
if rightSpeed > 0:
GPIO.output(self.In1B, GPIO.HIGH)
GPIO.output(self.In2B, GPIO.LOW)
else:
GPIO.output(self.In1B, GPIO.LOW)
GPIO.output(self.In2B, GPIO.HIGH)
sleep(t)
def stop(self, t=0):
self.pwmA.ChangeDutyCycle(0);
self.pwmB.ChangeDutyCycle(0);
sleep(t)
def main():
motor.move(0.6, 0, 2)
motor.stop(2)
motor.move(-0.5, 0.2, 2)
motor.stop(2)
if __name__ == '__main__':
motor = Motor(2, 3, 4, 22, 17, 27)
main()