diff --git a/drivers/led_strip/CMakeLists.txt b/drivers/led_strip/CMakeLists.txt index 6bbab5b330cd0..63e1c61765600 100644 --- a/drivers/led_strip/CMakeLists.txt +++ b/drivers/led_strip/CMakeLists.txt @@ -1,6 +1,6 @@ # SPDX-License-Identifier: Apache-2.0 -zephyr_sources_ifdef(CONFIG_LPD880X_STRIP lpd880x.c) -zephyr_sources_ifdef(CONFIG_WS2812_STRIP ws2812.c) -zephyr_sources_ifdef(CONFIG_WS2812B_SW ws2812b_sw.c) -zephyr_sources_ifdef(CONFIG_APA102_STRIP apa102.c) +zephyr_sources_ifdef(CONFIG_LPD880X_STRIP lpd880x.c) +zephyr_sources_ifdef(CONFIG_WS2812_STRIP_SPI ws2812_spi.c) +zephyr_sources_ifdef(CONFIG_WS2812_STRIP_GPIO ws2812_gpio.c) +zephyr_sources_ifdef(CONFIG_APA102_STRIP apa102.c) diff --git a/drivers/led_strip/Kconfig b/drivers/led_strip/Kconfig index b41ff7dfaf7d0..a9b00a294bc60 100644 --- a/drivers/led_strip/Kconfig +++ b/drivers/led_strip/Kconfig @@ -31,8 +31,6 @@ source "drivers/led_strip/Kconfig.lpd880x" source "drivers/led_strip/Kconfig.ws2812" -source "drivers/led_strip/Kconfig.ws2812b_sw" - source "drivers/led_strip/Kconfig.apa102" endif # LED_STRIP diff --git a/drivers/led_strip/Kconfig.ws2812 b/drivers/led_strip/Kconfig.ws2812 index 111db1dcc8298..e87b4e1ab2fa0 100644 --- a/drivers/led_strip/Kconfig.ws2812 +++ b/drivers/led_strip/Kconfig.ws2812 @@ -1,4 +1,6 @@ # Copyright (c) 2017 Linaro Limited +# Copyright (c) 2019 Nordic Semiconductor ASA +# # SPDX-License-Identifier: Apache-2.0 # The following blog post is an excellent resource about pulse timing: @@ -7,93 +9,33 @@ menuconfig WS2812_STRIP bool "Enable WS2812 (and compatible) LED strip driver" - depends on SPI + select LED_STRIP_RGB_SCRATCH help Enable LED strip driver for daisy chains of WS2812-ish (or WS2812B, WS2813, SK6812, or compatible) devices. - These devices have a one-wire communications interface - which encodes bits using pulses. Short pulses indicate - zero bits, and long pulses indicate ones; refer to the - chip datasheets for precise specifications. To implement - this in a multitasking operating system, this driver - generates the pulses using a SPI peripheral. if WS2812_STRIP -config WS2812_STRIP_MAX_PIXELS - int "Maximum number of pixels in a strip" - default 12 - help - Set this to the maximum number of pixels you need - to control at once. There is an 8x memory penalty associated - with each increment of this value, so it's worth optimizing. - -config WS2812_STRIP_ONE_FRAME - hex "SPI frame to shift out to signal a one bit" - default 0x7c if SOC_SERIES_STM32F4X - default 0x70 if SOC_FAMILY_NRF - help - When shifted out at the configured clock frequency, - this must generate a pulse whose width fits within the chipset - specifications for T1H, and whose interpulse timing meets low - times. It is recommended that the first and last bits in the - frame be zero; this "encourages" SPI IPs to leave MOSI low - between frames. - -config WS2812_STRIP_ZERO_FRAME - hex "SPI frame to shift out to signal a zero bit" - default 0x60 if SOC_SERIES_STM32F4X - default 0x40 if SOC_FAMILY_NRF - help - When shifted out at the configured clock frequency, - this must generate a pulse whose width fits within the chipset - specifications for T0H, and whose interpulse timing meets low - times. It is recommended that the first and last bits in the - frame be zero; this "encourages" SPI IPs to leave MOSI low - between frames. - -# By default, we use GRBW [sic] (and ignore W). -comment "The following options determine channel data order on the wire." - -config WS2812_RED_ORDER - int "Order in which a red pixel should be shifted out" - default 1 - range 0 3 - help - If the red channel is shifted out first, specify 0. - If second, specify 1, and so on. +choice WS2812_STRIP_DRIVER +prompt "Driver backend" +default WS2812_STRIP_SPI -config WS2812_GRN_ORDER - int "Order in which a green pixel should be shifted out" - default 0 - range 0 3 - help - If the green channel is shifted out first, specify 0. - If second, specify 1, and so on. - -config WS2812_BLU_ORDER - int "Order in which a blue pixel should be shifted out" - default 2 - range 0 3 +config WS2812_STRIP_SPI + bool "Enable the SPI driver" + depends on SPI help - If the blue channel is shifted out first, specify 0. - If second, specify 1, and so on. + The SPI driver is portable, but requires significantly more + memory (1 byte of overhead per bit of pixel data). -config WS2812_HAS_WHITE_CHANNEL - bool "Does the chip have a white channel on wire?" - default y +config WS2812_STRIP_GPIO + bool "Enable the GPIO driver" + # Only an Cortex-M0 inline assembly implementation for the nRF51 + # is supported currently. + depends on SOC_SERIES_NRF51X help - If the chipset has a white channel, say y. White channels - are not used by the driver, but must be declared if expected - by the chip. + The GPIO driver does bit-banging with inline assembly, + and is not available on all SoCs. -config WS2812_WHT_ORDER - int "Order in which a white pixel should be shifted out" - default 3 - range 0 3 - depends on WS2812_HAS_WHITE_CHANNEL - help - If the blue channel is shifted out first, specify 0. - If second, specify 1, and so on. +endchoice -endif # WS2812_STRIP +endif diff --git a/drivers/led_strip/Kconfig.ws2812b_sw b/drivers/led_strip/Kconfig.ws2812b_sw deleted file mode 100644 index 7a0a9551445be..0000000000000 --- a/drivers/led_strip/Kconfig.ws2812b_sw +++ /dev/null @@ -1,36 +0,0 @@ -# Copyright (c) 2018 Intel Corporation -# SPDX-License-Identifier: Apache-2.0 - -menuconfig WS2812B_SW - bool "Enable WS2812B software-based LED strip driver" - # Only an Cortex-M0 inline assembly implementation for the nRF51 - # is supported currently. - depends on SOC_SERIES_NRF51X - help - A software-based (bit-banging) LED strip driver for daisy - chains of WS2812B devices. This driver implements the signal - sending with software-based bit-banging. If a more efficient - option, such as SPI, is available, another driver is recommended - to be used. - -if WS2812B_SW - -config WS2812B_SW_NAME - string "Driver name" - default "ws2812b_sw" - help - Device name for WS2812B LED strip. - -config WS2812B_SW_GPIO_NAME - string "GPIO port that the LED strip is connected to" - default "GPIO_0" if SOC_FAMILY_NRF - help - GPIO port name. - -config WS2812B_SW_GPIO_PIN - int "GPIO pin that the LED strip is connected to" - default 3 if BOARD_BBC_MICROBIT # P0 - help - GPIO pin number that the LED strip is connected to. - -endif diff --git a/drivers/led_strip/ws2812.c b/drivers/led_strip/ws2812.c deleted file mode 100644 index 5c7477291811d..0000000000000 --- a/drivers/led_strip/ws2812.c +++ /dev/null @@ -1,209 +0,0 @@ -/* - * Copyright (c) 2017 Linaro Limited - * - * SPDX-License-Identifier: Apache-2.0 - */ - -#include - -#include - -#define LOG_LEVEL CONFIG_LED_STRIP_LOG_LEVEL -#include -LOG_MODULE_REGISTER(ws2812); - -#include -#include -#include -#include - -/* - * WS2812-ish SPI master configuration: - * - * - mode 0 (the default), 8 bit, MSB first (arbitrary), one-line SPI - * - no shenanigans (don't hold CS, don't hold the device lock, this - * isn't an EEPROM) - */ -#define SPI_OPER (SPI_OP_MODE_MASTER | \ - SPI_TRANSFER_MSB | \ - SPI_WORD_SET(8) | \ - SPI_LINES_SINGLE) - -#define SPI_FREQ DT_INST_0_WORLDSEMI_WS2812_SPI_MAX_FREQUENCY -#define ONE_FRAME CONFIG_WS2812_STRIP_ONE_FRAME -#define ZERO_FRAME CONFIG_WS2812_STRIP_ZERO_FRAME -#define RED_OFFSET (8 * sizeof(u8_t) * CONFIG_WS2812_RED_ORDER) -#define GRN_OFFSET (8 * sizeof(u8_t) * CONFIG_WS2812_GRN_ORDER) -#define BLU_OFFSET (8 * sizeof(u8_t) * CONFIG_WS2812_BLU_ORDER) -#ifdef CONFIG_WS2812_HAS_WHITE_CHANNEL -#define WHT_OFFSET (8 * sizeof(u8_t) * CONFIG_WS2812_WHT_ORDER) -#else -#define WHT_OFFSET -1 -#endif - -/* - * Despite datasheet claims (see blog post link in Kconfig.ws2812), a - * 6 microsecond pulse is enough to reset the strip. Convert that into - * a number of 8 bit SPI frames, adding another just to be safe. - */ -#define RESET_NFRAMES ((size_t)ceiling_fraction(3 * SPI_FREQ, 4000000) + 1) - -#if CONFIG_WS2812_HAS_WHITE_CHANNEL -#define PX_BUF_PER_PX 32 -#else -#define PX_BUF_PER_PX 24 -#endif - -struct ws2812_data { - struct device *spi; - struct spi_config config; - u8_t px_buf[PX_BUF_PER_PX * CONFIG_WS2812_STRIP_MAX_PIXELS]; -}; - -/* - * Convert a color channel's bits into a sequence of SPI frames (with - * the proper pulse and inter-pulse widths) to shift out. - */ -static inline void ws2812_serialize_color(u8_t buf[8], u8_t color) -{ - int i; - - for (i = 0; i < 8; i++) { - buf[i] = color & BIT(7 - i) ? ONE_FRAME : ZERO_FRAME; - } -} - -/* - * Convert a pixel into SPI frames, returning the number of bytes used. - */ -static void ws2812_serialize_pixel(u8_t px[PX_BUF_PER_PX], - struct led_rgb *pixel) -{ - ws2812_serialize_color(px + RED_OFFSET, pixel->r); - ws2812_serialize_color(px + GRN_OFFSET, pixel->g); - ws2812_serialize_color(px + BLU_OFFSET, pixel->b); - if (IS_ENABLED(CONFIG_WS2812_HAS_WHITE_CHANNEL)) { - ws2812_serialize_color(px + WHT_OFFSET, 0); /* unused */ - } -} - -/* - * Latch current color values on strip and reset its state machines. - */ -static int ws2812_reset_strip(struct ws2812_data *data) -{ - u8_t reset_buf[RESET_NFRAMES]; - const struct spi_buf reset = { - .buf = reset_buf, - .len = sizeof(reset_buf), - }; - const struct spi_buf_set tx = { - .buffers = &reset, - .count = 1 - }; - - (void)memset(reset_buf, 0x00, sizeof(reset_buf)); - - return spi_write(data->spi, &data->config, &tx); -} - -static int ws2812_strip_update_rgb(struct device *dev, struct led_rgb *pixels, - size_t num_pixels) -{ - struct ws2812_data *drv_data = dev->driver_data; - struct spi_config *config = &drv_data->config; - u8_t *px_buf = drv_data->px_buf; - struct spi_buf buf = { - .buf = px_buf, - .len = PX_BUF_PER_PX * num_pixels, - }; - const struct spi_buf_set tx = { - .buffers = &buf, - .count = 1 - }; - size_t i; - int rc; - - if (num_pixels > CONFIG_WS2812_STRIP_MAX_PIXELS) { - return -ENOMEM; - } - - for (i = 0; i < num_pixels; i++) { - ws2812_serialize_pixel(&px_buf[PX_BUF_PER_PX * i], &pixels[i]); - } - - rc = spi_write(drv_data->spi, config, &tx); - if (rc) { - (void)ws2812_reset_strip(drv_data); - return rc; - } - - return ws2812_reset_strip(drv_data); -} - -static int ws2812_strip_update_channels(struct device *dev, u8_t *channels, - size_t num_channels) -{ - struct ws2812_data *drv_data = dev->driver_data; - struct spi_config *config = &drv_data->config; - u8_t px_buf[8]; /* one byte per bit */ - const struct spi_buf buf = { - .buf = px_buf, - .len = sizeof(px_buf), - }; - const struct spi_buf_set tx = { - .buffers = &buf, - .count = 1 - }; - size_t i; - int rc; - - for (i = 0; i < num_channels; i++) { - ws2812_serialize_color(px_buf, channels[i]); - rc = spi_write(drv_data->spi, config, &tx); - if (rc) { - /* - * Latch anything we've shifted out first, to - * call visual attention to the problematic - * pixel. - */ - (void)ws2812_reset_strip(drv_data); - LOG_ERR("can't set channel %u: %d", i, rc); - return rc; - } - } - - return ws2812_reset_strip(drv_data); -} - -static int ws2812_strip_init(struct device *dev) -{ - struct ws2812_data *data = dev->driver_data; - struct spi_config *config = &data->config; - - data->spi = device_get_binding(DT_INST_0_WORLDSEMI_WS2812_BUS_NAME); - if (!data->spi) { - LOG_ERR("SPI device %s not found", - DT_INST_0_WORLDSEMI_WS2812_BUS_NAME); - return -ENODEV; - } - - config->frequency = SPI_FREQ; - config->operation = SPI_OPER; - config->slave = DT_INST_0_WORLDSEMI_WS2812_BASE_ADDRESS; - config->cs = NULL; - - return 0; -} - -static struct ws2812_data ws2812_strip_data; - -static const struct led_strip_driver_api ws2812_strip_api = { - .update_rgb = ws2812_strip_update_rgb, - .update_channels = ws2812_strip_update_channels, -}; - -DEVICE_AND_API_INIT(ws2812_strip, DT_INST_0_WORLDSEMI_WS2812_LABEL, - ws2812_strip_init, &ws2812_strip_data, - NULL, POST_KERNEL, CONFIG_LED_STRIP_INIT_PRIORITY, - &ws2812_strip_api); diff --git a/drivers/led_strip/ws2812_gpio.c b/drivers/led_strip/ws2812_gpio.c new file mode 100644 index 0000000000000..5b794f2ddd07b --- /dev/null +++ b/drivers/led_strip/ws2812_gpio.c @@ -0,0 +1,246 @@ +/* + * Copyright (c) 2018 Intel Corporation + * Copyright (c) 2019 Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +#include + +#define LOG_LEVEL CONFIG_LED_STRIP_LOG_LEVEL +#include +LOG_MODULE_REGISTER(ws2812_gpio); + +#include +#include +#include +#include +#include + +struct ws2812_gpio_data { + struct device *gpio; + struct device *clk; +}; + +struct ws2812_gpio_cfg { + u8_t pin; + bool has_white; +}; + +static struct ws2812_gpio_data *dev_data(struct device *dev) +{ + return dev->driver_data; +} + +static const struct ws2812_gpio_cfg *dev_cfg(struct device *dev) +{ + return dev->config->config_info; +} + +/* + * This is hard-coded to nRF51 in two ways: + * + * 1. The assembly delays T1H, T0H, TxL + * 2. GPIO set/clear + */ + +/* + * T1H: 1 bit high pulse delay: 12 cycles == .75 usec + * T0H: 0 bit high pulse delay: 4 cycles == .25 usec + * TxL: inter-bit low pulse delay: 8 cycles == .5 usec + * + * We can't use k_busy_wait() here: its argument is in microseconds, + * and we need roughly .05 microsecond resolution. + */ +#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n" +#define DELAY_T0H "nop\nnop\nnop\nnop\n" +#define DELAY_TxL "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n" + +/* + * GPIO set/clear (these make assumptions about assembly details + * below). + * + * This uses OUTCLR == OUTSET+4. + * + * We should be able to make this portable using the results of + * https://github.com/zephyrproject-rtos/zephyr/issues/11917. + * + * We already have the GPIO device stashed in ws2812_gpio_data, so + * this driver can be used as a test case for the optimized API. + * + * Per Arm docs, both Rd and Rn must be r0-r7, so we use the "l" + * constraint in the below assembly. + */ +#define SET_HIGH "str %[p], [%[r], #0]\n" /* OUTSET = BIT(LED_PIN) */ +#define SET_LOW "str %[p], [%[r], #4]\n" /* OUTCLR = BIT(LED_PIN) */ + +/* Send out a 1 bit's pulse */ +#define ONE_BIT(base, pin) do { \ + __asm volatile (SET_HIGH \ + DELAY_T1H \ + SET_LOW \ + DELAY_TxL \ + :: \ + [r] "l" (base), \ + [p] "l" (pin)); } while (0) + +/* Send out a 0 bit's pulse */ +#define ZERO_BIT(base, pin) do { \ + __asm volatile (SET_HIGH \ + DELAY_T0H \ + SET_LOW \ + DELAY_TxL \ + :: \ + [r] "l" (base), \ + [p] "l" (pin)); } while (0) + +static int send_buf(struct device *dev, u8_t *buf, size_t len) +{ + volatile u32_t *base = (u32_t *)&NRF_GPIO->OUTSET; + const u32_t val = BIT(dev_cfg(dev)->pin); + struct device *clk = dev_data(dev)->clk; + unsigned int key; + int rc; + + rc = clock_control_on(clk, NULL); + if (rc) { + return rc; + } + + key = irq_lock(); + + while (len--) { + u32_t b = *buf++; + s32_t i; + + /* + * Generate signal out of the bits, MSbit first. + * + * Accumulator maintenance and branching mean the + * inter-bit time will be longer than TxL, but the + * wp.josh.com blog post says we have at least 5 usec + * of slack time between bits before we risk the + * signal getting latched, so this will be fine as + * long as the compiler does something minimally + * reasonable. + */ + for (i = 7; i >= 0; i--) { + if (b & BIT(i)) { + ONE_BIT(base, val); + } else { + ZERO_BIT(base, val); + } + } + } + + irq_unlock(key); + + rc = clock_control_off(clk, NULL); + + return rc; +} + +static int ws2812_gpio_update_rgb(struct device *dev, struct led_rgb *pixels, + size_t num_pixels) +{ + const struct ws2812_gpio_cfg *config = dev->config->config_info; + const bool has_white = config->has_white; + u8_t *ptr = (u8_t *)pixels; + size_t i; + + /* Convert from RGB to on-wire format (GRB or GRBW) */ + for (i = 0; i < num_pixels; i++) { + u8_t r = pixels[i].r; + u8_t g = pixels[i].g; + u8_t b = pixels[i].b; + + *ptr++ = g; + *ptr++ = r; + *ptr++ = b; + if (has_white) { + *ptr++ = 0; /* white channel is unused */ + } + } + + return send_buf(dev, (u8_t *)pixels, num_pixels * (has_white ? 4 : 3)); +} + +static int ws2812_gpio_update_channels(struct device *dev, u8_t *channels, + size_t num_channels) +{ + LOG_ERR("update_channels not implemented"); + return -ENOTSUP; +} + +static const struct led_strip_driver_api ws2812_gpio_api = { + .update_rgb = ws2812_gpio_update_rgb, + .update_channels = ws2812_gpio_update_channels, +}; + +#define WS2812_GPIO_LABEL(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_GPIO_LABEL) +#define WS2812_GPIO_HAS_WHITE(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_GPIO_HAS_WHITE_CHANNEL == 1) +#define WS2812_GPIO_DEV(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_GPIO_IN_GPIOS_CONTROLLER) +#define WS2812_GPIO_PIN(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_GPIO_IN_GPIOS_PIN) +#define WS2812_GPIO_FLAGS(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_GPIO_IN_GPIOS_FLAGS) +/* + * The inline assembly above is designed to work on nRF51 devices with + * the 16 MHz clock enabled. + * + * TODO: try to make this portable, or at least port to more devices. + */ +#define WS2812_GPIO_CLK(idx) DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_16M" + +#define WS2812_GPIO_DEVICE(idx) \ + \ + static int ws2812_gpio_##idx##_init(struct device *dev) \ + { \ + struct ws2812_gpio_data *data = dev_data(dev); \ + \ + data->gpio = device_get_binding(WS2812_GPIO_DEV(idx)); \ + if (!data->gpio) { \ + LOG_ERR("Unable to find GPIO controller %s", \ + WS2812_GPIO_DEV(idx)); \ + return -ENODEV; \ + } \ + \ + data->clk = device_get_binding(WS2812_GPIO_CLK(idx)); \ + if (!data->clk) { \ + LOG_ERR("Unable to find clock %s", \ + WS2812_GPIO_CLK(idx)); \ + return -ENODEV; \ + } \ + \ + return gpio_pin_configure(data->gpio, \ + WS2812_GPIO_PIN(idx), \ + WS2812_GPIO_FLAGS(idx) | \ + GPIO_OUTPUT); \ + } \ + \ + static struct ws2812_gpio_data ws2812_gpio_##idx##_data; \ + \ + static const struct ws2812_gpio_cfg ws2812_gpio_##idx##_cfg = { \ + .pin = WS2812_GPIO_PIN(idx), \ + .has_white = WS2812_GPIO_HAS_WHITE(idx), \ + }; \ + \ + DEVICE_AND_API_INIT(ws2812_gpio_##idx, WS2812_GPIO_LABEL(idx), \ + ws2812_gpio_##idx##_init, \ + &ws2812_gpio_##idx##_data, \ + &ws2812_gpio_##idx##_cfg, POST_KERNEL, \ + CONFIG_LED_STRIP_INIT_PRIORITY, \ + &ws2812_gpio_api) + +#ifdef DT_INST_0_WORLDSEMI_WS2812_GPIO_LABEL +WS2812_GPIO_DEVICE(0); +#endif + +#ifdef DT_INST_1_WORLDSEMI_WS2812_GPIO_LABEL +WS2812_GPIO_DEVICE(1); +#endif diff --git a/drivers/led_strip/ws2812_spi.c b/drivers/led_strip/ws2812_spi.c new file mode 100644 index 0000000000000..df3193e8fe6a4 --- /dev/null +++ b/drivers/led_strip/ws2812_spi.c @@ -0,0 +1,237 @@ +/* + * Copyright (c) 2017 Linaro Limited + * Copyright (c) 2019, Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +#include + +#define LOG_LEVEL CONFIG_LED_STRIP_LOG_LEVEL +#include +LOG_MODULE_REGISTER(ws2812_spi); + +#include +#include +#include +#include +#include + +/* spi-one-frame and spi-zero-frame in DT are for 8-bit frames. */ +#define SPI_FRAME_BITS 8 + +/* + * Delay time to make sure the strip has latched a signal. + * + * Despite datasheet claims, a 6 microsecond delay is enough to reset + * the strip. Delay for 8 usec just to be safe. + */ +#define RESET_DELAY_USEC 8 + +/* + * SPI master configuration: + * + * - mode 0 (the default), 8 bit, MSB first (arbitrary), one-line SPI + * - no shenanigans (don't hold CS, don't hold the device lock, this + * isn't an EEPROM) + */ +#define SPI_OPER (SPI_OP_MODE_MASTER | SPI_TRANSFER_MSB | \ + SPI_WORD_SET(SPI_FRAME_BITS) | SPI_LINES_SINGLE) + +#define BYTES_PER_PX(has_white) ((has_white) ? 32 : 24) + +struct ws2812_spi_data { + struct device *spi; +}; + +struct ws2812_spi_cfg { + struct spi_config spi_cfg; + u8_t *px_buf; + size_t px_buf_size; + u8_t one_frame; + u8_t zero_frame; + bool has_white; +}; + +static struct ws2812_spi_data *dev_data(struct device *dev) +{ + return dev->driver_data; +} + +static const struct ws2812_spi_cfg *dev_cfg(struct device *dev) +{ + return dev->config->config_info; +} + +/* + * Serialize an 8-bit color channel value into an equivalent sequence + * of SPI frames, MSbit first, where a one bit becomes SPI frame + * one_frame, and zero bit becomes zero_frame. + */ +static inline void ws2812_spi_ser(u8_t buf[8], u8_t color, + const u8_t one_frame, const u8_t zero_frame) +{ + int i; + + for (i = 0; i < 8; i++) { + buf[i] = color & BIT(7 - i) ? one_frame : zero_frame; + } +} + +/* + * Returns true if and only if cfg->px_buf is big enough to convert + * num_pixels RGB color values into SPI frames. + */ +static inline bool num_pixels_ok(const struct ws2812_spi_cfg *cfg, + size_t num_pixels) +{ + size_t nbytes; + bool overflow; + + overflow = size_mul_overflow(num_pixels, BYTES_PER_PX(cfg->has_white), + &nbytes); + return !overflow && (nbytes <= cfg->px_buf_size); +} + +/* + * Latch current color values on strip and reset its state machines. + */ +static inline void ws2812_reset_delay(void) +{ + /* + * TODO: swap out with k_usleep() once that can be trusted to + * work reliably. + */ + k_busy_wait(RESET_DELAY_USEC); +} + +static int ws2812_strip_update_rgb(struct device *dev, struct led_rgb *pixels, + size_t num_pixels) +{ + const struct ws2812_spi_cfg *cfg = dev_cfg(dev); + const u8_t one = cfg->one_frame, zero = cfg->zero_frame; + struct spi_buf buf = { + .buf = cfg->px_buf, + .len = cfg->px_buf_size, + }; + const struct spi_buf_set tx = { + .buffers = &buf, + .count = 1 + }; + u8_t *px_buf = cfg->px_buf; + size_t i; + int rc; + + if (!num_pixels_ok(cfg, num_pixels)) { + return -ENOMEM; + } + + /* + * Convert pixel data into SPI frames. Each frame has pixel + * data in GRB on-wire format, with zeroed out white channel data + * if applicable. + */ + for (i = 0; i < num_pixels; i++) { + ws2812_spi_ser(px_buf, pixels[i].g, one, zero); + ws2812_spi_ser(px_buf + 8, pixels[i].r, one, zero); + ws2812_spi_ser(px_buf + 16, pixels[i].b, one, zero); + if (cfg->has_white) { + ws2812_spi_ser(px_buf + 24, 0, one, zero); + px_buf += 32; + } else { + px_buf += 24; + } + } + + /* + * Display the pixel data. + */ + rc = spi_write(dev_data(dev)->spi, &cfg->spi_cfg, &tx); + ws2812_reset_delay(); + + return rc; +} + +static int ws2812_strip_update_channels(struct device *dev, u8_t *channels, + size_t num_channels) +{ + LOG_ERR("update_channels not implemented"); + return -ENOTSUP; +} + +static const struct led_strip_driver_api ws2812_spi_api = { + .update_rgb = ws2812_strip_update_rgb, + .update_channels = ws2812_strip_update_channels, +}; + +#define WS2812_SPI_LABEL(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_LABEL) +#define WS2812_SPI_NUM_PIXELS(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_CHAIN_LENGTH) +#define WS2812_SPI_HAS_WHITE(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_HAS_WHITE_CHANNEL == 1) +#define WS2812_SPI_BUS(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_BUS_NAME) +#define WS2812_SPI_SLAVE(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_BASE_ADDRESS) +#define WS2812_SPI_FREQ(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_SPI_MAX_FREQUENCY) +#define WS2812_SPI_ONE_FRAME(idx) \ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_SPI_ONE_FRAME) +#define WS2812_SPI_ZERO_FRAME(idx)\ + (DT_INST_##idx##_WORLDSEMI_WS2812_SPI_SPI_ZERO_FRAME) +#define WS2812_SPI_BUFSZ(idx) \ + (BYTES_PER_PX(WS2812_SPI_HAS_WHITE(idx)) * WS2812_SPI_NUM_PIXELS(idx)) + +#define WS2812_SPI_DEVICE(idx) \ + \ + static struct ws2812_spi_data ws2812_spi_##idx##_data; \ + \ + static u8_t ws2812_spi_##idx##_px_buf[WS2812_SPI_BUFSZ(idx)]; \ + \ + static const struct ws2812_spi_cfg ws2812_spi_##idx##_cfg = { \ + .spi_cfg = { \ + .frequency = WS2812_SPI_FREQ(idx), \ + .operation = SPI_OPER, \ + .slave = WS2812_SPI_SLAVE(idx), \ + .cs = NULL, \ + }, \ + .px_buf = ws2812_spi_##idx##_px_buf, \ + .px_buf_size = WS2812_SPI_BUFSZ(idx), \ + .one_frame = WS2812_SPI_ONE_FRAME(idx), \ + .zero_frame = WS2812_SPI_ZERO_FRAME(idx), \ + .has_white = WS2812_SPI_HAS_WHITE(idx), \ + }; \ + \ + static int ws2812_spi_##idx##_init(struct device *dev) \ + { \ + struct ws2812_spi_data *data = dev_data(dev); \ + \ + data->spi = device_get_binding(WS2812_SPI_BUS(idx)); \ + if (!data->spi) { \ + LOG_ERR("SPI device %s not found", \ + WS2812_SPI_BUS(idx)); \ + return -ENODEV; \ + } \ + \ + return 0; \ + } \ + \ + DEVICE_AND_API_INIT(ws2812_spi_##idx, \ + WS2812_SPI_LABEL(idx), \ + ws2812_spi_##idx##_init, \ + &ws2812_spi_##idx##_data, \ + &ws2812_spi_##idx##_cfg, \ + POST_KERNEL, \ + CONFIG_LED_STRIP_INIT_PRIORITY, \ + &ws2812_spi_api); + +#ifdef DT_INST_0_WORLDSEMI_WS2812_SPI_LABEL +WS2812_SPI_DEVICE(0); +#endif + +#ifdef DT_INST_1_WORLDSEMI_WS2812_SPI_LABEL +WS2812_SPI_DEVICE(1); +#endif diff --git a/drivers/led_strip/ws2812b_sw.c b/drivers/led_strip/ws2812b_sw.c deleted file mode 100644 index f44fca42df1bd..0000000000000 --- a/drivers/led_strip/ws2812b_sw.c +++ /dev/null @@ -1,149 +0,0 @@ -/* - * Copyright (c) 2018 Intel Corporation - * - * SPDX-License-Identifier: Apache-2.0 - */ - -#include - -#include - -#define LOG_LEVEL CONFIG_LED_STRIP_LOG_LEVEL -#include -LOG_MODULE_REGISTER(ws2812b_sw); - -#include -#include -#include -#include -#include - -#define BLOCKING ((void *)1) - -static int send_buf(u8_t *buf, size_t len) -{ - /* Address of OUTSET. OUTCLR is OUTSET + 4 */ - volatile u32_t *base = (u32_t *)(NRF_GPIO_BASE + 0x508); - u32_t pin = BIT(CONFIG_WS2812B_SW_GPIO_PIN); - struct device *clock; - unsigned int key; - /* Initilization of i is strictly not needed, but it avoids an - * uninitialized warning with the inline assembly. - */ - u32_t i = 0U; - - clock = device_get_binding(DT_INST_0_NORDIC_NRF_CLOCK_LABEL "_16M"); - if (!clock) { - LOG_ERR("Unable to get HF clock"); - return -EIO; - } - - /* The inline assembly further below is designed to work only with - * the 16 MHz clock enabled. - */ - clock_control_on(clock, BLOCKING); - key = irq_lock(); - - while (len--) { - u32_t b = *buf++; - - /* Generate signal out of the bits, MSB. 1-bit should be - * roughly 0.85us high, 0.4us low, whereas a 0-bit should be - * roughly 0.4us high, 0.85us low. - */ - __asm volatile ("movs %[i], #8\n" /* i = 8 */ - ".start_bit:\n" - - /* OUTSET = BIT(LED_PIN) */ - "strb %[p], [%[r], #0]\n" - - /* if (b & 0x80) goto .long */ - "tst %[b], %[m]\n" - "bne .long\n" - - /* 0-bit */ - "nop\nnop\n" - /* OUTCLR = BIT(LED_PIN) */ - "strb %[p], [%[r], #4]\n" - "nop\nnop\nnop\n" - "b .next_bit\n" - - /* 1-bit */ - ".long:\n" - "nop\nnop\nnop\nnop\nnop\nnop\nnop\n" - /* OUTCLR = BIT(LED_PIN) */ - "strb %[p], [%[r], #4]\n" - - ".next_bit:\n" - /* b <<= 1 */ - "lsl %[b], #1\n" - /* i-- */ - "sub %[i], #1\n" - /* if (i > 0) goto .start_bit */ - "bne .start_bit\n" - : - [i] "+r" (i) - : - [b] "l" (b), - [m] "l" (0x80), - [r] "l" (base), - [p] "r" (pin) - :); - } - - irq_unlock(key); - clock_control_off(clock, NULL); - - return 0; -} - -static int ws2812b_sw_update_rgb(struct device *dev, struct led_rgb *pixels, - size_t num_pixels) -{ - u8_t *ptr = (u8_t *)pixels; - size_t i; - - /* Convert from RGB to GRB format */ - for (i = 0; i < num_pixels; i++) { - u8_t r = pixels[i].r; - u8_t b = pixels[i].b; - u8_t g = pixels[i].g; - - *ptr++ = g; - *ptr++ = r; - *ptr++ = b; - } - - return send_buf((u8_t *)pixels, num_pixels * 3); -} - -static int ws2812b_sw_update_channels(struct device *dev, u8_t *channels, - size_t num_channels) -{ - LOG_ERR("update_channels not implemented"); - return -ENOSYS; -} - -static int ws2812b_sw_init(struct device *dev) -{ - struct device *gpio; - - gpio = device_get_binding(CONFIG_WS2812B_SW_GPIO_NAME); - if (!gpio) { - LOG_ERR("Unable to find %s", CONFIG_WS2812B_SW_GPIO_NAME); - return -ENODEV; - } - - gpio_pin_configure(gpio, CONFIG_WS2812B_SW_GPIO_PIN, GPIO_DIR_OUT); - - return 0; -} - -static const struct led_strip_driver_api ws2812b_sw_api = { - .update_rgb = ws2812b_sw_update_rgb, - .update_channels = ws2812b_sw_update_channels, -}; - -DEVICE_AND_API_INIT(ws2812b_sw, CONFIG_WS2812B_SW_NAME, ws2812b_sw_init, NULL, - NULL, POST_KERNEL, CONFIG_LED_STRIP_INIT_PRIORITY, - &ws2812b_sw_api); diff --git a/dts/bindings/led_strip/worldsemi,ws2812-gpio.yaml b/dts/bindings/led_strip/worldsemi,ws2812-gpio.yaml new file mode 100644 index 0000000000000..cd1737c6cb16a --- /dev/null +++ b/dts/bindings/led_strip/worldsemi,ws2812-gpio.yaml @@ -0,0 +1,25 @@ +# Copyright (c) 2019, Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +title: Worldsemi WS2812 LED strip, GPIO binding + +description: | + Driver bindings for bit-banging a WS2812 or compatible LED strip. + + The GPIO driver uses inline assembly, and isn't available for all + boards. + +compatible: "worldsemi,ws2812-gpio" + +include: [base.yaml, ws2812.yaml] + +properties: + label: + required: true + + in-gpios: + type: phandle-array + required: true + description: | + GPIO phandle and specifier for the pin connected to the daisy + chain's input pin. Exactly one pin should be given. diff --git a/dts/bindings/led_strip/worldsemi,ws2812-spi.yaml b/dts/bindings/led_strip/worldsemi,ws2812-spi.yaml new file mode 100644 index 0000000000000..a02e575222106 --- /dev/null +++ b/dts/bindings/led_strip/worldsemi,ws2812-spi.yaml @@ -0,0 +1,35 @@ +# Copyright (c) 2019, Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +title: Worldsemi WS2812 LED strip, SPI binding + +description: | + Driver bindings for controlling a WS2812 or compatible LED + strip with a SPI master. + + The SPI driver should be usable as long as a zephyr SPI API driver + is available for your board. Hardware specific tuning is required + using these properties: + + - spi-max-frequency + - spi-zero-frame + - spi-one-frame. + + Use of this driver implies an 8x internal memory overhead (1 byte of + driver RAM overhead per bit of pixel data). + +compatible: "worldsemi,ws2812-spi" + +include: [spi-device.yaml, ws2812.yaml] + +properties: + + spi-one-frame: + type: int + required: true + description: 8-bit SPI frame to shift out for a 1 pulse. + + spi-zero-frame: + type: int + required: true + description: 8-bit SPI frame to shift out for a 0 pulse. diff --git a/dts/bindings/led_strip/worldsemi,ws2812.yaml b/dts/bindings/led_strip/worldsemi,ws2812.yaml deleted file mode 100644 index b93f3dd67fcba..0000000000000 --- a/dts/bindings/led_strip/worldsemi,ws2812.yaml +++ /dev/null @@ -1,10 +0,0 @@ -# Copyright (c) 2019, Linaro Limited -# SPDX-License-Identifier: Apache-2.0 - -title: Worldsemi WS2812 SPI LED strip - -description: Worldsemi WS2812 SPI LED strip binding - -compatible: "worldsemi,ws2812" - -include: spi-device.yaml diff --git a/dts/bindings/led_strip/ws2812.yaml b/dts/bindings/led_strip/ws2812.yaml new file mode 100644 index 0000000000000..f28b6556ac0f3 --- /dev/null +++ b/dts/bindings/led_strip/ws2812.yaml @@ -0,0 +1,35 @@ +# Copyright (c) 2019, Linaro Limited +# Copyright (c) 2019, Nordic Semiconductor ASA +# +# SPDX-License-Identifier: Apache-2.0 + +title: Worldsemi WS2812 (and compatible) LED controller + +description: | + Driver bindings for daisy chains of WS2812 (and compatible devices + like SK6812) LED controllers. + + The PWM protocol is described here: + https://wp.josh.com/2014/05/13/ws2812-neopixels-are-not-so-finicky-once-you-get-to-know-them/ + + A 0 bit's pulse width is between 200 and 500 ns. A 1 bit's is + at least 550 ns, with 700 ns or so typical. Pixel order is GRB. + + You can connect the device to either a GPIO on your SoC, or a SPI + MOSI line. Use the worldsemi,ws2812-spi.yaml or + worldsemi,ws2812-gpio.yaml bindings instead of this file after + making your choice. + +properties: + chain-length: + type: int + required: true + description: | + The number of devices in the daisy-chain. + + has-white-channel: + type: boolean + description: | + If true, the device has a white channel. This is not supported + by the led_strip.h API, so the white data on the wire will be + zero if set. diff --git a/samples/drivers/led_ws2812/Kconfig b/samples/drivers/led_ws2812/Kconfig new file mode 100644 index 0000000000000..82588dcc9bd19 --- /dev/null +++ b/samples/drivers/led_ws2812/Kconfig @@ -0,0 +1,9 @@ +# Copyright (c) 2019 Nordic Semiconductor ASA +# SPDX-License-Identifier: Apache-2.0 + +# Use the SPI driver by default, unless the GPIO driver is +# specifically configured in. +config SPI + default y + +source "$ZEPHYR_BASE/Kconfig.zephyr" diff --git a/samples/drivers/led_ws2812/README.rst b/samples/drivers/led_ws2812/README.rst index f2053fafc234f..867c6d109476b 100644 --- a/samples/drivers/led_ws2812/README.rst +++ b/samples/drivers/led_ws2812/README.rst @@ -19,83 +19,46 @@ Requirements - LED strip using WS2812 or compatible, such as the `NeoPixel Ring 12 from AdaFruit`_. -- Zephyr board with SPI master driver. SPI communications must use 5V - signaling, which may require a level translator, such as the +- Note that 5V communications may require a level translator, such as the `74AHCT125`_. -- 5V power supply. +- LED power strip supply. It's fine to power the LED strip off of your board's + IO voltage level even if that's below 5V; the LEDs will simply be dimmer in + this case. Wiring ****** -#. Ensure your Zephyr board, the 5V power supply, and the LED strip - share a common ground. -#. Connect the MOSI pin of your board's SPI master to the data input - pin of the first WS2812 IC in the strip. -#. Connect the 5V power supply pin to the 5V input of the LED strip. +#. Ensure your Zephyr board, and the LED strip share a common ground. +#. Connect the LED strip control pin (either SPI MOSI or GPIO) from your board + to the data input pin of the first WS2812 IC in the strip. +#. Power the LED strip at an I/O level compatible with the control pin signals. Building and Running ******************** .. _blog post on WS2812 timing: https://wp.josh.com/2014/05/13/ws2812-neopixels-are-not-so-finicky-once-you-get-to-know-them/ -The sample application is located at ``samples/drivers/led_ws2812/`` -in the Zephyr source tree. +This sample's source directory is :zephyr_file:`samples/drivers/led_ws2812/`. -Configure For Your LED Strip -============================ +To make sure the sample is set up properly for building, you must: -The first thing you need to do is make sure that the driver is -configured to match the particular LED chips you're using. For -example, some chips have a "green, red, blue" color ordering on their -data pin, while others have "red, green, blue, white". Check your -chip's datasheet for your configuration (though given the number of -competing implementations and knock-offs, some trial and error may be -necessary). +- select the correct WS2812 driver backend for your SoC. This currently should + be :option:`CONFIG_WS2812_STRIP_SPI` unless you are using an nRF51 SoC, in + which case it will be :option:`CONFIG_WS2812_STRIP_GPIO`. -To make sure the driver is set up properly for your chips, check the -values of the following configuration options: +- create a ``led-strip`` :ref:`devicetree alias `, which + refers to a node in your :ref:`devicetree ` with a + ``worldsemi,ws2812-spi`` or ``worldsemi,ws2812-gpio`` compatible. The node + must be properly configured for the driver backend (SPI or GPIO) and daisy + chain length (number of WS2812 chips). -- :option:`CONFIG_WS2812_RED_ORDER` -- :option:`CONFIG_WS2812_GRN_ORDER` -- :option:`CONFIG_WS2812_BLU_ORDER` -- :option:`CONFIG_WS2812_WHT_ORDER` (available if your chips have a white - channel by setting :option:`CONFIG_WS2812_HAS_WHITE_CHANNEL` to ``y``). +For example devicetree configurations for each compatible, see +:zephyr_file:`samples/drivers/led_ws2812/boards/nrf52_pca10040.overlay` and +:zephyr_file:`samples/drivers/led_ws2812/boards/nrf51_pca10028.overlay`. -Refer to their help strings for details. - -Configure For Your Board -======================== - -Now check if your board is already supported, by looking for a file -named ``boards/YOUR_BOARD_NAME.conf`` in the application directory. - -If your board isn't supported yet, you'll need to configure the -application as follows. - -#. Configure your board's SPI master in a configuration file under - ``boards/`` in the sample directory. - - To provide additional configuration for some particular board, - create a ``boards/YOUR_BOARD_NAME.conf`` file in the application - directory. It will be merged into the application configuration. - - In this file, you must ensure that the SPI peripheral you want to - use for this demo is enabled, and that its name is "ws2812_spi". - See ``boards/96b_carbon.conf`` for an example, and refer to your - board's configuration options to set up your desired SPI master. - -#. Set the number of LEDs in your strip in the application sources. - This is determined by the macro ``STRIP_NUM_LEDS`` in the file - ``src/main.c``. The value in the file was chosen to work with the - AdaFruit NeoPixel Ring 12. - -#. Make sure that the SPI timing will generate pulses of the - appropriate widths. This involves setting the configuration options - :option:`CONFIG_WS2812_STRIP_ONE_FRAME`, and - :option:`CONFIG_WS2812_STRIP_ZERO_FRAME`. Refer to the Kconfig help for - those options, as well as this `blog post on WS2812 timing`_, for - more details. +Some boards are already supported out of the box; see the :file:`boards` +directory for this sample for details. Then build and flash the application: @@ -105,18 +68,14 @@ Then build and flash the application: :goals: flash :compact: -Refer to your :ref:`board's documentation ` for alternative -flash instructions if your board doesn't support the ``flash`` target. - When you connect to your board's serial console, you should see the following output: .. code-block:: none - ***** BOOTING ZEPHYR OS v1.9.99 ***** - [general] [INF] main: Found SPI device ws2812_spi - [general] [INF] main: Found LED strip device ws2812_strip - [general] [INF] main: Displaying pattern on strip + ***** Booting Zephyr OS build v2.1.0-rc1-191-gd2466cdaf045 ***** + [00:00:00.005,920] main: Found LED strip device WS2812 + [00:00:00.005,950] main: Displaying pattern on strip References ********** diff --git a/samples/drivers/led_ws2812/boards/96b_carbon.conf b/samples/drivers/led_ws2812/boards/96b_carbon.conf deleted file mode 100644 index 8bc20fc88d330..0000000000000 --- a/samples/drivers/led_ws2812/boards/96b_carbon.conf +++ /dev/null @@ -1,8 +0,0 @@ -CONFIG_POLL=y -CONFIG_SPI=y - -CONFIG_SPI_STM32=y -CONFIG_SPI_STM32_INTERRUPT=y -CONFIG_SPI_2=y - -CONFIG_WS2812_STRIP=y diff --git a/samples/drivers/led_ws2812/boards/96b_carbon.overlay b/samples/drivers/led_ws2812/boards/96b_carbon.overlay deleted file mode 100644 index b0b22b6073ec8..0000000000000 --- a/samples/drivers/led_ws2812/boards/96b_carbon.overlay +++ /dev/null @@ -1,15 +0,0 @@ -/* - * Copyright (c) 2018 Nordic Semiconductor ASA - * - * SPDX-License-Identifier: Apache-2.0 - */ - -&spi2 { - - ws2812@0 { - compatible = "worldsemi,ws2812"; - reg = <0>; - spi-max-frequency = <5250000>; - label = "WS2812"; - }; -}; diff --git a/samples/drivers/led_ws2812/boards/bbc_microbit.conf b/samples/drivers/led_ws2812/boards/bbc_microbit.conf index ad2dc4103b68f..3f0afed7d43dd 100644 --- a/samples/drivers/led_ws2812/boards/bbc_microbit.conf +++ b/samples/drivers/led_ws2812/boards/bbc_microbit.conf @@ -1,2 +1,2 @@ -CONFIG_GPIO=y -CONFIG_WS2812B_SW=y +CONFIG_SPI=n +CONFIG_WS2812_STRIP_GPIO=y diff --git a/samples/drivers/led_ws2812/boards/bbc_microbit.overlay b/samples/drivers/led_ws2812/boards/bbc_microbit.overlay new file mode 100644 index 0000000000000..f294dc607ae01 --- /dev/null +++ b/samples/drivers/led_ws2812/boards/bbc_microbit.overlay @@ -0,0 +1,22 @@ +/* + * Copyright (c) 2019, Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +/ { + led_strip: ws2812 { + compatible = "worldsemi,ws2812-gpio"; + label = "WS2812"; + + chain-length = <16>; /* arbitrary; change at will */ + /* P0: */ + in-gpios = <&gpio0 3 0>; + }; + + aliases { + led-strip = &led_strip; + }; +}; diff --git a/samples/drivers/led_ws2812/boards/nrf51_pca10028.conf b/samples/drivers/led_ws2812/boards/nrf51_pca10028.conf new file mode 100644 index 0000000000000..3f0afed7d43dd --- /dev/null +++ b/samples/drivers/led_ws2812/boards/nrf51_pca10028.conf @@ -0,0 +1,2 @@ +CONFIG_SPI=n +CONFIG_WS2812_STRIP_GPIO=y diff --git a/samples/drivers/led_ws2812/boards/nrf51_pca10028.overlay b/samples/drivers/led_ws2812/boards/nrf51_pca10028.overlay new file mode 100644 index 0000000000000..c0597a6fb9cb6 --- /dev/null +++ b/samples/drivers/led_ws2812/boards/nrf51_pca10028.overlay @@ -0,0 +1,25 @@ +/* + * Copyright (c) 2019, Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +/ { + led_strip: ws2812 { + compatible = "worldsemi,ws2812-gpio"; + label = "WS2812"; + + chain-length = <16>; /* arbitrary */ + /* + * Arduino D11 / P0.25, which was chosen to match the pin + * used in nrf52_pca10040.overlay. + */ + in-gpios = <&gpio0 25 0>; + }; + + aliases { + led-strip = &led_strip; + }; +}; diff --git a/samples/drivers/led_ws2812/boards/nrf52_pca10040.overlay b/samples/drivers/led_ws2812/boards/nrf52_pca10040.overlay new file mode 100644 index 0000000000000..fbdcdda7e7af4 --- /dev/null +++ b/samples/drivers/led_ws2812/boards/nrf52_pca10040.overlay @@ -0,0 +1,29 @@ +/* + * Copyright (c) 2019, Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "../nrf52-bindings.h" + +&arduino_spi { /* MOSI on D11 / P0.23 */ + led_strip: ws2812@0 { + compatible = "worldsemi,ws2812-spi"; + label = "WS2812"; + + /* SPI */ + reg = <0>; /* ignored, but necessary for SPI bindings */ + spi-max-frequency = ; + + /* WS2812 */ + chain-length = <16>; /* arbitrary; change at will */ + spi-one-frame = ; + spi-zero-frame = ; + }; +}; + +/ { + aliases { + led-strip = &led_strip; + }; +}; diff --git a/samples/drivers/led_ws2812/nrf52-bindings.h b/samples/drivers/led_ws2812/nrf52-bindings.h new file mode 100644 index 0000000000000..3ed907330a90c --- /dev/null +++ b/samples/drivers/led_ws2812/nrf52-bindings.h @@ -0,0 +1,20 @@ +/* + * Copyright (c) 2019, Nordic Semiconductor ASA + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_SAMPLES_DRIVERS_LED_WS2812_H_ +#define ZEPHYR_SAMPLES_DRIVERS_LED_WS2812_H_ + +/* + * At 4 MHz, 1 bit is 250 ns, so 3 bits is 750 ns. + * + * That's cutting it a bit close to the edge of the timing parameters, + * but it seems to work on AdaFruit LED rings. + */ +#define SPI_FREQ 4000000 +#define ZERO_FRAME 0x40 +#define ONE_FRAME 0x70 + +#endif diff --git a/samples/drivers/led_ws2812/prj.conf b/samples/drivers/led_ws2812/prj.conf index fe87e26daddb0..4319cb1f793f7 100644 --- a/samples/drivers/led_ws2812/prj.conf +++ b/samples/drivers/led_ws2812/prj.conf @@ -1,4 +1,4 @@ -# This file expresses generic requirements ONLY; see README.rst. - CONFIG_LOG=y CONFIG_LED_STRIP=y +CONFIG_LED_STRIP_LOG_LEVEL_DBG=y +CONFIG_WS2812_STRIP=y diff --git a/samples/drivers/led_ws2812/sample.yaml b/samples/drivers/led_ws2812/sample.yaml index 134ef2705f263..4d9811b650a95 100644 --- a/samples/drivers/led_ws2812/sample.yaml +++ b/samples/drivers/led_ws2812/sample.yaml @@ -3,5 +3,5 @@ sample: name: WS2812 sample tests: sample.driver.led_ws2812: - platform_whitelist: 96b_carbon bbc_microbit + platform_whitelist: bbc_microbit nrf51_pca10028 nrf52_pca10040 tags: LED diff --git a/samples/drivers/led_ws2812/src/main.c b/samples/drivers/led_ws2812/src/main.c index f3543df8a324b..adf0423fc9f32 100644 --- a/samples/drivers/led_ws2812/src/main.c +++ b/samples/drivers/led_ws2812/src/main.c @@ -18,72 +18,54 @@ LOG_MODULE_REGISTER(main); #include #include -/* - * Number of RGB LEDs in the LED strip, adjust as needed. - */ -#if defined(CONFIG_WS2812_STRIP) -#define STRIP_NUM_LEDS 12 -#define STRIP_DEV_NAME DT_INST_0_WORLDSEMI_WS2812_LABEL -#else -#define STRIP_NUM_LEDS 24 -#define STRIP_DEV_NAME CONFIG_WS2812B_SW_NAME -#endif +#define STRIP_LABEL DT_ALIAS_LED_STRIP_LABEL +#define STRIP_NUM_PIXELS DT_ALIAS_LED_STRIP_CHAIN_LENGTH -#define DELAY_TIME K_MSEC(40) +#define DELAY_TIME K_MSEC(50) -static const struct led_rgb colors[] = { - { .r = 0xff, .g = 0x00, .b = 0x00, }, /* red */ - { .r = 0x00, .g = 0xff, .b = 0x00, }, /* green */ - { .r = 0x00, .g = 0x00, .b = 0xff, }, /* blue */ -}; +#define RGB(_r, _g, _b) { .r = (_r), .g = (_g), .b = (_b) } -static const struct led_rgb black = { - .r = 0x00, - .g = 0x00, - .b = 0x00, +static const struct led_rgb colors[] = { + RGB(0x0f, 0x00, 0x00), /* red */ + RGB(0x00, 0x0f, 0x00), /* green */ + RGB(0x00, 0x00, 0x0f), /* blue */ }; -struct led_rgb strip_colors[STRIP_NUM_LEDS]; - -const struct led_rgb *color_at(size_t time, size_t i) -{ - size_t rgb_start = time % STRIP_NUM_LEDS; - - if (rgb_start <= i && i < rgb_start + ARRAY_SIZE(colors)) { - return &colors[i - rgb_start]; - } else { - return &black; - } -} +struct led_rgb pixels[STRIP_NUM_PIXELS]; void main(void) { struct device *strip; - size_t i, time; + size_t cursor = 0, color = 0; + int rc; - strip = device_get_binding(STRIP_DEV_NAME); + strip = device_get_binding(STRIP_LABEL); if (strip) { - LOG_INF("Found LED strip device %s", STRIP_DEV_NAME); + LOG_INF("Found LED strip device %s", STRIP_LABEL); } else { - LOG_ERR("LED strip device %s not found", STRIP_DEV_NAME); + LOG_ERR("LED strip device %s not found", STRIP_LABEL); return; } - /* - * Display a pattern that "walks" the three primary colors - * down the strip until it reaches the end, then starts at the - * beginning. This has the effect of moving it around in a - * circle in the case of rings of pixels. - */ LOG_INF("Displaying pattern on strip"); - time = 0; while (1) { - for (i = 0; i < STRIP_NUM_LEDS; i++) { - memcpy(&strip_colors[i], color_at(time, i), - sizeof(strip_colors[i])); + memset(&pixels, 0x00, sizeof(pixels)); + memcpy(&pixels[cursor], &colors[color], sizeof(struct led_rgb)); + rc = led_strip_update_rgb(strip, pixels, STRIP_NUM_PIXELS); + + if (rc) { + LOG_ERR("couldn't update strip: %d", rc); } - led_strip_update_rgb(strip, strip_colors, STRIP_NUM_LEDS); + + cursor++; + if (cursor >= STRIP_NUM_PIXELS) { + cursor = 0; + color++; + if (color == ARRAY_SIZE(colors)) { + color = 0; + } + } + k_sleep(DELAY_TIME); - time++; } }