drivers

package module
v0.16.0 Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: May 12, 2021 License: BSD-3-Clause Imports: 2 Imported by: 248

README

TinyGo Drivers

PkgGoDev CircleCI

This package provides a collection of hardware drivers for devices such as sensors and displays that can be used together with TinyGo.

Installing

go get tinygo.org/x/drivers

How to use

Here is an example in TinyGo that uses the BMP180 digital barometer:

package main

import (
    "time"

    "machine"

    "tinygo.org/x/drivers/bmp180"
)

func main() {
    machine.I2C0.Configure(machine.I2CConfig{})
    sensor := bmp180.New(machine.I2C0)
    sensor.Configure()

    connected := sensor.Connected()
    if !connected {
        println("BMP180 not detected")
        return
    }
    println("BMP180 detected")

    for {
        temp, _ := sensor.ReadTemperature()
        println("Temperature:", float32(temp)/1000, "°C")

        pressure, _ := sensor.ReadPressure()
        println("Pressure", float32(pressure)/100000, "hPa")

        time.Sleep(2 * time.Second)
    }
}

Currently supported devices

The following 65 devices are supported.

Device Name Interface Type
ADT7410 I2C Temperature Sensor I2C
ADXL345 accelerometer I2C
AHT20 I2C Temperature and Humidity Sensor I2C
AMG88xx 8x8 Thermal camera sensor I2C
APA102 RGB LED SPI
AT24CX 2-wire serial EEPROM I2C
BBC micro:bit LED matrix GPIO
BH1750 ambient light sensor I2C
BlinkM RGB LED I2C
BME280 humidity/pressure sensor I2C
BMI160 accelerometer/gyroscope SPI
BMP180 barometer I2C
BMP280 temperature/barometer I2C
BMP388 pressure sensor I2C
Buzzer GPIO
DHTXX thermometer and humidity sensor GPIO
DS1307 real time clock I2C
DS3231 real time clock I2C
ESP32 as WiFi Coprocessor with Arduino nina-fw SPI
ESP8266/ESP32 AT Command set for WiFi/TCP/UDP UART
GPS module I2C/UART
HC-SR04 Ultrasonic distance sensor GPIO
HD44780 LCD controller GPIO/I2C
HUB75 RGB led matrix SPI
ILI9341 TFT color display SPI
INA260 Volt/Amp/Power meter I2C
4x4 Membrane Keypad GPIO
L293x motor driver GPIO/PWM
L9110x motor driver GPIO/PWM
LIS2MDL magnetometer I2C
LIS3DH accelerometer I2C
LSM6DS3 accelerometer I2C
MAG3110 magnetometer I2C
MAX7219 & MAX7221 display driver SPI
MCP23017 port expander I2C
MCP3008 analog to digital converter (ADC) SPI
MCP2515 Stand-Alone CAN Controller with SPI Interface SPI
Microphone - PDM I2S/PDM
MMA8653 accelerometer I2C
MPU6050 accelerometer/gyroscope I2C
P1AM-100 Base Controller SPI
PCD8544 display SPI
PCF8563 real time clock I2C
Resistive Touchscreen (4-wire) GPIO
Semihosting Debug
Servo PWM
Shift register (PISO) GPIO
Shift registers (SIPO) GPIO
SHT3x Digital Humidity Sensor I2C
SPI NOR Flash Memory SPI/QSPI
SSD1306 OLED display I2C / SPI
SSD1331 TFT color display SPI
SSD1351 OLED display SPI
ST7735 TFT color display SPI
ST7789 TFT color display SPI
Stepper motor "Easystepper" controller GPIO
Thermistor ADC
TM1637 7-segment LED display I2C
TMP102 I2C Temperature Sensor I2C
VEML6070 UV light sensor I2C
VL53L1X time-of-flight distance sensor I2C
Waveshare 2.13" (B & C) e-paper display SPI
Waveshare 2.13" e-paper display SPI
Waveshare 4.2" e-paper B/W display SPI
WS2812 RGB LED GPIO

Contributing

Your contributions are welcome!

Please take a look at our CONTRIBUTING.md document for details.

License

This project is licensed under the BSD 3-clause license, just like the Go project itself.

Documentation

Overview

Package drivers provides a collection of hardware drivers for TinyGo (https://tinygo.org) for devices such as sensors and displays.

Here is an example in TinyGo that uses the BMP180 digital barometer:

package main

import (
	"time"
	"machine"

	"tinygo.org/x/drivers/bmp180"
)

func main() {
	machine.I2C0.Configure(machine.I2CConfig{})
	sensor := bmp180.New(machine.I2C0)
	sensor.Configure()

	connected := sensor.Connected()
	if !connected {
		println("BMP180 not detected")
		return
	}
	println("BMP180 detected")

	for {
		temp, _ := sensor.ReadTemperature()
		println("Temperature:", float32(temp)/1000, "°C")

		pressure, _ := sensor.ReadPressure()
		println("Pressure", float32(pressure)/100000, "hPa")

		time.Sleep(2 * time.Second)
	}
}

Each individual driver is contained within its own sub-package within this package and there are no interdependencies in order to minimize the final size of compiled code that uses any of these drivers.

Index

Constants

View Source
const Version = "0.16.0"

Version returns a user-readable string showing the version of the drivers package for support purposes. Update this value before release of new version of software.

Variables

This section is empty.

Functions

This section is empty.

Types

type Displayer

type Displayer interface {
	// Size returns the current size of the display.
	Size() (x, y int16)

	// SetPizel modifies the internal buffer.
	SetPixel(x, y int16, c color.RGBA)

	// Display sends the buffer (if any) to the screen.
	Display() error
}

type I2C added in v0.14.0

type I2C interface {
	ReadRegister(addr uint8, r uint8, buf []byte) error
	WriteRegister(addr uint8, r uint8, buf []byte) error
	Tx(addr uint16, w, r []byte) error
}

I2C represents an I2C bus. It is notably implemented by the machine.I2C type.

type SPI added in v0.15.1

type SPI interface {
	// Tx transmits the given buffer w and receives at the same time the buffer r.
	// The two buffers must be the same length. The only exception is when w or r are nil,
	// in which case Tx only transmits (without receiving) or only receives (while sending 0 bytes).
	Tx(w, r []byte) error

	// Transfer writes a single byte out on the SPI bus and receives a byte at the same time.
	// If you want to transfer multiple bytes, it is more efficient to use Tx instead.
	Transfer(b byte) (byte, error)
}

SPI represents a SPI bus. It is implemented by the machine.SPI type.

type UART added in v0.16.0

type UART interface {
	io.Reader
	io.Writer

	Buffered() int
}

UART represents a UART connection. It is implemented by the machine.UART type.

Directories

Path Synopsis
Package adt7410 provides a driver for the adt7410 I2C Temperature Sensor.
Package adt7410 provides a driver for the adt7410 I2C Temperature Sensor.
Package adxl345 provides a driver for the ADXL345 digital accelerometer.
Package adxl345 provides a driver for the ADXL345 digital accelerometer.
Package amg88xx provides a driver for the AMG88XX Thermal Camera Datasheet: https://cdn-learn.adafruit.com/assets/assets/000/043/261/original/Grid-EYE_SPECIFICATIONS%28Reference%29.pdf
Package amg88xx provides a driver for the AMG88XX Thermal Camera Datasheet: https://cdn-learn.adafruit.com/assets/assets/000/043/261/original/Grid-EYE_SPECIFICATIONS%28Reference%29.pdf
Package apa102 implements a driver for the APA102 SPI LED.
Package apa102 implements a driver for the APA102 SPI LED.
Package at24cx provides a driver for the AT24C32/64/128/256/512 2-wire serial EEPROM Datasheet: https://www.openimpulse.com/blog/wp-content/uploads/wpsc/downloadables/24C32-Datasheet.pdf
Package at24cx provides a driver for the AT24C32/64/128/256/512 2-wire serial EEPROM Datasheet: https://www.openimpulse.com/blog/wp-content/uploads/wpsc/downloadables/24C32-Datasheet.pdf
Package bh1750 provides a driver for the BH1750 digital Ambient Light Datasheet: https://www.mouser.com/ds/2/348/bh1750fvi-e-186247.pdf
Package bh1750 provides a driver for the BH1750 digital Ambient Light Datasheet: https://www.mouser.com/ds/2/348/bh1750fvi-e-186247.pdf
Package blinkm implements a driver for the BlinkM I2C RGB LED.
Package blinkm implements a driver for the BlinkM I2C RGB LED.
Package bme280 provides a driver for the BME280 digital combined humidity and pressure sensor by Bosch.
Package bme280 provides a driver for the BME280 digital combined humidity and pressure sensor by Bosch.
Package bmp180 provides a driver for the BMP180 digital pressure sensor by Bosch.
Package bmp180 provides a driver for the BMP180 digital pressure sensor by Bosch.
Package bmp280 provides a driver for the BMP280 digital temperature & pressure sensor by Bosch.
Package bmp280 provides a driver for the BMP280 digital temperature & pressure sensor by Bosch.
Package bmp388 provides a driver for Bosch's BMP388 digital temperature & pressure sensor.
Package bmp388 provides a driver for Bosch's BMP388 digital temperature & pressure sensor.
Package buzzer provides a very simplistic driver for a connected buzzer or low-fidelity speaker.
Package buzzer provides a very simplistic driver for a connected buzzer or low-fidelity speaker.
Package ds1307 provides a driver for the DS1307 RTC Datasheet: https://datasheets.maximintegrated.com/en/ds/DS1307.pdf
Package ds1307 provides a driver for the DS1307 RTC Datasheet: https://datasheets.maximintegrated.com/en/ds/DS1307.pdf
Package ds3231 provides a driver for the DS3231 RTC Datasheet: https://datasheets.maximintegrated.com/en/ds/DS3231.pdf
Package ds3231 provides a driver for the DS3231 RTC Datasheet: https://datasheets.maximintegrated.com/en/ds/DS3231.pdf
Package easystepper provides a simple driver to rotate a 4-wire stepper motor.
Package easystepper provides a simple driver to rotate a 4-wire stepper motor.
Package espat implements TCP/UDP wireless communication over serial with a separate ESP8266 or ESP32 board using the Espressif AT command set across a UART interface.
Package espat implements TCP/UDP wireless communication over serial with a separate ESP8266 or ESP32 board using the Espressif AT command set across a UART interface.
examples
apa102
Connects to an APA102 SPI RGB LED strip with 30 LEDS.
Connects to an APA102 SPI RGB LED strip with 30 LEDS.
apa102/itsybitsy-m0
This example demostrates how to control the "Dotstar" (APA102) LED included on the Adafruit Itsy Bitsy M0 board.
This example demostrates how to control the "Dotstar" (APA102) LED included on the Adafruit Itsy Bitsy M0 board.
blinkm
Connects to an BlinkM I2C RGB LED.
Connects to an BlinkM I2C RGB LED.
dht
ds3231
Connects to an MAG3110 I2C magnetometer.
Connects to an MAG3110 I2C magnetometer.
espat/espconsole
This is a console to a ESP8266/ESP32 running on the device UART1.
This is a console to a ESP8266/ESP32 running on the device UART1.
espat/esphub
This is a sensor hub that uses a ESP8266/ESP32 running on the device UART1.
This is a sensor hub that uses a ESP8266/ESP32 running on the device UART1.
espat/espstation
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
espat/mqttclient
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
espat/mqttsub
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
espat/tcpclient
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
ili9341/pyportal_boing
Port of Adafruit's "pyportal_boing" demo found here: https://github.com/adafruit/Adafruit_ILI9341/blob/master/examples/pyportal_boing
Port of Adafruit's "pyportal_boing" demo found here: https://github.com/adafruit/Adafruit_ILI9341/blob/master/examples/pyportal_boing
lis3dh
Connects to a LIS3DH I2C accelerometer on the Adafruit Circuit Playground Express.
Connects to a LIS3DH I2C accelerometer on the Adafruit Circuit Playground Express.
lsm6ds3
Connects to an LSM6DS3 I2C a 6 axis Inertial Measurement Unit (IMU)
Connects to an LSM6DS3 I2C a 6 axis Inertial Measurement Unit (IMU)
mag3110
Connects to an MAG3110 I2C magnetometer.
Connects to an MAG3110 I2C magnetometer.
mcp23017-multiple
This example demonstrates putting several mcp23017 devices together into a single virtual I/O array.
This example demonstrates putting several mcp23017 devices together into a single virtual I/O array.
mcp3008
Connects to a MCP3008 ADC via SPI.
Connects to a MCP3008 ADC via SPI.
microphone
Example using the i2s hardware interface on the Adafruit Circuit Playground Express to read data from the onboard MEMS microphone.
Example using the i2s hardware interface on the Adafruit Circuit Playground Express to read data from the onboard MEMS microphone.
mma8653
Connects to an MMA8653 I2C accelerometer.
Connects to an MMA8653 I2C accelerometer.
mpu6050
Connects to an MPU6050 I2C accelerometer/gyroscope.
Connects to an MPU6050 I2C accelerometer/gyroscope.
shifter
This example is designed to implement the button shifter for a PyBadge.
This example is designed to implement the button shifter for a PyBadge.
thermistor
This example uses the settings for the thermistor that is built in to the Adafruit Circuit Playground Express.
This example uses the settings for the thermistor that is built in to the Adafruit Circuit Playground Express.
touch/resistive/fourwire
demo of 4-wire touchscreen as described in app note: http://ww1.microchip.com/downloads/en/Appnotes/doc8091.pdf
demo of 4-wire touchscreen as described in app note: http://ww1.microchip.com/downloads/en/Appnotes/doc8091.pdf
wifinina/connect
This example connects to Access Point and prints some info
This example connects to Access Point and prints some info
wifinina/mqttclient
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
wifinina/mqttsub
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
This is a sensor station that uses a ESP8266 or ESP32 running on the device UART1.
wifinina/ntpclient
This is an example of using the wifinina driver to implement a NTP client.
This is an example of using the wifinina driver to implement a NTP client.
wifinina/tcpclient
This example opens a TCP connection using a device with WiFiNINA firmware and sends some data, for the purpose of testing speed and connectivity.
This example opens a TCP connection using a device with WiFiNINA firmware and sends some data, for the purpose of testing speed and connectivity.
wifinina/tlsclient
This example opens a TCP connection using a device with WiFiNINA firmware and sends a HTTPS request to retrieve a webpage You shall see "strict-transport-security" header in the response, this confirms communication is indeed over HTTPS https://developer.mozilla.org/en-US/docs/Web/HTTP/Headers/Strict-Transport-Security
This example opens a TCP connection using a device with WiFiNINA firmware and sends a HTTPS request to retrieve a webpage You shall see "strict-transport-security" header in the response, this confirms communication is indeed over HTTPS https://developer.mozilla.org/en-US/docs/Web/HTTP/Headers/Strict-Transport-Security
wifinina/udpstation
This is a sensor station that uses a ESP32 running nina-fw over SPI.
This is a sensor station that uses a ESP32 running nina-fw over SPI.
wifinina/webclient
This example opens a TCP connection using a device with WiFiNINA firmware and sends a HTTP request to retrieve a webpage, based on the following Arduino example: https://github.com/arduino-libraries/WiFiNINA/blob/master/examples/WiFiWebClientRepeating/
This example opens a TCP connection using a device with WiFiNINA firmware and sends a HTTP request to retrieve a webpage, based on the following Arduino example: https://github.com/arduino-libraries/WiFiNINA/blob/master/examples/WiFiWebClientRepeating/
ws2812
Connects to an WS2812 RGB LED strip with 10 LEDS.
Connects to an WS2812 RGB LED strip with 10 LEDS.
Package gps provides a driver for GPS receivers over UART and I2C
Package gps provides a driver for GPS receivers over UART and I2C
Package hcsr04 provides a driver for the HC-SR04 ultrasonic distance sensor Datasheet: https://cdn.sparkfun.com/datasheets/Sensors/Proximity/HCSR04.pdf
Package hcsr04 provides a driver for the HC-SR04 ultrasonic distance sensor Datasheet: https://cdn.sparkfun.com/datasheets/Sensors/Proximity/HCSR04.pdf
Package hd44780 provides a driver for the HD44780 LCD controller.
Package hd44780 provides a driver for the HD44780 LCD controller.
Package hd44780i2c implements a driver for the Hitachi HD44780 LCD display module with an I2C adapter.
Package hd44780i2c implements a driver for the Hitachi HD44780 LCD display module with an I2C adapter.
Package hub75 implements a driver for the HUB75 LED matrix.
Package hub75 implements a driver for the HUB75 LED matrix.
Package l293x provides a driver to the L293/L293D H-bridge chip typically used to control DC motors.
Package l293x provides a driver to the L293/L293D H-bridge chip typically used to control DC motors.
Package l9110x provides a driver to the L9110/L9110S H-bridge chip typically used to control DC motors.
Package l9110x provides a driver to the L9110/L9110S H-bridge chip typically used to control DC motors.
Package lis2mdl implements a driver for the LIS2MDL, a magnetic sensor which is included on BBC micro:bit v1.5.
Package lis2mdl implements a driver for the LIS2MDL, a magnetic sensor which is included on BBC micro:bit v1.5.
Package lis3dh provides a driver for the LIS3DH digital accelerometer.
Package lis3dh provides a driver for the LIS3DH digital accelerometer.
Package lsm303agr implements a driver for the LSM303AGR, a 3 axis accelerometer/magnetic sensor which is included on BBC micro:bits v1.5.
Package lsm303agr implements a driver for the LSM303AGR, a 3 axis accelerometer/magnetic sensor which is included on BBC micro:bits v1.5.
Package lsm6ds3 implements a driver for the LSM6DS3 a 6 axis Inertial Measurement Unit (IMU) Datasheet: https://www.st.com/resource/en/datasheet/lsm6ds3.pdf
Package lsm6ds3 implements a driver for the LSM6DS3 a 6 axis Inertial Measurement Unit (IMU) Datasheet: https://www.st.com/resource/en/datasheet/lsm6ds3.pdf
Package mag3110 implements a driver for the MAG3110 3-axis magnetometer by Freescale/NXP.
Package mag3110 implements a driver for the MAG3110 3-axis magnetometer by Freescale/NXP.
Driver works for max7219 and 7221 Datasheet: https://datasheets.maximintegrated.com/en/ds/MAX7219-MAX7221.pdf
Driver works for max7219 and 7221 Datasheet: https://datasheets.maximintegrated.com/en/ds/MAX7219-MAX7221.pdf
Package mcp23017 implements a driver for the MCP23017 I2C port expander chip.
Package mcp23017 implements a driver for the MCP23017 I2C port expander chip.
Package mcp2515 implements a driver for the MCP2515 CAN Controller.
Package mcp2515 implements a driver for the MCP2515 CAN Controller.
Package mcp3008 implements a driver for the MCP3008 Analog to Digital Converter.
Package mcp3008 implements a driver for the MCP3008 Analog to Digital Converter.
Package microbitmatrix implements a driver for the BBC micro:bit's LED matrix.
Package microbitmatrix implements a driver for the BBC micro:bit's LED matrix.
Package microphone implements a driver for a PDM microphone.
Package microphone implements a driver for a PDM microphone.
Package mma8653 provides a driver for the MMA8653 3-axis accelerometer by Freescale/NXP.
Package mma8653 provides a driver for the MMA8653 3-axis accelerometer by Freescale/NXP.
Package mpu6050 provides a driver for the MPU6050 accelerometer and gyroscope made by InvenSense.
Package mpu6050 provides a driver for the MPU6050 accelerometer and gyroscope made by InvenSense.
net
package net is intended to provide compatible interfaces with the Go standard library's net package.
package net is intended to provide compatible interfaces with the Go standard library's net package.
mqtt
Package mqtt is intended to provide compatible interfaces with the Paho mqtt library.
Package mqtt is intended to provide compatible interfaces with the Paho mqtt library.
tls
Package tls is intended to provide a minimal set of compatible interfaces with the Go standard library's tls package.
Package tls is intended to provide a minimal set of compatible interfaces with the Go standard library's tls package.
Package pcd8544 implements a driver for the PCD8544 48x84 pixels matrix LCD, used in Nokia's 5110 and 3310 phones.
Package pcd8544 implements a driver for the PCD8544 48x84 pixels matrix LCD, used in Nokia's 5110 and 3310 phones.
Package semihosting implements parts of the ARM semihosting specification, for communicating over a debug connection.
Package semihosting implements parts of the ARM semihosting specification, for communicating over a debug connection.
Package shifter is for 8bit shift register, most common are 74HC165 and 74165
Package shifter is for 8bit shift register, most common are 74HC165 and 74165
Package shiftregister is for 8bit shift output register using 3 GPIO pins like SN74ALS164A, SN74AHC594, SN74AHC595, ...
Package shiftregister is for 8bit shift output register using 3 GPIO pins like SN74ALS164A, SN74AHC594, SN74AHC595, ...
Package sht3x provides a driver for the SHT3x digital humidity sensor series by Sensirion.
Package sht3x provides a driver for the SHT3x digital humidity sensor series by Sensirion.
Package ssd1306 implements a driver for the SSD1306 led matrix controller, it comes in various colors and screen sizes.
Package ssd1306 implements a driver for the SSD1306 led matrix controller, it comes in various colors and screen sizes.
Package ssd1331 implements a driver for the SSD1331 TFT color displays.
Package ssd1331 implements a driver for the SSD1331 TFT color displays.
Package ssd1351 implements a driver for the SSD1351 OLED color displays.
Package ssd1351 implements a driver for the SSD1351 OLED color displays.
Package st7735 implements a driver for the ST7735 TFT displays, it comes in various screen sizes.
Package st7735 implements a driver for the ST7735 TFT displays, it comes in various screen sizes.
Package st7789 implements a driver for the ST7789 TFT displays, it comes in various screen sizes.
Package st7789 implements a driver for the ST7789 TFT displays, it comes in various screen sizes.
Package tester contains mock structs to make it easier to test I2C devices.
Package tester contains mock structs to make it easier to test I2C devices.
Package thermistor is for temperature sensing using a thermistor such as the NTC 3950.
Package thermistor is for temperature sensing using a thermistor such as the NTC 3950.
Package tm1637 provides a driver for the TM1637 4-digit 7-segment LED display.
Package tm1637 provides a driver for the TM1637 4-digit 7-segment LED display.
Package veml6070 provides a driver for the VEML6070 digital UV light sensor by Vishay.
Package veml6070 provides a driver for the VEML6070 digital UV light sensor by Vishay.
Package vl53l1x provides a driver for the VL53L1X time-of-flight distance sensor Datasheet: https://www.st.com/resource/en/datasheet/vl53l1x.pdf This driver was based on the library https://github.com/pololu/vl53l1x-arduino and ST's VL53L1X API (STSW-IMG007) https://www.st.com/content/st_com/en/products/embedded-software/proximity-sensors-software/stsw-img007.html
Package vl53l1x provides a driver for the VL53L1X time-of-flight distance sensor Datasheet: https://www.st.com/resource/en/datasheet/vl53l1x.pdf This driver was based on the library https://github.com/pololu/vl53l1x-arduino and ST's VL53L1X API (STSW-IMG007) https://www.st.com/content/st_com/en/products/embedded-software/proximity-sensors-software/stsw-img007.html
epd2in13
Package epd2in13 implements a driver for Waveshare 2.13in black and white e-paper device.
Package epd2in13 implements a driver for Waveshare 2.13in black and white e-paper device.
epd2in13x
Package epd2in13x implements a driver for Waveshare 2.13in (B & C versions) tri-color e-paper device.
Package epd2in13x implements a driver for Waveshare 2.13in (B & C versions) tri-color e-paper device.
epd4in2
Package epd4in2 implements a driver for Waveshare 4.2in black and white e-paper device.
Package epd4in2 implements a driver for Waveshare 4.2in black and white e-paper device.
Package wifinina implements TCP wireless communication over SPI with an attached separate ESP32 board using the Arduino WiFiNINA protocol.
Package wifinina implements TCP wireless communication over SPI with an attached separate ESP32 board using the Arduino WiFiNINA protocol.
Package ws2812 implements a driver for WS2812 and SK6812 RGB LED strips.
Package ws2812 implements a driver for WS2812 and SK6812 RGB LED strips.

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL