Skip to content

Commit 6df8a4e

Browse files
committed
Add GPIO commands
1 parent 319fe54 commit 6df8a4e

File tree

1 file changed

+46
-8
lines changed

1 file changed

+46
-8
lines changed

redboard.py

Lines changed: 46 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#Python library for the Red Robotics 'HeadBoard' and 'SideBoard' Raspberry Pi add on robotics boards.
22
#Simple python commands for controlling motors, servos and Neopixels (WS2812B).
3-
#Version 1.21 30/3/2018
3+
#Version 1.22 21/6/2018
44
# Author: Neil Lambeth. neil@redrobotics.co.uk @NeilRedRobotics
55

66
from __future__ import print_function # Make print work with python 2 & 3
@@ -28,6 +28,9 @@
2828
RM = 0
2929
LM = 0
3030

31+
INPUT = 1
32+
OUTPUT = 0
33+
3134
pi = pigpio.pi()
3235

3336
pi.set_mode(dira, pigpio.OUTPUT)
@@ -45,7 +48,34 @@
4548
pi.set_mode(servo_0, pigpio.OUTPUT)
4649
pi.set_mode(servo_1, pigpio.OUTPUT)
4750

48-
print("Redboard Library V1.21 loaded")
51+
print("Redboard Library V1.22 loaded")
52+
53+
#-----------------------------------------------------
54+
55+
56+
#GPIO
57+
58+
def output_pin(p):
59+
pi.set_mode(p, pigpio.OUTPUT)
60+
61+
def input_pin(p):
62+
pi.set_mode(p, pigpio.INPUT)
63+
64+
def pull_up(p):
65+
pi.set_pull_up_down(p, pigpio.PUD_UP)
66+
67+
def pull_down(p):
68+
pi.set_pull_up_down(p, pigpio.PUD_DOWN)
69+
70+
71+
def setPin(p, state):
72+
pi.write(p, state)
73+
74+
def readPin(p):
75+
r = pi.read(p)
76+
return r
77+
78+
#-----------------------------------------------------
4979

5080
def servo0(pos0):
5181
if pos0 >= 0 and pos0 <91:
@@ -63,6 +93,8 @@ def servo0(pos0):
6393
else:
6494
print ("Out Of Range!")
6595

96+
#-----------------------------------------------------
97+
6698
def servo0_P(pos0):
6799
if pos0 >499 and pos0 <2501:
68100
print ("servo0 =",pos0)
@@ -71,12 +103,13 @@ def servo0_P(pos0):
71103
else:
72104
print ("Out Of Range!")
73105

106+
#-----------------------------------------------------
107+
74108
def servo0_off():
75109
pi.set_servo_pulsewidth(servo_0, 0)
76110
print ("servo0 off")
77111

78-
79-
112+
#-----------------------------------------------------
80113

81114
def servo1(pos1):
82115
if pos1 >= 0 and pos1 <91:
@@ -94,6 +127,7 @@ def servo1(pos1):
94127
else:
95128
print ("Out Of Range!")
96129

130+
#-----------------------------------------------------
97131

98132
def servo1_P(pos1):
99133
if pos1 >499 and pos1 <2501:
@@ -103,12 +137,13 @@ def servo1_P(pos1):
103137
else:
104138
print ("Out Of Range!")
105139

140+
#-----------------------------------------------------
141+
106142
def servo1_off():
107143
pi.set_servo_pulsewidth(servo_1, 0)
108144
print ("servo1 off")
109145

110-
111-
146+
#-----------------------------------------------------
112147

113148
def M1(lm):
114149

@@ -139,6 +174,7 @@ def M1(lm):
139174

140175
pi.set_PWM_dutycycle(pwmb,LM)
141176

177+
#-----------------------------------------------------
142178

143179
def M1_8bit(lm):
144180

@@ -167,7 +203,7 @@ def M1_8bit(lm):
167203

168204
pi.set_PWM_dutycycle(pwmb,LM)
169205

170-
206+
#-----------------------------------------------------
171207

172208
def M2(rm):
173209

@@ -200,6 +236,8 @@ def M2(rm):
200236
pi.set_PWM_dutycycle(pwma,RM)
201237

202238

239+
#-----------------------------------------------------
240+
203241
def M2_8bit(rm):
204242

205243
if rm > 255: # Make sure the value sent to the motor is 255 or less
@@ -228,7 +266,7 @@ def M2_8bit(rm):
228266

229267
pi.set_PWM_dutycycle(pwma,RM)
230268

231-
269+
#-----------------------------------------------------
232270

233271
def Stop():
234272
pi.set_PWM_dutycycle(pwma,0)

0 commit comments

Comments
 (0)