drivers

package module
v0.27.0 Latest Latest
Warning

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

Go to latest
Published: Feb 26, 2024 License: BSD-3-Clause Imports: 2 Imported by: 248

README

TinyGo Drivers

PkgGoDev Build

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

For the complete list, please see: https://tinygo.org/docs/reference/devices/

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)
    }
}

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 (
	Rotation0 = iota
	Rotation90
	Rotation180
	Rotation270
	Rotation0Mirror
	Rotation90Mirror
	Rotation180Mirror
	Rotation270Mirror
)

Clockwise rotation of the screen.

View Source
const Version = "0.27.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 {
	// Tx performs a [I²C] transaction with address addr.
	// Most I2C peripherals have some sort of register mapping scheme to allow
	// users to interact with them:
	//
	//  bus.Tx(addr, []byte{reg}, buf) // Reads register reg into buf.
	//  bus.Tx(addr, append([]byte{reg}, buf...), nil) // Writes buf into register reg.
	//
	// The semantics of most I2C transactions require that the w write buffer be non-empty.
	//
	// [I²C]: https://en.wikipedia.org/wiki/I%C2%B2C
	Tx(addr uint16, w, r []byte) error
}

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

type Measurement added in v0.25.0

type Measurement uint32

Measurement specifies a type of measurement, for example: temperature, acceleration, pressure.

const (
	Voltage Measurement = 1 << iota
	Temperature
	Humidity
	Pressure
	Distance
	Acceleration
	AngularVelocity
	MagneticField
	Luminosity
	Time
	// Gas or liquid concentration, usually measured in ppm (parts per million).
	Concentration

	// AllMeasurements is the OR of all Measurement values. It ensures all measurements are done.
	AllMeasurements Measurement = (1 << 32) - 1
)

Sensor measurements

type Rotation added in v0.25.0

type Rotation uint8

Rotation is how much a display has been rotated. Displays can be rotated, and sometimes also mirrored.

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 Sensor added in v0.25.0

type Sensor interface {
	// Update performs IO to update the measurements of a sensor.
	// It shall return error only when the sensor encounters an error that prevents it from
	// storing all or part of the measurements it was called to do.
	Update(which Measurement) error
}

Sensor represents an object capable of making one or more measurements. A sensor will then have methods which read the last updated measurements.

Many Sensors may be collected into one Sensor interface to synchronize measurements.

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 adafruit4650 implements a driver for the Adafruit FeatherWing OLED - 128x64 OLED display.
Package adafruit4650 implements a driver for the Adafruit FeatherWing OLED - 128x64 OLED display.
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
Package amg88xx provides a driver for the AMG88XX Thermal Camera
Package apa102 implements a driver for the APA102 SPI LED.
Package apa102 implements a driver for the APA102 SPI LED.
Package apds9960 implements a driver for APDS-9960, a digital proximity, ambient light, RGB and gesture sensor.
Package apds9960 implements a driver for APDS-9960, a digital proximity, ambient light, RGB and gesture sensor.
Package at24cx provides a driver for the AT24C32/64/128/256/512 2-wire serial EEPROM
Package at24cx provides a driver for the AT24C32/64/128/256/512 2-wire serial EEPROM
Package axp192 provides a driver for the axp192 I2C Enhanced single Cell Li-Battery and Power System Management IC.
Package axp192 provides a driver for the axp192 I2C Enhanced single Cell Li-Battery and Power System Management IC.
Package bh1750 provides a driver for the BH1750 digital Ambient Light
Package bh1750 provides a driver for the BH1750 digital Ambient Light
Package blinkm implements a driver for the BlinkM I2C RGB LED.
Package blinkm implements a driver for the BlinkM I2C RGB LED.
Package bma42x provides a driver for the BMA421 and BMA425 accelerometer chips.
Package bma42x provides a driver for the BMA421 and BMA425 accelerometer chips.
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.
cmd
Package ds1307 provides a driver for the DS1307 RTC
Package ds1307 provides a driver for the DS1307 RTC
Package ds18b20 provides a driver for the DS18B20 digital thermometer
Package ds18b20 provides a driver for the DS18B20 digital thermometer
Package ds3231 provides a driver for the DS3231 RTC
Package ds3231 provides a driver for the DS3231 RTC
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.
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 DS3231 I2C Real Time Clock (RTC).
Connects to an DS3231 I2C Real Time Clock (RTC).
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.
lora/lorawan/atcmd
AT command set console running on the device UART to communicate with an attached LoRa device.
AT command set console running on the device UART to communicate with an attached LoRa device.
lora/lorawan/basic-demo
Simple code for connecting to Lorawan network and uploading sample payload
Simple code for connecting to Lorawan network and uploading sample payload
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)
lsm6ds3tr
Connects to an LSM6DS3TR I2C a 6 axis Inertial Measurement Unit (IMU)
Connects to an LSM6DS3TR I2C a 6 axis Inertial Measurement Unit (IMU)
lsm6dsox
Connects to an LSM6DSOX I2C a 6 axis Inertial Measurement Unit (IMU)
Connects to an LSM6DSOX I2C a 6 axis Inertial Measurement Unit (IMU)
lsm9ds1
LSM9DS1, 9 axis Inertial Measurement Unit (IMU)
LSM9DS1, 9 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.
mpu6886
Connects to an MPU6886 I2C accelerometer/gyroscope.
Connects to an MPU6886 I2C accelerometer/gyroscope.
mpu9150
Connects to an MPU9150 I2C accelerometer/gyroscope.
Connects to an MPU9150 I2C accelerometer/gyroscope.
qmi8658c
Connects to an QMI8658C I2C accelerometer/gyroscope and print the read data.
Connects to an QMI8658C I2C accelerometer/gyroscope and print the read data.
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.
ssd1306/spi_thumby
This example using the SSD1306 OLED display over SPI on the Thumby board A very tiny 72x40 display.
This example using the SSD1306 OLED display over SPI on the Thumby board A very tiny 72x40 display.
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
ws2812
Connects to an WS2812 RGB LED strip with 10 LEDS.
Connects to an WS2812 RGB LED strip with 10 LEDS.
Package ft6336 provides a driver for the FT6336 I2C Self-Capacitive touch panel controller.
Package ft6336 provides a driver for the FT6336 I2C Self-Capacitive touch panel controller.
Package gc9a01 implements a driver for the gc9a01 LCD round display
Package gc9a01 implements a driver for the gc9a01 LCD round display
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
Package hcsr04 provides a driver for the HC-SR04 ultrasonic distance sensor
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 hts221 implements a driver for HTS221, a capacitive digital sensor for relative humidity and temperature.
Package hts221 implements a driver for HTS221, a capacitive digital sensor for relative humidity and temperature.
Package hub75 implements a driver for the HUB75 LED matrix.
Package hub75 implements a driver for the HUB75 LED matrix.
image
internal/compress/flate
Package flate implements the DEFLATE compressed data format, described in RFC 1951.
Package flate implements the DEFLATE compressed data format, described in RFC 1951.
internal/compress/zlib
Package zlib implements reading and writing of zlib format compressed data, as specified in RFC 1950.
Package zlib implements reading and writing of zlib format compressed data, as specified in RFC 1950.
internal/imageutil
Package imageutil contains code shared by image-related packages.
Package imageutil contains code shared by image-related packages.
jpeg
Package jpeg implements a JPEG image decoder and encoder.
Package jpeg implements a JPEG image decoder and encoder.
png
Package png implements a PNG image decoder and encoder.
Package png implements a PNG image decoder and encoder.
internal
Package is31fl3731 provides a driver for the Lumissil IS31FL3731 matrix LED driver.
Package is31fl3731 provides a driver for the Lumissil IS31FL3731 matrix LED driver.
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 lps22hb implements a driver for LPS22HB, a MEMS nano pressure sensor.
Package lps22hb implements a driver for LPS22HB, a MEMS nano pressure sensor.
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)
Package lsm6ds3 implements a driver for the LSM6DS3 a 6 axis Inertial Measurement Unit (IMU)
Package lsm6ds3tr implements a driver for the LSM6DS3TR a 6 axis Inertial Measurement Unit (IMU)
Package lsm6ds3tr implements a driver for the LSM6DS3TR a 6 axis Inertial Measurement Unit (IMU)
Package lsm6dsox implements a driver for the LSM6DSOX a 6 axis Inertial Measurement Unit (IMU)
Package lsm6dsox implements a driver for the LSM6DSOX a 6 axis Inertial Measurement Unit (IMU)
LSM9DS1, 9 axis Inertial Measurement Unit (IMU)
LSM9DS1, 9 axis Inertial Measurement Unit (IMU)
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.
Package makeybutton providers a driver for a button that can be triggered by anything that is conductive by using an ultra high value resistor.
Package makeybutton providers a driver for a button that can be triggered by anything that is conductive by using an ultra high value resistor.
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 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.
Package mpu6886 provides a driver for the MPU6886 accelerometer and gyroscope made by InvenSense.
Package mpu6886 provides a driver for the MPU6886 accelerometer and gyroscope made by InvenSense.
Package wire implements the Dallas Semiconductor Corp.'s 1-wire bus system.
Package wire implements the Dallas Semiconductor Corp.'s 1-wire bus system.
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 pcf8523 implements a driver for the PCF8523 CMOS Real-Time Clock (RTC)
Package pcf8523 implements a driver for the PCF8523 CMOS Real-Time Clock (RTC)
Package pixel contains pixel format definitions used in various displays and fast operations on them.
Package pixel contains pixel format definitions used in various displays and fast operations on them.
Package qmi8658c provides a driver for the QMI8658C accelerometer and gyroscope made by QST Solutions.
Package qmi8658c provides a driver for the QMI8658C accelerometer and gyroscope made by QST Solutions.
Package scd4x provides a driver for the scd4x I2C envrironment sensor.
Package scd4x provides a driver for the scd4x I2C envrironment sensor.
package sdcard provides a TinyGo driver for sdcard/mmc devices using a SPI connection.
package sdcard provides a TinyGo driver for sdcard/mmc devices using a SPI connection.
Package seesaw provides a driver implementation to communicate with Adafruit's seesaw chip.
Package seesaw provides a driver implementation to communicate with Adafruit's seesaw chip.
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.
SGP30 VOC sensor.
SGP30 VOC sensor.
Package sh1106 implements a driver for the SH1106 display controller
Package sh1106 implements a driver for the SH1106 display controller
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 sht4x provides a driver for the SHT4x digital humidity sensor series by Sensirion.
Package sht4x provides a driver for the SHT4x digital humidity sensor series by Sensirion.
Package shtc3 provides a driver for the SHTC3 digital humidity sensor series by Sensirion.
Package shtc3 provides a driver for the SHTC3 digital humidity sensor series by Sensirion.
Package ssd1289 implements a driver for the SSD1289 led matrix controller as packaged on the TFT_320QVT board
Package ssd1289 implements a driver for the SSD1289 led matrix controller as packaged on the TFT_320QVT board
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 sx127x provides a driver for SX127x LoRa transceivers.
Package sx127x provides a driver for SX127x LoRa transceivers.
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 ttp229 is for the 16 keys or 8 keys touch pad detector IC Datasheet (BSF version): https://www.sunrom.com/download/SUNROM-TTP229-BSF_V1.1_EN.pdf
Package ttp229 is for the 16 keys or 8 keys touch pad detector IC Datasheet (BSF version): https://www.sunrom.com/download/SUNROM-TTP229-BSF_V1.1_EN.pdf
Package uc8151 implements a driver for e-ink displays controlled by UC8151
Package uc8151 implements a driver for e-ink displays controlled by UC8151
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
Package vl53l1x provides a driver for the VL53L1X time-of-flight distance sensor
Package vl6180x provides a driver for the VL6180X time-of-flight distance sensor
Package vl6180x provides a driver for the VL6180X time-of-flight distance sensor
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.
epd2in9
Package epd2in9 implements a driver for Waveshare 2.9in black and white e-paper device.
Package epd2in9 implements a driver for Waveshare 2.9in black and white 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 ws2812 implements a driver for WS2812 and SK6812 RGB LED strips.
Package ws2812 implements a driver for WS2812 and SK6812 RGB LED strips.
Package xpt2046 implements a driver for the XPT2046 resistive touch controller as packaged on the TFT_320QVT board
Package xpt2046 implements a driver for the XPT2046 resistive touch controller as packaged on the TFT_320QVT board

Jump to

Keyboard shortcuts

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