Commit 8f01dc77 authored by Aadil M. Alli's avatar Aadil M. Alli

Initial commit

parents
File added
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Ab = AlphaBot2()
Ab.backward()
print('backward')
\ No newline at end of file
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Ab = AlphaBot2()
Ab.forward()
print('forward')
\ No newline at end of file
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Ab = AlphaBot2()
Ab.left()
print('left')
\ No newline at end of file
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Ab = AlphaBot2()
Ab.right()
print('right')
\ No newline at end of file
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Ab = AlphaBot2()
Ab.stop()
print('stop')
\ No newline at end of file
import RPi.GPIO as GPIO
import time
class AlphaBot2(object):
def __init__(self,ain1=20,ain2=21,ena=6,bin1=12,bin2=13,enb=26):
self.AIN1 = ain1
self.AIN2 = ain2
self.BIN1 = bin1
self.BIN2 = bin2
self.ENA = ena
self.ENB = enb
self.PA = 15
self.PB = 15
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(self.AIN1,GPIO.OUT)
GPIO.setup(self.AIN2,GPIO.OUT)
GPIO.setup(self.BIN1,GPIO.OUT)
GPIO.setup(self.BIN2,GPIO.OUT)
GPIO.setup(self.ENA,GPIO.OUT)
GPIO.setup(self.ENB,GPIO.OUT)
self.PWMA = GPIO.PWM(self.ENA,500)
self.PWMB = GPIO.PWM(self.ENB,500)
self.PWMA.start(self.PA)
self.PWMB.start(self.PB)
self.stop()
def forward(self):
self.PWMA.ChangeDutyCycle(self.PA)
self.PWMB.ChangeDutyCycle(self.PB)
GPIO.output(self.AIN1,GPIO.LOW)
GPIO.output(self.AIN2,GPIO.HIGH)
GPIO.output(self.BIN1,GPIO.LOW)
GPIO.output(self.BIN2,GPIO.HIGH)
def stop(self):
self.PWMA.ChangeDutyCycle(0)
self.PWMB.ChangeDutyCycle(0)
GPIO.output(self.AIN1,GPIO.LOW)
GPIO.output(self.AIN2,GPIO.LOW)
GPIO.output(self.BIN1,GPIO.LOW)
GPIO.output(self.BIN2,GPIO.LOW)
def backward(self):
self.PWMA.ChangeDutyCycle(self.PA)
self.PWMB.ChangeDutyCycle(self.PB)
GPIO.output(self.AIN1,GPIO.HIGH)
GPIO.output(self.AIN2,GPIO.LOW)
GPIO.output(self.BIN1,GPIO.HIGH)
GPIO.output(self.BIN2,GPIO.LOW)
def left(self):
self.PWMA.ChangeDutyCycle(25)
self.PWMB.ChangeDutyCycle(25)
GPIO.output(self.AIN1,GPIO.HIGH)
GPIO.output(self.AIN2,GPIO.LOW)
GPIO.output(self.BIN1,GPIO.LOW)
GPIO.output(self.BIN2,GPIO.HIGH)
def right(self):
self.PWMA.ChangeDutyCycle(25)
self.PWMB.ChangeDutyCycle(25)
GPIO.output(self.AIN1,GPIO.LOW)
GPIO.output(self.AIN2,GPIO.HIGH)
GPIO.output(self.BIN1,GPIO.HIGH)
GPIO.output(self.BIN2,GPIO.LOW)
def setPWMA(self,value):
self.PA = value
self.PWMA.ChangeDutyCycle(self.PA)
def setPWMB(self,value):
self.PB = value
self.PWMB.ChangeDutyCycle(self.PB)
def setMotor(self, left, right):
if((right >= 0) and (right <= 100)):
GPIO.output(self.AIN1,GPIO.HIGH)
GPIO.output(self.AIN2,GPIO.LOW)
self.PWMA.ChangeDutyCycle(right)
elif((right < 0) and (right >= -100)):
GPIO.output(self.AIN1,GPIO.LOW)
GPIO.output(self.AIN2,GPIO.HIGH)
self.PWMA.ChangeDutyCycle(0 - right)
if((left >= 0) and (left <= 100)):
GPIO.output(self.BIN1,GPIO.HIGH)
GPIO.output(self.BIN2,GPIO.LOW)
self.PWMB.ChangeDutyCycle(left)
elif((left < 0) and (left >= -100)):
GPIO.output(self.BIN1,GPIO.LOW)
GPIO.output(self.BIN2,GPIO.HIGH)
self.PWMB.ChangeDutyCycle(0 - left)
if __name__=='__main__':
Ab = AlphaBot2()
Ab.forward()
try:
while True:
time.sleep(1)
except KeyboardInterrupt:
GPIO.cleanup()
import RPi.GPIO as GPIO
import time
from AlphaBot2 import AlphaBot2
Ab = AlphaBot2()
DR = 16
DL = 19
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(DR,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(DL,GPIO.IN,GPIO.PUD_UP)
try:
while True:
DR_status = GPIO.input(DR)
DL_status = GPIO.input(DL)
print("DR_status:", DR_status)
print("DL_status:", DL_status)
# print(DR_status,DL_status)
if (DL_status == 0):
Ab.left()
#Ab.right()
time.sleep(0.01)
Ab.stop()
# print("object")
elif (DR_status == 0):
Ab.right()
time.sleep(0.01)
Ab.stop()
else:
Ab.forward()
# print("forward")
except KeyboardInterrupt:
GPIO.cleanup();
import RPi.GPIO as GPIO
import time
from AlphaBot2 import AlphaBot2
Ab = AlphaBot2()
CTR = 7
A = 8
B = 9
C = 10
D = 11
BUZ = 4
def beep_on():
GPIO.output(BUZ,GPIO.HIGH)
def beep_off():
GPIO.output(BUZ,GPIO.LOW)
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(CTR,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(A,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(B,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(C,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(D,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(BUZ,GPIO.OUT)
try:
while True:
if GPIO.input(CTR) == 0:
beep_on();
Ab.stop();
print("center")
while GPIO.input(CTR) == 0:
time.sleep(0.01)
elif GPIO.input(A) == 0:
beep_on();
Ab.forward();
print("up")
while GPIO.input(A) == 0:
time.sleep(0.01)
elif GPIO.input(B) == 0:
beep_on();
Ab.right();
print("right")
while GPIO.input(B) == 0:
time.sleep(0.01)
elif GPIO.input(C) == 0:
beep_on();
Ab.left();
print("left")
while GPIO.input(C) == 0:
time.sleep(0.01)
elif GPIO.input(D) == 0:
beep_on();
Ab.backward();
print("down")
while GPIO.input(D) == 0:
time.sleep(0.01)
else:
beep_off();
except KeyboardInterrupt:
GPIO.cleanup()
\ No newline at end of file
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
from AlphaBot2 import AlphaBot2
from rpi_ws281x import Adafruit_NeoPixel, Color
from TRSensors import TRSensor
import time
Button = 7
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(Button,GPIO.IN,GPIO.PUD_UP)
# LED strip configuration:
LED_COUNT = 4 # Number of LED pixels.
LED_PIN = 18 # GPIO pin connected to the pixels (must support PWM!).
LED_FREQ_HZ = 800000 # LED signal frequency in hertz (usually 800khz)
LED_DMA = 5 # DMA channel to use for generating signal (try 5)
LED_BRIGHTNESS = 255 # Set to 0 for darkest and 255 for brightest
LED_INVERT = False # True to invert the signal (when using NPN transistor level shift)
maximum = 100;
j = 0
integral = 0;
last_proportional = 0
def Wheel(pos):
# """Generate rainbow colors across 0-255 positions."""
if pos < 85:
return Color(pos * 3, 255 - pos * 3, 0)
elif pos < 170:
pos -= 85
return Color(255 - pos * 3, 0, pos * 3)
else:
pos -= 170
return Color(0, pos * 3, 255 - pos * 3)
# Create NeoPixel object with appropriate configuration.
strip = Adafruit_NeoPixel(LED_COUNT, LED_PIN, LED_FREQ_HZ, LED_DMA, LED_INVERT, LED_BRIGHTNESS)
# Intialize the library (must be called once before other functions).
strip.begin()
strip.setPixelColor(0, Color(100, 0, 0)) #Red
strip.setPixelColor(1, Color(0, 100, 0)) #Blue
strip.setPixelColor(2, Color(0, 0, 100)) #Green
strip.setPixelColor(3, Color(100, 100, 0)) #Yellow
strip.show()
TR = TRSensor()
Ab = AlphaBot2()
Ab.stop()
print("Line follow Example")
time.sleep(0.5)
for i in range(0,100):
if(i<25 or i>= 75):
Ab.right()
Ab.setPWMA(30)
Ab.setPWMB(30)
else:
Ab.left()
Ab.setPWMA(30)
Ab.setPWMB(30)
TR.calibrate()
Ab.stop()
print(TR.calibratedMin)
print(TR.calibratedMax)
while (GPIO.input(Button) != 0):
position,Sensors = TR.readLine()
print(position,Sensors)
time.sleep(0.05)
Ab.forward()
print("about to follow")
while True:
position,Sensors = TR.readLine()
#print(position)
if(Sensors[0] >900 and Sensors[1] >900 and Sensors[2] >900 and Sensors[3] >900 and Sensors[4] >900):
Ab.setPWMA(0)
Ab.setPWMB(0)
print("greater than 900")
else:
print("less than 900")
# The "proportional" term should be 0 when we are on the line.
proportional = position - 2000
print("crash1")
# Compute the derivative (change) and integral (sum) of the position.
derivative = proportional - last_proportional
integral += proportional
print("crash2")
# Remember the last position.
last_proportional = proportional
print("crash3")
'''
// Compute the difference between the two motor power settings,
// m1 - m2. If this is a positive number the robot will turn
// to the right. If it is a negative number, the robot will
// turn to the left, and the magnitude of the number determines
// the sharpness of the turn. You can adjust the constants by which
// the proportional, integral, and derivative terms are multiplied to
// improve performance.
'''
power_difference = proportional/30 + integral/10000 + derivative*2;
print("crash4")
if (power_difference > maximum):
power_difference = maximum
if (power_difference < - maximum):
power_difference = - maximum
print(position,power_difference)
if (power_difference < 0):
Ab.setPWMA(maximum + power_difference)
Ab.setPWMB(maximum);
else:
Ab.setPWMA(maximum);
Ab.setPWMB(maximum - power_difference)
print("crash5")
# for i in range(0,strip.numPixels()):
# strip.setPixelColor(i, Wheel(((i * 256 / strip.numPixels()) + j) & 255))
# strip.show();
print("crash6")
j += 1
print("crash7")
if(j > 256*4):
j= 0
print("crash8")
#!/usr/bin/python
import time
import math
import smbus
# ============================================================================
# Raspi PCA9685 16-Channel PWM Servo Driver
# ============================================================================
class PCA9685:
# Registers/etc.
__SUBADR1 = 0x02
__SUBADR2 = 0x03
__SUBADR3 = 0x04
__MODE1 = 0x00
__PRESCALE = 0xFE
__LED0_ON_L = 0x06
__LED0_ON_H = 0x07
__LED0_OFF_L = 0x08
__LED0_OFF_H = 0x09
__ALLLED_ON_L = 0xFA
__ALLLED_ON_H = 0xFB
__ALLLED_OFF_L = 0xFC
__ALLLED_OFF_H = 0xFD
def __init__(self, address=0x40, debug=False):
self.bus = smbus.SMBus(1)
self.address = address
self.debug = debug
if (self.debug):
print("Reseting PCA9685")
self.write(self.__MODE1, 0x00)
def write(self, reg, value):
"Writes an 8-bit value to the specified register/address"
self.bus.write_byte_data(self.address, reg, value)
if (self.debug):
print("I2C: Write 0x%02X to register 0x%02X" % (value, reg))
def read(self, reg):
"Read an unsigned byte from the I2C device"
result = self.bus.read_byte_data(self.address, reg)
if (self.debug):
print("I2C: Device 0x%02X returned 0x%02X from reg 0x%02X" % (self.address, result & 0xFF, reg))
return result
def setPWMFreq(self, freq):
"Sets the PWM frequency"
prescaleval = 25000000.0 # 25MHz
prescaleval /= 4096.0 # 12-bit
prescaleval /= float(freq)
prescaleval -= 1.0
if (self.debug):
print("Setting PWM frequency to %d Hz" % freq)
print("Estimated pre-scale: %d" % prescaleval)
prescale = math.floor(prescaleval + 0.5)
if (self.debug):
print("Final pre-scale: %d" % prescale)
oldmode = self.read(self.__MODE1);
newmode = (oldmode & 0x7F) | 0x10 # sleep
self.write(self.__MODE1, newmode) # go to sleep
self.write(self.__PRESCALE, int(math.floor(prescale)))
self.write(self.__MODE1, oldmode)
time.sleep(0.005)
self.write(self.__MODE1, oldmode | 0x80)
def setPWM(self, channel, on, off):
"Sets a single PWM channel"
self.write(self.__LED0_ON_L+4*channel, on & 0xFF)
self.write(self.__LED0_ON_H+4*channel, on >> 8)
self.write(self.__LED0_OFF_L+4*channel, off & 0xFF)
self.write(self.__LED0_OFF_H+4*channel, off >> 8)
if (self.debug):
print("channel: %d LED_ON: %d LED_OFF: %d" % (channel,on,off))
def setServoPulse(self, channel, pulse):
"Sets the Servo Pulse,The PWM frequency must be 50HZ"
pulse = pulse*4096/20000 #PWM frequency is 50HZ,the period is 20000us
self.setPWM(channel, 0, pulse)
if __name__=='__main__':
pwm = PCA9685(0x40, debug=True)
pwm.setPWMFreq(50)
while True:
# setServoPulse(2,2500)
for i in range(500,2500,10):
pwm.setServoPulse(0,i)
time.sleep(0.02)
for i in range(2500,500,-10):
pwm.setServoPulse(0,i)
time.sleep(0.02)
#!/usr/bin/python
# -*- coding:utf-8 -*-
import RPi.GPIO as GPIO
import time
CS = 5
Clock = 25
Address = 24
DataOut = 23
Button = 7
class TRSensor(object):
def __init__(self,numSensors = 5):
self.numSensors = numSensors
self.calibratedMin = [0] * self.numSensors
self.calibratedMax = [1023] * self.numSensors
self.last_value = 0
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(Clock,GPIO.OUT)
GPIO.setup(Address,GPIO.OUT)
GPIO.setup(CS,GPIO.OUT)
GPIO.setup(DataOut,GPIO.IN,GPIO.PUD_UP)
GPIO.setup(Button,GPIO.IN,GPIO.PUD_UP)
"""
Reads the sensor values into an array. There *MUST* be space
for as many values as there were sensors specified in the constructor.
Example usage:
unsigned int sensor_values[8];
sensors.read(sensor_values);
The values returned are a measure of the reflectance in abstract units,
with higher values corresponding to lower reflectance (e.g. a black
surface or a void).
"""
def AnalogRead(self):
value = [0]*(self.numSensors+1)
#Read Channel0~channel6 AD value
for j in range(0,self.numSensors+1):
GPIO.output(CS, GPIO.LOW)
for i in range(0,4):
#sent 4-bit Address
if(((j) >> (3 - i)) & 0x01):
GPIO.output(Address,GPIO.HIGH)
else:
GPIO.output(Address,GPIO.LOW)
#read MSB 4-bit data
value[j] <<= 1
if(GPIO.input(DataOut)):
value[j] |= 0x01
GPIO.output(Clock,GPIO.HIGH)
GPIO.output(Clock,GPIO.LOW)
for i in range(0,6):
#read LSB 8-bit data
value[j] <<= 1
if(GPIO.input(DataOut)):
value[j] |= 0x01
GPIO.output(Clock,GPIO.HIGH)
GPIO.output(Clock,GPIO.LOW)
#no mean ,just delay
# for i in range(0,6):
# GPIO.output(Clock,GPIO.HIGH)
# GPIO.output(Clock,GPIO.LOW)
time.sleep(0.0001)
GPIO.output(CS,GPIO.HIGH)
# print value[1:]
return value[1:]
"""
Reads the sensors 10 times and uses the results for
calibration. The sensor values are not returned; instead, the
maximum and minimum values found over time are stored internally
and used for the readCalibrated() method.
"""
def calibrate(self):
max_sensor_values = [0]*self.numSensors
min_sensor_values = [0]*self.numSensors
for j in range(0,10):
sensor_values = self.AnalogRead();
for i in range(0,self.numSensors):
# set the max we found THIS time
if((j == 0) or max_sensor_values[i] < sensor_values[i]):
max_sensor_values[i] = sensor_values[i]
# set the min we found THIS time
if((j == 0) or min_sensor_values[i] > sensor_values[i]):
min_sensor_values[i] = sensor_values[i]
# record the min and max calibration values
for i in range(0,self.numSensors):
if(min_sensor_values[i] > self.calibratedMin[i]):
self.calibratedMin[i] = min_sensor_values[i]
if(max_sensor_values[i] < self.calibratedMax[i]):
self.calibratedMax[i] = max_sensor_values[i]
"""
Returns values calibrated to a value between 0 and 1000, where
0 corresponds to the minimum value read by calibrate() and 1000
corresponds to the maximum value. Calibration values are
stored separately for each sensor, so that differences in the
sensors are accounted for automatically.
"""
def readCalibrated(self):
value = 0
#read the needed values
sensor_values = self.AnalogRead();
for i in range (0,self.numSensors):
denominator = self.calibratedMax[i] - self.calibratedMin[i]
if(denominator != 0):
value = (sensor_values[i] - self.calibratedMin[i])* 1000 / denominator
if(value < 0):
value = 0
elif(value > 1000):
value = 1000
sensor_values[i] = value
#print("readCalibrated",sensor_values)
return sensor_values
"""
Operates the same as read calibrated, but also returns an
estimated position of the robot with respect to a line. The
estimate is made using a weighted average of the sensor indices
multiplied by 1000, so that a return value of 0 indicates that
the line is directly below sensor 0, a return value of 1000
indicates that the line is directly below sensor 1, 2000
indicates that it's below sensor 2000, etc. Intermediate
values indicate that the line is between two sensors. The
formula is:
0*value0 + 1000*value1 + 2000*value2 + ...
--------------------------------------------
value0 + value1 + value2 + ...
By default, this function assumes a dark line (high values)
surrounded by white (low values). If your line is light on
black, set the optional second argument white_line to true. In
this case, each sensor value will be replaced by (1000-value)
before the averaging.
"""
def readLine(self, white_line = 0):
sensor_values = self.readCalibrated()
avg = 0
sum = 0
on_line = 0
for i in range(0,self.numSensors):
value = sensor_values[i]
if(white_line):
value = 1000-value
# keep track of whether we see the line at all
if(value > 200):
on_line = 1
# only average in values that are above a noise threshold
if(value > 50):
avg += value * (i * 1000); # this is for the weighted total,
sum += value; #this is for the denominator
if(on_line != 1):
# If it last read to the left of center, return 0.
if(self.last_value < (self.numSensors - 1)*1000/2):
#print("left")
self.last_value = 0;
# If it last read to the right of center, return the max.
else:
#print("right")
self.last_value = (self.numSensors - 1)*1000
else:
self.last_value = avg/sum
return self.last_value,sensor_values
# Simple example prints accel/mag data once per second:
if __name__ == '__main__':
TR = TRSensor()
print("TRSensor Example")
while True:
print(TR.AnalogRead())
time.sleep(0.2)
import RPi.GPIO as GPIO
import time
from AlphaBot2 import AlphaBot2
TRIG = 22
ECHO = 27
Ab = AlphaBot2()
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(TRIG,GPIO.OUT,initial=GPIO.LOW)
GPIO.setup(ECHO,GPIO.IN)
def Distance():
GPIO.output(TRIG,GPIO.HIGH)
time.sleep(0.000015)
GPIO.output(TRIG,GPIO.LOW)
while not GPIO.input(ECHO):
pass
t1 = time.time()
while GPIO.input(ECHO):
pass
t2 = time.time()
return (t2-t1)*34000/2
print("Ultrasonic_Obstacle_Avoidance")
try:
while True:
Dist = Distance()
print("Distance = %0.2f cm"%Dist)
if Dist <= 20:
Ab.right()
# Ab.left()
else:
Ab.forward()
time.sleep(0.02)
except KeyboardInterrupt:
GPIO.cleanup();
import RPi.GPIO as GPIO
import time
TRIG = 22
ECHO = 27
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(TRIG,GPIO.OUT,initial=GPIO.LOW)
GPIO.setup(ECHO,GPIO.IN)
def dist():
GPIO.output(TRIG,GPIO.HIGH)
time.sleep(0.000015)
GPIO.output(TRIG,GPIO.LOW)
while not GPIO.input(ECHO):
pass
t1 = time.time()
while GPIO.input(ECHO):
pass
t2 = time.time()
return (t2-t1)*34000/2
try:
while True:
print "Distance:%0.2f cm" % dist()
time.sleep(1)
except KeyboardInterrupt:
GPIO.cleanup()
# NeoPixel library strandtest example
# Author: Tony DiCola (tony@tonydicola.com)
#
# Direct port of the Arduino NeoPixel library strandtest example. Showcases
# various animations on a strip of NeoPixels.
import time
from rpi_ws281x import Adafruit_NeoPixel, Color
# LED strip configuration:
LED_COUNT = 4 # Number of LED pixels.
LED_PIN = 18 # GPIO pin connected to the pixels (must support PWM!).
LED_FREQ_HZ = 800000 # LED signal frequency in hertz (usually 800khz)
LED_DMA = 5 # DMA channel to use for generating signal (try 5)
LED_BRIGHTNESS = 255 # Set to 0 for darkest and 255 for brightest
LED_INVERT = False # True to invert the signal (when using NPN transistor level shift)
LED_CHANNEL = 0
strip = Adafruit_NeoPixel(LED_COUNT, LED_PIN, LED_FREQ_HZ, LED_DMA, LED_INVERT, LED_BRIGHTNESS)
# Create NeoPixel object with appropriate configuration.
# Intialize the library (must be called once before other functions).
strip.begin()
strip.setPixelColor(0, Color(255, 0, 0)) #Red
strip.setPixelColor(1, Color(0, 255, 0)) #Green
strip.setPixelColor(2, Color(0, 0, 255)) #Blue
strip.setPixelColor(3, Color(255, 255, 0)) #Yellow
strip.show()
time.sleep(2)
strip.setPixelColor(0, Color(0, 0, 0)) #Red
strip.setPixelColor(1, Color(0, 0, 0)) #Green
strip.setPixelColor(2, Color(0, 0, 0)) #Blue
strip.setPixelColor(3, Color(0, 0, 0)) #Yellow
strip.show()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment