nRF9160 ws2812 GPIO driver - only works when debug optimisations are off

Hi All, 

I have been working on getting the ws2812-gpio working on the nRF9160 as I want to use the periphs for real stuff, rather than an entire SPI used for an LED. 

It's almost working, but it only works with following line in prj.conf

#turn off compiler optimisations so we can debug it
CONFIG_NO_OPTIMIZATIONS=y
I assume that the following lines are optimised out for some reason.
/* 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 (false)

/* 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 (false)

Here's what I did to get it going - hopefully someone else can clean it up and get it into Zephyr!

The White LED, is still a bit green so the timing might be slightly off, but I haven't got a scope at home to fine tune it. 

Kconfig.ws2812

config WS2812_STRIP_GPIO
	bool "GPIO driver"
	# Only an Cortex-M0 inline assembly implementation for the nRF51
	# is supported currently.
	#MKB Added || SOC_SERIES_NRF91X as this part also has a 16MHz periph clock so it might work
	#lets find out! 
	depends on SOC_SERIES_NRF51X || SOC_SERIES_NRF91X
	help
	  The GPIO driver does bit-banging with inline assembly,
	  and is not available on all SoCs.

	  Note that this driver is not compatible with the Everlight B1414
	  controller.

endchoice

overlay

#include <zephyr/dt-bindings/gpio/gpio.h>
#include <zephyr/dt-bindings/led/led.h>

/ {
	led_strip: ws2812 {
		compatible = "worldsemi,ws2812-gpio";

		chain-length = <1>; /* arbitrary; change at will */
		color-mapping = <LED_COLOR_ID_GREEN
				 LED_COLOR_ID_RED
				 LED_COLOR_ID_BLUE>;
		/* P0: */
		in-gpios = <&gpio0 3 0>;
	};

	aliases {
		led-strip = &led_strip;
	};
};

ws2810_gpio.c

/*
 * Copyright (c) 2018 Intel Corporation
 * Copyright (c) 2019 Nordic Semiconductor ASA
 * Copyright (c) 2021 Seagate Technology LLC
 *
 * SPDX-License-Identifier: Apache-2.0
 */

#define DT_DRV_COMPAT worldsemi_ws2812_gpio

#include <zephyr/drivers/led_strip.h>

#include <string.h>

#define LOG_LEVEL CONFIG_LED_STRIP_LOG_LEVEL
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(ws2812_gpio);

#include <zephyr/zephyr.h>
#include <soc.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/device.h>
#include <zephyr/drivers/clock_control.h>
#include <zephyr/drivers/clock_control/nrf_clock_control.h>
#include <zephyr/dt-bindings/led/led.h>


struct ws2812_gpio_cfg {
	struct gpio_dt_spec in_gpio;
	uint8_t num_colors;
	const uint8_t *color_mapping;
};

/*
 * 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 MHZ_64
#ifdef CONFIG_SOC_SERIES_NRF91X


	#ifdef MHZ_64
	#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_T0H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_TxL "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#endif

	#ifdef MHZ_32
	#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_T0H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_TxL "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#endif

	#ifdef MHZ_28
	#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_T0H "nop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_TxL "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#endif


	#ifdef MHZ_24
	#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_T0H "nop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_TxL "nop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\nnop\n"
	#endif


	#ifdef MHZ_16
	#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"
	#endif

	#ifdef MHZ_8
	#define DELAY_T1H "nop\nnop\nnop\nnop\nnop\nnop\n"
	#define DELAY_T0H "nop\nnop\n"
	#define DELAY_TxL "nop\nnop\nnop\nnop\n"
	#endif

	#ifdef MHZ_4
	#define DELAY_T1H "nop\nnop\nnop\n"
	#define DELAY_T0H "nop\n"
	#define DELAY_TxL "nop\nnop\n"
	#endif


#else
#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"
#endif
/*
 * 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_config, 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 (false)

/* 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 (false)



#ifdef CONFIG_SOC_SERIES_NRF91X
static int send_buf(const struct device *dev, uint8_t *buf, size_t len)
{
	const struct ws2812_gpio_cfg *config = dev->config;

	volatile uint32_t *base = (uint32_t *)&NRF_P0->OUTSET;
	
	const uint32_t val = BIT(config->in_gpio.pin);
	
	//do we really need to turn on  / have access to the perhip clock when the nops are running at sysclk anyway 
	//and we never use the clock for anything,
	//#define CLOCK_REQUIRED
	unsigned int key;
	#ifdef CLOCK_REQUIRED
	struct onoff_manager *mgr =
		z_nrf_clock_control_get_onoff(CLOCK_CONTROL_NRF_SUBSYS_HF);
	struct onoff_client cli;
	
	int rc;

	sys_notify_init_spinwait(&cli.notify);
	rc = onoff_request(mgr, &cli);
	if (rc < 0) {
		return rc;
	}

	while (sys_notify_fetch_result(&cli.notify, &rc)) {
		/* pend until clock is up and running */
	}
	#endif
	key = irq_lock();
	
	while (len--) {
		uint32_t b = *buf++;
		int32_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);
	#ifdef CLOCK_REQUIRED
	rc = onoff_release(mgr);
	/* Returns non-negative value on success. Cap to 0 as API states. */
	rc = MIN(rc, 0);
	return rc;
#else
	return 0;
#endif 
	
}



#else



static int send_buf(const struct device *dev, uint8_t *buf, size_t len)
{
	const struct ws2812_gpio_cfg *config = dev->config;

	//MKB replaced the commented line below with the #ifdef statement 
	//to support the NRF9160 as well as the default.
	//volatile uint32_t *base = (uint32_t *)&NRF_GPIO->OUTSET;
	#ifdef CONFIG_SOC_SERIES_NRF91X
		volatile uint32_t *base = (uint32_t *)&NRF_P0->OUTSET;
	#else
		//NRF_GPIO has actually been renamed to NRF_P0 in any case
		volatile uint32_t *base = (uint32_t *)&NRF_GPIO->OUTSET;
	#endif		
	const uint32_t val = BIT(config->in_gpio.pin);
	struct onoff_manager *mgr =
		z_nrf_clock_control_get_onoff(CLOCK_CONTROL_NRF_SUBSYS_HF);
	struct onoff_client cli;
	unsigned int key;
	int rc;

	sys_notify_init_spinwait(&cli.notify);
	rc = onoff_request(mgr, &cli);
	if (rc < 0) {
		return rc;
	}

	while (sys_notify_fetch_result(&cli.notify, &rc)) {
		/* pend until clock is up and running */
	}

	key = irq_lock();

	while (len--) {
		uint32_t b = *buf++;
		int32_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 = onoff_release(mgr);
	/* Returns non-negative value on success. Cap to 0 as API states. */
	rc = MIN(rc, 0);

	return rc;
}

#endif

static int ws2812_gpio_update_rgb(const struct device *dev,
				  struct led_rgb *pixels,
				  size_t num_pixels)
{
	const struct ws2812_gpio_cfg *config = dev->config;
	uint8_t *ptr = (uint8_t *)pixels;
	size_t i;

	/* Convert from RGB to on-wire format (e.g. GRB, GRBW, RGB, etc) */
	for (i = 0; i < num_pixels; i++) {
		uint8_t j;

		for (j = 0; j < config->num_colors; j++) {
			switch (config->color_mapping[j]) {
			/* White channel is not supported by LED strip API. */
			case LED_COLOR_ID_WHITE:
				*ptr++ = 0;
				break;
			case LED_COLOR_ID_RED:
				*ptr++ = pixels[i].r;
				break;
			case LED_COLOR_ID_GREEN:
				*ptr++ = pixels[i].g;
				break;
			case LED_COLOR_ID_BLUE:
				*ptr++ = pixels[i].b;
				break;
			default:
				return -EINVAL;
			}
		}
	}

	return send_buf(dev, (uint8_t *)pixels, num_pixels * config->num_colors);
}

static int ws2812_gpio_update_channels(const struct device *dev,
				       uint8_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,
};

/*
 * Retrieve the channel to color mapping (e.g. RGB, BGR, GRB, ...) from the
 * "color-mapping" DT property.
 */
#define WS2812_COLOR_MAPPING(idx)					\
static const uint8_t ws2812_gpio_##idx##_color_mapping[] =		\
	DT_INST_PROP(idx, color_mapping)

#define WS2812_NUM_COLORS(idx) (DT_INST_PROP_LEN(idx, color_mapping))

/*
 * 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_DEVICE(idx)					\
									\
	static int ws2812_gpio_##idx##_init(const struct device *dev)	\
	{								\
		const struct ws2812_gpio_cfg *cfg = dev->config;	\
		uint8_t i;						\
									\
		if (!device_is_ready(cfg->in_gpio.port)) {		\
			LOG_ERR("GPIO device not ready");		\
			return -ENODEV;					\
		}							\
									\
		for (i = 0; i < cfg->num_colors; i++) {			\
			switch (cfg->color_mapping[i]) {		\
			case LED_COLOR_ID_WHITE:			\
			case LED_COLOR_ID_RED:				\
			case LED_COLOR_ID_GREEN:			\
			case LED_COLOR_ID_BLUE:				\
				break;					\
			default:					\
				LOG_ERR("%s: invalid channel to color mapping." \
					" Check the color-mapping DT property",	\
					dev->name);			\
				return -EINVAL;				\
			}						\
		}							\
									\
		return gpio_pin_configure_dt(&cfg->in_gpio, GPIO_OUTPUT); \
	}								\
									\
	WS2812_COLOR_MAPPING(idx);					\
									\
	static const struct ws2812_gpio_cfg ws2812_gpio_##idx##_cfg = { \
		.in_gpio = GPIO_DT_SPEC_INST_GET(idx, in_gpios),	\
		.num_colors = WS2812_NUM_COLORS(idx),			\
		.color_mapping = ws2812_gpio_##idx##_color_mapping,	\
	};								\
									\
	DEVICE_DT_INST_DEFINE(idx,					\
			    ws2812_gpio_##idx##_init,			\
			    NULL,					\
			    NULL,					\
			    &ws2812_gpio_##idx##_cfg, POST_KERNEL,	\
			    CONFIG_LED_STRIP_INIT_PRIORITY,		\
			    &ws2812_gpio_api);

DT_INST_FOREACH_STATUS_OKAY(WS2812_GPIO_DEVICE)

main.c

/*
 * Copyright (c) 2017 Linaro Limited
 * Copyright (c) 2018 Intel Corporation
 *
 * SPDX-License-Identifier: Apache-2.0
 */

#include <errno.h>
#include <string.h>

#define LOG_LEVEL 4
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(main);

#include <zephyr/zephyr.h>
#include <zephyr/drivers/led_strip.h>
#include <zephyr/device.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/sys/util.h>

#define STRIP_NODE		DT_ALIAS(led_strip)
#define STRIP_NUM_PIXELS	DT_PROP(DT_ALIAS(led_strip), chain_length)

#define DELAY_TIME K_MSEC(1000)

#define RGB(_r, _g, _b) { .r = (_r), .g = (_g), .b = (_b) }

static const struct led_rgb colors[] = {
	RGB(0xff, 0x00, 0x00), /* red */
	RGB(0x00, 0xff, 0x00), /* blue */
	RGB(0x00, 0x00, 0xff), /* green */
	RGB(0xff, 0xff, 0xff), /* white */
	RGB(0x00, 0x00, 0x00), /* off */
	
	
};

struct led_rgb pixels[STRIP_NUM_PIXELS];

static const struct device *strip = DEVICE_DT_GET(STRIP_NODE);

void main(void)
{
	size_t cursor = 0, color = 0;
	int rc;

	if (device_is_ready(strip)) {
		LOG_INF("Found LED strip device %s", strip->name);
	} else {
		LOG_ERR("LED strip device %s is not ready", strip->name);
		return;
	}

	LOG_INF("Displaying pattern on strip");
	while (1) {
		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);
		}

		cursor++;
		if (cursor >= STRIP_NUM_PIXELS) {
			cursor = 0;
			LOG_INF("colour = %d", color);
			color++;
			if (color == ARRAY_SIZE(colors)) {
				color = 0;
			}
		}

		k_sleep(DELAY_TIME);
	}
}

Parents Reply Children
  • Here it is using PWM - credit to whoever did it first. I just made it fit with the new NRFX functions
    
    /*
     * Copyright (c) 2020 Seagate Technology LLC
     *
     * SPDX-License-Identifier: Apache-2.0
     */
    
    //https://mcuoneclipse.com/2015/08/05/tutorial-adafruit-ws2812b-neopixels-with-the-freescale-frdm-k64f-board-part-5-dma/
    //https://jimmywongiot.com/2021/06/01/advanced-pulse-width-modulation-pwm-on-nordic-nrf52-series/
    //https://medium.com/home-wireless/using-a-pwm-device-in-zephyr-7100d089f15c
    //https://devzone.nordicsemi.com/f/nordic-q-a/44313/nrf52832-pwm-with-easydma-problem/174145
    
    #include <zephyr/zephyr.h>
    #include <zephyr/logging/log.h>
    #include <nrfx_pwm.h>
    #include <nrfx.h>
    #include "hal/nrf_gpio.h"
    #include "led_effect.h"
    #include "opito_ws2812_pwm.h"
    
    
    //set the following in the prj.conf 
    //CONFIG_PWM=n              //disable zephyr PWM
    //CONFIG_NRFX_PWM0=y        //enable nrf PWM (this doesn't use devicetree or any zephyr stuff)
                                //so you have to set it all up manually.
    #ifdef CONFIG_NRFX_PWM0
    #define NRF_ERROR_BUSY 17
    #define NRF_SUCCESS 0
    LOG_MODULE_REGISTER(opito_ws2812_pwm, CONFIG_LOG_DEFAULT_LEVEL);
    
    
    #define WS2812_PIN  NRF_GPIO_PIN_MAP(0,3)
    
    typedef enum
    {
        RED	    = 0x00FF0000,
        GREEN   = 0x0000FF00,
        BLUE    = 0x000000FF
    }COLOR;
    
    
    #define LED_MATRIX_WIDTH 1
    #define LED_MATRIX_HEIGHT 1
    #define LED_MATRIX_TOTAL_BYTE_WIDTH	LED_MATRIX_WIDTH * LED_MATRIX_HEIGHT * 3
    #define LED_MATRIX_TOTAL_BIT_WIDTH	LED_MATRIX_TOTAL_BYTE_WIDTH * 8
    
    #define WS2812_T1H                  14 | 0x8000
    #define WS2812_T0H                  6 | 0x8000
    
    
    static nrfx_pwm_t led_pwm0 = NRFX_PWM_INSTANCE(0);
    //32 bits (24 for data + (8 for reset?))
    static nrf_pwm_values_individual_t pwm_duty_cycle_values[LED_MATRIX_TOTAL_BIT_WIDTH];
    volatile bool pwm_sequence_finished = true;
    
    
    typedef struct {
        uint8_t r;
        uint8_t g;
        uint8_t b;
        uint8_t place_holder;
    
    }rgb_color_t;
    
    typedef union {
        uint32_t	    u;
        rgb_color_t	    s;
    }color_t;
    
    
    static nrf_pwm_sequence_t pwm_sequence =
    {
        .values.p_individual = pwm_duty_cycle_values,
        .length          = (sizeof(pwm_duty_cycle_values) / sizeof(uint16_t)),
        .repeats         = 0,
        .end_delay       = 0
    };
    
    
    /**
     * @brief Run tests on a single LED using the LED API syscalls.
     *
     * @param led_pwm LED PWM device.
     * @param led Number of the LED to test.
     */
    
    static rgb_color_t led_matrix_buffer[LED_MATRIX_WIDTH][LED_MATRIX_HEIGHT];
    uint32_t drv_ws2812_display(void);
    
    
    
    void pwm_handler(nrfx_pwm_evt_type_t event_type, void *context) {
    	switch(event_type)  {
    	case NRFX_PWM_EVT_FINISHED:
    	    pwm_sequence_finished = true;
    	    break;
    	default:
    	    break;
        }
    }
    
    
    
    int32_t drv_ws2812_pixel_draw(uint16_t x, uint16_t y, uint32_t color){
        uint32_t err_code = NRF_SUCCESS;
        led_matrix_buffer[x][y].r = (color & 0x00FF0000) >> 16;
        led_matrix_buffer[x][y].g = (color & 0x0000FF00) >> 8;
        led_matrix_buffer[x][y].b = (color & 0x000000FF);
        
        return err_code;
    }
    
    
    static void convert_rgb_to_pwm_sequence(void) {
        uint8_t * ptr = (uint8_t *)led_matrix_buffer;
        uint32_t i = 0;
        for(int led = 0; led < LED_MATRIX_TOTAL_BYTE_WIDTH; led++) {
            for(int bit = 7; bit >= 0; bit--) {
                uint8_t b = (*ptr >> bit) & 0x01;
                uint16_t pwm = 0;
                if(b == 1) {
                    pwm = WS2812_T1H;
                }
                else {
                    pwm = WS2812_T0H;
                }
                pwm_duty_cycle_values[i++].channel_1 = pwm;
            }
            ptr++;
        }
    }
    
    
    
    static uint32_t pwm_init(void) {
        IRQ_DIRECT_CONNECT(PWM0_IRQn, 0, nrfx_pwm_0_irq_handler, 0);
    	nrfx_pwm_config_t pwm_config = NRFX_PWM_DEFAULT_CONFIG(0xFF,0xFF,0xFF,0xFF);
        pwm_config.output_pins[0] = NRFX_PWM_PIN_NOT_USED; 
        pwm_config.output_pins[1] = WS2812_PIN; 
        pwm_config.output_pins[2] = NRFX_PWM_PIN_NOT_USED;
        pwm_config.output_pins[3] = NRFX_PWM_PIN_NOT_USED;
        pwm_config.load_mode    = NRF_PWM_LOAD_INDIVIDUAL;
        // WS2812 protocol requires a 800 kHz PWM frequency. PWM Top value = 20 and Base Clock = 16 MHz achieves this
        pwm_config.top_value    = 20; 
        pwm_config.base_clock   = NRF_PWM_CLK_16MHz;
    	return nrfx_pwm_init(&led_pwm0, &pwm_config, pwm_handler, NULL);
    }
    
    uint32_t drv_ws2812_init(void){   
        memset(led_matrix_buffer, 0x00, sizeof(led_matrix_buffer));   
        return pwm_init();
    }
    
    
    uint32_t drv_ws2812_display(void){
    	
        if(!pwm_sequence_finished)  {
            return NRF_ERROR_BUSY;
        }
        convert_rgb_to_pwm_sequence();
        pwm_sequence_finished = false;
        uint32_t err_code = nrfx_pwm_simple_playback(&led_pwm0, &pwm_sequence, 1, NRFX_PWM_FLAG_STOP);
        return err_code;
    }
    
    
    void display_led(uint32_t colour){
    
    			drv_ws2812_pixel_draw(0,0,colour);
    			drv_ws2812_display();
    }
    
    
    void example_main(void) {
    	color_t our_colour; 
    
    	drv_ws2812_init();
    	do {
    			
    			our_colour.s.r = 0x0F;
    			our_colour.s.g = 0x0F;
    			our_colour.s.b = 0x0F;
    			
    			drv_ws2812_pixel_draw(0,0,our_colour.u);
    			
    			drv_ws2812_display();
    			k_sleep(K_MSEC(100));
    	} while (true);
    }
    #endif //#ifdef CONFIG_NRFX_PWM0

Related