ws2811.c
Go to the documentation of this file.
1 /*
2  * ws2811.c
3  *
4  * Copyright (c) 2014 Jeremy Garff <jer @ jers.net>
5  *
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without modification, are permitted
9  * provided that the following conditions are met:
10  *
11  * 1. Redistributions of source code must retain the above copyright notice, this list of
12  * conditions and the following disclaimer.
13  * 2. Redistributions in binary form must reproduce the above copyright notice, this list
14  * of conditions and the following disclaimer in the documentation and/or other materials
15  * provided with the distribution.
16  * 3. Neither the name of the owner nor the names of its contributors may be used to endorse
17  * or promote products derived from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
20  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
21  * FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
24  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
26  * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  *
28  */
29 
30 
31 #include <stdint.h>
32 #include <stdio.h>
33 #include <stdlib.h>
34 #include <string.h>
35 #include <unistd.h>
36 #include <sys/stat.h>
37 #include <fcntl.h>
38 #include <sys/ioctl.h>
39 #include <sys/mman.h>
40 #include <signal.h>
41 #include <linux/types.h>
42 #include <linux/spi/spidev.h>
43 #include <time.h>
44 #include <math.h>
45 #include "mailbox.h"
46 #include "clk.h"
47 #include "gpio.h"
48 #include "dma.h"
49 #include "pwm.h"
50 #include "pcm.h"
51 #include "rpihw.h"
52 
53 #include "ws2811.h"
54 
55 
56 #define BUS_TO_PHYS(x) ((x)&~0xC0000000)
57 
58 #define OSC_FREQ 19200000 // crystal frequency
59 #define OSC_FREQ_PI4 54000000 // Pi 4 crystal frequency
60 
61 /* 4 colors (R, G, B + W), 8 bits per byte, 3 symbols per bit + 55uS low for reset signal */
62 #define LED_COLOURS 4
63 #define LED_RESET_uS 55
64 #define LED_BIT_COUNT(leds, freq) ((leds * LED_COLOURS * 8 * 3) + ((LED_RESET_uS * \
65  (freq * 3)) / 1000000))
66 
67 /* Minimum time to wait for reset to occur in microseconds. */
68 #define LED_RESET_WAIT_TIME 300
69 
70 // Pad out to the nearest uint32 + 32-bits for idle low/high times the number of channels
71 #define PWM_BYTE_COUNT(leds, freq) (((((LED_BIT_COUNT(leds, freq) >> 3) & ~0x7) + 4) + 4) * \
72  RPI_PWM_CHANNELS)
73 #define PCM_BYTE_COUNT(leds, freq) ((((LED_BIT_COUNT(leds, freq) >> 3) & ~0x7) + 4) + 4)
74 
75 // Symbol definitions
76 #define SYMBOL_HIGH 0x6 // 1 1 0
77 #define SYMBOL_LOW 0x4 // 1 0 0
78 
79 // Symbol definitions for software inversion (PCM and SPI only)
80 #define SYMBOL_HIGH_INV 0x1 // 0 0 1
81 #define SYMBOL_LOW_INV 0x3 // 0 1 1
82 
83 // Driver mode definitions
84 #define NONE 0
85 #define PWM 1
86 #define PCM 2
87 #define SPI 3
88 
89 // We use the mailbox interface to request memory from the VideoCore.
90 // This lets us request one physically contiguous chunk, find its
91 // physical address, and map it 'uncached' so that writes from this
92 // code are immediately visible to the DMA controller. This struct
93 // holds data relevant to the mailbox interface.
94 typedef struct videocore_mbox {
95  int handle; /* From mbox_open() */
96  unsigned mem_ref; /* From mem_alloc() */
97  unsigned bus_addr; /* From mem_lock() */
98  unsigned size; /* Size of allocation */
99  uint8_t *virt_addr; /* From mapmem() */
101 
102 typedef struct ws2811_device
103 {
105  volatile uint8_t *pxl_raw;
106  volatile dma_t *dma;
107  volatile pwm_t *pwm;
108  volatile pcm_t *pcm;
109  int spi_fd;
110  volatile dma_cb_t *dma_cb;
111  uint32_t dma_cb_addr;
112  volatile gpio_t *gpio;
113  volatile cm_clk_t *cm_clk;
117 
123 static uint64_t get_microsecond_timestamp()
124 {
125  struct timespec t;
126 
127  if (clock_gettime(CLOCK_MONOTONIC_RAW, &t) != 0) {
128  return 0;
129  }
130 
131  return (uint64_t) t.tv_sec * 1000000 + t.tv_nsec / 1000;
132 }
133 
141 static int max_channel_led_count(ws2811_t *ws2811)
142 {
143  int chan, max = 0;
144 
145  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
146  {
147  if (ws2811->channel[chan].count > max)
148  {
149  max = ws2811->channel[chan].count;
150  }
151  }
152 
153  return max;
154 }
155 
164 static int map_registers(ws2811_t *ws2811)
165 {
166  ws2811_device_t *device = ws2811->device;
167  const rpi_hw_t *rpi_hw = ws2811->rpi_hw;
168  uint32_t base = ws2811->rpi_hw->periph_base;
169  uint32_t dma_addr;
170  uint32_t offset = 0;
171 
172  dma_addr = dmanum_to_offset(ws2811->dmanum);
173  if (!dma_addr)
174  {
175  return -1;
176  }
177  dma_addr += rpi_hw->periph_base;
178 
179  device->dma = mapmem(dma_addr, sizeof(dma_t), DEV_MEM);
180  if (!device->dma)
181  {
182  return -1;
183  }
184 
185  switch (device->driver_mode) {
186  case PWM:
187  device->pwm = mapmem(PWM_OFFSET + base, sizeof(pwm_t), DEV_MEM);
188  if (!device->pwm)
189  {
190  return -1;
191  }
192  break;
193 
194  case PCM:
195  device->pcm = mapmem(PCM_OFFSET + base, sizeof(pcm_t), DEV_MEM);
196  if (!device->pcm)
197  {
198  return -1;
199  }
200  break;
201  }
202 
203  /*
204  * The below call can potentially work with /dev/gpiomem instead.
205  * However, it used /dev/mem before, so I'm leaving it as such.
206  */
207 
208  device->gpio = mapmem(GPIO_OFFSET + base, sizeof(gpio_t), DEV_MEM);
209  if (!device->gpio)
210  {
211  return -1;
212  }
213 
214  switch (device->driver_mode) {
215  case PWM:
216  offset = CM_PWM_OFFSET;
217  break;
218  case PCM:
219  offset = CM_PCM_OFFSET;
220  break;
221  }
222  device->cm_clk = mapmem(offset + base, sizeof(cm_clk_t), DEV_MEM);
223  if (!device->cm_clk)
224  {
225  return -1;
226  }
227 
228  return 0;
229 }
230 
238 static void unmap_registers(ws2811_t *ws2811)
239 {
240  ws2811_device_t *device = ws2811->device;
241 
242  if (device->dma)
243  {
244  unmapmem((void *)device->dma, sizeof(dma_t));
245  }
246 
247  if (device->pwm)
248  {
249  unmapmem((void *)device->pwm, sizeof(pwm_t));
250  }
251 
252  if (device->pcm)
253  {
254  unmapmem((void *)device->pcm, sizeof(pcm_t));
255  }
256 
257  if (device->cm_clk)
258  {
259  unmapmem((void *)device->cm_clk, sizeof(cm_clk_t));
260  }
261 
262  if (device->gpio)
263  {
264  unmapmem((void *)device->gpio, sizeof(gpio_t));
265  }
266 }
267 
276 static uint32_t addr_to_bus(ws2811_device_t *device, const volatile void *virt)
277 {
278  videocore_mbox_t *mbox = &device->mbox;
279 
280  uint32_t offset = (uint8_t *)virt - mbox->virt_addr;
281 
282  return mbox->bus_addr + offset;
283 }
284 
292 static void stop_pwm(ws2811_t *ws2811)
293 {
294  ws2811_device_t *device = ws2811->device;
295  volatile pwm_t *pwm = device->pwm;
296  volatile cm_clk_t *cm_clk = device->cm_clk;
297 
298  // Turn off the PWM in case already running
299  pwm->ctl = 0;
300  usleep(10);
301 
302  // Kill the clock if it was already running
303  cm_clk->ctl = CM_CLK_CTL_PASSWD | CM_CLK_CTL_KILL;
304  usleep(10);
305  while (cm_clk->ctl & CM_CLK_CTL_BUSY)
306  ;
307 }
308 
316 static void stop_pcm(ws2811_t *ws2811)
317 {
318  ws2811_device_t *device = ws2811->device;
319  volatile pcm_t *pcm = device->pcm;
320  volatile cm_clk_t *cm_clk = device->cm_clk;
321 
322  // Turn off the PCM in case already running
323  pcm->cs = 0;
324  usleep(10);
325 
326  // Kill the clock if it was already running
327  cm_clk->ctl = CM_CLK_CTL_PASSWD | CM_CLK_CTL_KILL;
328  usleep(10);
329  while (cm_clk->ctl & CM_CLK_CTL_BUSY)
330  ;
331 }
332 
340 static int setup_pwm(ws2811_t *ws2811)
341 {
342  ws2811_device_t *device = ws2811->device;
343  volatile dma_t *dma = device->dma;
344  volatile dma_cb_t *dma_cb = device->dma_cb;
345  volatile pwm_t *pwm = device->pwm;
346  volatile cm_clk_t *cm_clk = device->cm_clk;
347  int maxcount = device->max_count;
348  uint32_t freq = ws2811->freq;
349  int32_t byte_count;
350 
351  const rpi_hw_t *rpi_hw = ws2811->rpi_hw;
352  const uint32_t rpi_type = rpi_hw->type;
353  uint32_t osc_freq = OSC_FREQ;
354 
355  if(rpi_type == RPI_HWVER_TYPE_PI4){
356  osc_freq = OSC_FREQ_PI4;
357  }
358 
359  stop_pwm(ws2811);
360 
361  // Setup the Clock - Use OSC @ 19.2Mhz w/ 3 clocks/tick
362  cm_clk->div = CM_CLK_DIV_PASSWD | CM_CLK_DIV_DIVI(osc_freq / (3 * freq));
363  cm_clk->ctl = CM_CLK_CTL_PASSWD | CM_CLK_CTL_SRC_OSC;
365  usleep(10);
366  while (!(cm_clk->ctl & CM_CLK_CTL_BUSY))
367  ;
368 
369  // Setup the PWM, use delays as the block is rumored to lock up without them. Make
370  // sure to use a high enough priority to avoid any FIFO underruns, especially if
371  // the CPU is busy doing lots of memory accesses, or another DMA controller is
372  // busy. The FIFO will clock out data at a much slower rate (2.6Mhz max), so
373  // the odds of a DMA priority boost are extremely low.
374 
375  pwm->rng1 = 32; // 32-bits per word to serialize
376  usleep(10);
377  pwm->ctl = RPI_PWM_CTL_CLRF1;
378  usleep(10);
380  usleep(10);
381  pwm->ctl = RPI_PWM_CTL_USEF1 | RPI_PWM_CTL_MODE1 |
383  if (ws2811->channel[0].invert)
384  {
385  pwm->ctl |= RPI_PWM_CTL_POLA1;
386  }
387  if (ws2811->channel[1].invert)
388  {
389  pwm->ctl |= RPI_PWM_CTL_POLA2;
390  }
391  usleep(10);
392  pwm->ctl |= RPI_PWM_CTL_PWEN1 | RPI_PWM_CTL_PWEN2;
393 
394  // Initialize the DMA control block
395  byte_count = PWM_BYTE_COUNT(maxcount, freq);
396  dma_cb->ti = RPI_DMA_TI_NO_WIDE_BURSTS | // 32-bit transfers
397  RPI_DMA_TI_WAIT_RESP | // wait for write complete
398  RPI_DMA_TI_DEST_DREQ | // user peripheral flow control
399  RPI_DMA_TI_PERMAP(5) | // PWM peripheral
400  RPI_DMA_TI_SRC_INC; // Increment src addr
401 
402  dma_cb->source_ad = addr_to_bus(device, device->pxl_raw);
403 
404  dma_cb->dest_ad = (uintptr_t)&((pwm_t *)PWM_PERIPH_PHYS)->fif1;
405  dma_cb->txfr_len = byte_count;
406  dma_cb->stride = 0;
407  dma_cb->nextconbk = 0;
408 
409  dma->cs = 0;
410  dma->txfr_len = 0;
411 
412  return 0;
413 }
414 
422 static int setup_pcm(ws2811_t *ws2811)
423 {
424  ws2811_device_t *device = ws2811->device;
425  volatile dma_t *dma = device->dma;
426  volatile dma_cb_t *dma_cb = device->dma_cb;
427  volatile pcm_t *pcm = device->pcm;
428  volatile cm_clk_t *cm_clk = device->cm_clk;
429  //int maxcount = max_channel_led_count(ws2811);
430  int maxcount = device->max_count;
431  uint32_t freq = ws2811->freq;
432  int32_t byte_count;
433 
434  const rpi_hw_t *rpi_hw = ws2811->rpi_hw;
435  const uint32_t rpi_type = rpi_hw->type;
436  uint32_t osc_freq = OSC_FREQ;
437 
438  if(rpi_type == RPI_HWVER_TYPE_PI4){
439  osc_freq = OSC_FREQ_PI4;
440  }
441 
442  stop_pcm(ws2811);
443 
444  // Setup the PCM Clock - Use OSC @ 19.2Mhz w/ 3 clocks/tick
445  cm_clk->div = CM_CLK_DIV_PASSWD | CM_CLK_DIV_DIVI(osc_freq / (3 * freq));
446  cm_clk->ctl = CM_CLK_CTL_PASSWD | CM_CLK_CTL_SRC_OSC;
448  usleep(10);
449  while (!(cm_clk->ctl & CM_CLK_CTL_BUSY))
450  ;
451 
452  // Setup the PCM, use delays as the block is rumored to lock up without them. Make
453  // sure to use a high enough priority to avoid any FIFO underruns, especially if
454  // the CPU is busy doing lots of memory accesses, or another DMA controller is
455  // busy. The FIFO will clock out data at a much slower rate (2.6Mhz max), so
456  // the odds of a DMA priority boost are extremely low.
457 
458  pcm->cs = RPI_PCM_CS_EN; // Enable PCM hardware
459  pcm->mode = (RPI_PCM_MODE_FLEN(31) | RPI_PCM_MODE_FSLEN(1));
460  // Framelength 32, clock enabled, frame sync pulse
462  // Single 32-bit channel
463  pcm->cs |= RPI_PCM_CS_TXCLR; // Reset transmit fifo
464  usleep(10);
465  pcm->cs |= RPI_PCM_CS_DMAEN; // Enable DMA DREQ
466  pcm->dreq = (RPI_PCM_DREQ_TX(0x3F) | RPI_PCM_DREQ_TX_PANIC(0x10)); // Set FIFO tresholds
467 
468  // Initialize the DMA control block
469  byte_count = PCM_BYTE_COUNT(maxcount, freq);
470  dma_cb->ti = RPI_DMA_TI_NO_WIDE_BURSTS | // 32-bit transfers
471  RPI_DMA_TI_WAIT_RESP | // wait for write complete
472  RPI_DMA_TI_DEST_DREQ | // user peripheral flow control
473  RPI_DMA_TI_PERMAP(2) | // PCM TX peripheral
474  RPI_DMA_TI_SRC_INC; // Increment src addr
475 
476  dma_cb->source_ad = addr_to_bus(device, device->pxl_raw);
477  dma_cb->dest_ad = (uintptr_t)&((pcm_t *)PCM_PERIPH_PHYS)->fifo;
478  dma_cb->txfr_len = byte_count;
479  dma_cb->stride = 0;
480  dma_cb->nextconbk = 0;
481 
482  dma->cs = 0;
483  dma->txfr_len = 0;
484 
485  return 0;
486 }
487 
496 static void dma_start(ws2811_t *ws2811)
497 {
498  ws2811_device_t *device = ws2811->device;
499  volatile dma_t *dma = device->dma;
500  volatile pcm_t *pcm = device->pcm;
501  uint32_t dma_cb_addr = device->dma_cb_addr;
502 
503  dma->cs = RPI_DMA_CS_RESET;
504  usleep(10);
505 
506  dma->cs = RPI_DMA_CS_INT | RPI_DMA_CS_END;
507  usleep(10);
508 
509  dma->conblk_ad = dma_cb_addr;
510  dma->debug = 7; // clear debug error flags
513  RPI_DMA_CS_PRIORITY(15) |
515 
516  if (device->driver_mode == PCM)
517  {
518  pcm->cs |= RPI_PCM_CS_TXON; // Start transmission
519  }
520 }
521 
529 static int gpio_init(ws2811_t *ws2811)
530 {
531  volatile gpio_t *gpio = ws2811->device->gpio;
532  int chan;
533  int altnum;
534 
535  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
536  {
537  int pinnum = ws2811->channel[chan].gpionum;
538 
539  if (pinnum)
540  {
541  switch (ws2811->device->driver_mode)
542  {
543  case PWM:
544  altnum = pwm_pin_alt(chan, pinnum);
545  break;
546  case PCM:
547  altnum = pcm_pin_alt(PCMFUN_DOUT, pinnum);
548  break;
549  default:
550  altnum = -1;
551  }
552 
553  if (altnum < 0)
554  {
555  return -1;
556  }
557 
558  gpio_function_set(gpio, pinnum, altnum);
559  }
560  }
561 
562  return 0;
563 }
564 
574 void pwm_raw_init(ws2811_t *ws2811)
575 {
576  volatile uint32_t *pxl_raw = (uint32_t *)ws2811->device->pxl_raw;
577  int maxcount = ws2811->device->max_count;
578  int wordcount = (PWM_BYTE_COUNT(maxcount, ws2811->freq) / sizeof(uint32_t)) /
580  int chan;
581 
582  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
583  {
584  int i, wordpos = chan;
585 
586  for (i = 0; i < wordcount; i++)
587  {
588  pxl_raw[wordpos] = 0x0;
589  wordpos += 2;
590  }
591  }
592 }
593 
602 void pcm_raw_init(ws2811_t *ws2811)
603 {
604  volatile uint32_t *pxl_raw = (uint32_t *)ws2811->device->pxl_raw;
605  int maxcount = ws2811->device->max_count;
606  int wordcount = PCM_BYTE_COUNT(maxcount, ws2811->freq) / sizeof(uint32_t);
607  int i;
608 
609  for (i = 0; i < wordcount; i++)
610  {
611  pxl_raw[i] = 0x0;
612  }
613 }
614 
623 {
624  ws2811_device_t *device = ws2811->device;
625  int chan;
626 
627  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
628  {
629  if (ws2811->channel[chan].leds)
630  {
631  free(ws2811->channel[chan].leds);
632  }
633  ws2811->channel[chan].leds = NULL;
634  if (ws2811->channel[chan].gamma)
635  {
636  free(ws2811->channel[chan].gamma);
637  }
638  ws2811->channel[chan].gamma = NULL;
639  }
640 
641  if (device->mbox.handle != -1)
642  {
643  videocore_mbox_t *mbox = &device->mbox;
644 
645  unmapmem(mbox->virt_addr, mbox->size);
646  mem_unlock(mbox->handle, mbox->mem_ref);
647  mem_free(mbox->handle, mbox->mem_ref);
648  mbox_close(mbox->handle);
649 
650  mbox->handle = -1;
651  }
652 
653  if (device && (device->spi_fd > 0))
654  {
655  close(device->spi_fd);
656  }
657 
658  if (device) {
659  free(device);
660  }
661  ws2811->device = NULL;
662 }
663 
664 static int set_driver_mode(ws2811_t *ws2811, int gpionum)
665 {
666  int gpionum2;
667 
668  if (gpionum == 18 || gpionum == 12) {
669  ws2811->device->driver_mode = PWM;
670  // Check gpio for PWM1 (2nd channel) is OK if used
671  gpionum2 = ws2811->channel[1].gpionum;
672  if (gpionum2 == 0 || gpionum2 == 13 || gpionum2 == 19) {
673  return 0;
674  }
675  }
676  else if (gpionum == 21 || gpionum == 31) {
677  ws2811->device->driver_mode = PCM;
678  }
679  else if (gpionum == 10) {
680  ws2811->device->driver_mode = SPI;
681  }
682  else {
683  fprintf(stderr, "gpionum %d not allowed\n", gpionum);
684  return -1;
685  }
686  // For PCM and SPI zero the 2nd channel
687  memset(&ws2811->channel[1], 0, sizeof(ws2811_channel_t));
688 
689  return 0;
690 }
691 
693 {
694  const rpi_hw_t *rpi_hw;
695  int hwver, gpionum;
696  int gpionums_B1[] = { 10, 18, 21 };
697  int gpionums_B2[] = { 10, 18, 31 };
698  int gpionums_40p[] = { 10, 12, 18, 21};
699  int i;
700 
701  rpi_hw = ws2811->rpi_hw;
702  hwver = rpi_hw->hwver & 0x0000ffff;
703  gpionum = ws2811->channel[0].gpionum;
704  if (hwver < 0x0004) // Model B Rev 1
705  {
706  for ( i = 0; i < (int)(sizeof(gpionums_B1) / sizeof(gpionums_B1[0])); i++)
707  {
708  if (gpionums_B1[i] == gpionum) {
709  // Set driver mode (PWM, PCM, or SPI)
710  return set_driver_mode(ws2811, gpionum);
711  }
712  }
713  }
714  else if (hwver >= 0x0004 && hwver <= 0x000f) // Models B Rev2, A
715  {
716  for ( i = 0; i < (int)(sizeof(gpionums_B2) / sizeof(gpionums_B2[0])); i++)
717  {
718  if (gpionums_B2[i] == gpionum) {
719  // Set driver mode (PWM, PCM, or SPI)
720  return set_driver_mode(ws2811, gpionum);
721  }
722  }
723  }
724  else if (hwver >= 0x010) // Models B+, A+, 2B, 3B, Zero Zero-W
725  {
726  if ((ws2811->channel[0].count == 0) && (ws2811->channel[1].count > 0))
727  {
728  // Special case: nothing in channel 0, channel 1 only PWM1 allowed
729  // PWM1 only available on 40 pin GPIO interface
730  gpionum = ws2811->channel[1].gpionum;
731  if ((gpionum == 13) || (gpionum == 19))
732  {
733  ws2811->device->driver_mode = PWM;
734  return 0;
735  }
736  else {
737  return -1;
738  }
739  }
740  for ( i = 0; i < (int)(sizeof(gpionums_40p) / sizeof(gpionums_40p[0])); i++)
741  {
742  if (gpionums_40p[i] == gpionum) {
743  // Set driver mode (PWM, PCM, or SPI)
744  return set_driver_mode(ws2811, gpionum);
745  }
746  }
747  }
748  fprintf(stderr, "Gpio %d is illegal for LED channel 0\n", gpionum);
749  return -1;
750 }
751 
753 {
754  int spi_fd;
755  static uint8_t mode;
756  static uint8_t bits = 8;
757  uint32_t speed = ws2811->freq * 3;
758  ws2811_device_t *device = ws2811->device;
759  uint32_t base = ws2811->rpi_hw->periph_base;
760  int pinnum = ws2811->channel[0].gpionum;
761 
762  spi_fd = open("/dev/spidev0.0", O_RDWR);
763  if (spi_fd < 0) {
764  fprintf(stderr, "Cannot open /dev/spidev0.0. spi_bcm2835 module not loaded?\n");
765  return WS2811_ERROR_SPI_SETUP;
766  }
767  device->spi_fd = spi_fd;
768 
769  // SPI mode
770  if (ioctl(spi_fd, SPI_IOC_WR_MODE, &mode) < 0)
771  {
772  return WS2811_ERROR_SPI_SETUP;
773  }
774  if (ioctl(spi_fd, SPI_IOC_RD_MODE, &mode) < 0)
775  {
776  return WS2811_ERROR_SPI_SETUP;
777  }
778 
779  // Bits per word
780  if (ioctl(spi_fd, SPI_IOC_WR_BITS_PER_WORD, &bits) < 0)
781  {
782  return WS2811_ERROR_SPI_SETUP;
783  }
784  if (ioctl(spi_fd, SPI_IOC_RD_BITS_PER_WORD, &bits) < 0)
785  {
786  return WS2811_ERROR_SPI_SETUP;
787  }
788 
789  // Max speed Hz
790  if (ioctl(spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &speed) < 0)
791  {
792  return WS2811_ERROR_SPI_SETUP;
793  }
794  if (ioctl(spi_fd, SPI_IOC_RD_MAX_SPEED_HZ, &speed) < 0)
795  {
796  return WS2811_ERROR_SPI_SETUP;
797  }
798 
799  // Initialize device structure elements to not used
800  // except driver_mode, spi_fd and max_count (already defined when spi_init called)
801  device->pxl_raw = NULL;
802  device->dma = NULL;
803  device->pwm = NULL;
804  device->pcm = NULL;
805  device->dma_cb = NULL;
806  device->dma_cb_addr = 0;
807  device->cm_clk = NULL;
808  device->mbox.handle = -1;
809 
810  // Set SPI-MOSI pin
811  device->gpio = mapmem(GPIO_OFFSET + base, sizeof(gpio_t), DEV_GPIOMEM);
812  if (!device->gpio)
813  {
814  return WS2811_ERROR_SPI_SETUP;
815  }
816  gpio_function_set(device->gpio, pinnum, 0); // SPI-MOSI ALT0
817 
818  // Allocate LED buffer
819  ws2811_channel_t *channel = &ws2811->channel[0];
820  channel->leds = malloc(sizeof(ws2811_led_t) * channel->count);
821  if (!channel->leds)
822  {
823  ws2811_cleanup(ws2811);
824  return WS2811_ERROR_OUT_OF_MEMORY;
825  }
826  memset(channel->leds, 0, sizeof(ws2811_led_t) * channel->count);
827  if (!channel->strip_type)
828  {
829  channel->strip_type=WS2811_STRIP_RGB;
830  }
831 
832  // Set default uncorrected gamma table
833  if (!channel->gamma)
834  {
835  channel->gamma = malloc(sizeof(uint8_t) * 256);
836  int x;
837  for(x = 0; x < 256; x++){
838  channel->gamma[x] = x;
839  }
840  }
841 
842  channel->wshift = (channel->strip_type >> 24) & 0xff;
843  channel->rshift = (channel->strip_type >> 16) & 0xff;
844  channel->gshift = (channel->strip_type >> 8) & 0xff;
845  channel->bshift = (channel->strip_type >> 0) & 0xff;
846 
847  // Allocate SPI transmit buffer (same size as PCM)
848  device->pxl_raw = malloc(PCM_BYTE_COUNT(device->max_count, ws2811->freq));
849  if (device->pxl_raw == NULL)
850  {
851  ws2811_cleanup(ws2811);
852  return WS2811_ERROR_OUT_OF_MEMORY;
853  }
854  pcm_raw_init(ws2811);
855 
856  return WS2811_SUCCESS;
857 }
858 
860 {
861  int ret;
862  struct spi_ioc_transfer tr;
863 
864  memset(&tr, 0, sizeof(struct spi_ioc_transfer));
865  tr.tx_buf = (unsigned long)ws2811->device->pxl_raw;
866  tr.rx_buf = 0;
867  tr.len = PCM_BYTE_COUNT(ws2811->device->max_count, ws2811->freq);
868 
869  ret = ioctl(ws2811->device->spi_fd, SPI_IOC_MESSAGE(1), &tr);
870  if (ret < 1)
871  {
872  fprintf(stderr, "Can't send spi message");
873  return WS2811_ERROR_SPI_TRANSFER;
874  }
875 
876  return WS2811_SUCCESS;
877 }
878 
879 
880 /*
881  *
882  * Application API Functions
883  *
884  */
885 
886 
895 {
896  ws2811_device_t *device;
897  const rpi_hw_t *rpi_hw;
898  int chan;
899 
900  ws2811->rpi_hw = rpi_hw_detect();
901  if (!ws2811->rpi_hw)
902  {
903  return WS2811_ERROR_HW_NOT_SUPPORTED;
904  }
905  rpi_hw = ws2811->rpi_hw;
906 
907  ws2811->device = malloc(sizeof(*ws2811->device));
908  if (!ws2811->device)
909  {
910  return WS2811_ERROR_OUT_OF_MEMORY;
911  }
912  memset(ws2811->device, 0, sizeof(*ws2811->device));
913  device = ws2811->device;
914 
915  if (check_hwver_and_gpionum(ws2811) < 0)
916  {
917  return WS2811_ERROR_ILLEGAL_GPIO;
918  }
919 
920  device->max_count = max_channel_led_count(ws2811);
921 
922  if (device->driver_mode == SPI) {
923  return spi_init(ws2811);
924  }
925 
926  // Determine how much physical memory we need for DMA
927  switch (device->driver_mode) {
928  case PWM:
929  device->mbox.size = PWM_BYTE_COUNT(device->max_count, ws2811->freq) +
930  sizeof(dma_cb_t);
931  break;
932 
933  case PCM:
934  device->mbox.size = PCM_BYTE_COUNT(device->max_count, ws2811->freq) +
935  sizeof(dma_cb_t);
936  break;
937  }
938  // Round up to page size multiple
939  device->mbox.size = (device->mbox.size + (PAGE_SIZE - 1)) & ~(PAGE_SIZE - 1);
940 
941  device->mbox.handle = mbox_open();
942  if (device->mbox.handle == -1)
943  {
944  return WS2811_ERROR_MAILBOX_DEVICE;
945  }
946 
947  device->mbox.mem_ref = mem_alloc(device->mbox.handle, device->mbox.size, PAGE_SIZE,
948  rpi_hw->videocore_base == 0x40000000 ? 0xC : 0x4);
949  if (device->mbox.mem_ref == 0)
950  {
951  return WS2811_ERROR_OUT_OF_MEMORY;
952  }
953 
954  device->mbox.bus_addr = mem_lock(device->mbox.handle, device->mbox.mem_ref);
955  if (device->mbox.bus_addr == (uint32_t) ~0UL)
956  {
957  mem_free(device->mbox.handle, device->mbox.size);
958  return WS2811_ERROR_MEM_LOCK;
959  }
960 
961  device->mbox.virt_addr = mapmem(BUS_TO_PHYS(device->mbox.bus_addr), device->mbox.size, DEV_MEM);
962  if (!device->mbox.virt_addr)
963  {
964  mem_unlock(device->mbox.handle, device->mbox.mem_ref);
965  mem_free(device->mbox.handle, device->mbox.size);
966 
967  ws2811_cleanup(ws2811);
968  return WS2811_ERROR_MMAP;
969  }
970 
971  // Initialize all pointers to NULL. Any non-NULL pointers will be freed on cleanup.
972  device->pxl_raw = NULL;
973  device->dma_cb = NULL;
974  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
975  {
976  ws2811->channel[chan].leds = NULL;
977  }
978 
979  // Allocate the LED buffers
980  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
981  {
982  ws2811_channel_t *channel = &ws2811->channel[chan];
983 
984  channel->leds = malloc(sizeof(ws2811_led_t) * channel->count);
985  if (!channel->leds)
986  {
987  ws2811_cleanup(ws2811);
988  return WS2811_ERROR_OUT_OF_MEMORY;
989  }
990 
991  memset(channel->leds, 0, sizeof(ws2811_led_t) * channel->count);
992 
993  if (!channel->strip_type)
994  {
995  channel->strip_type=WS2811_STRIP_RGB;
996  }
997 
998  // Set default uncorrected gamma table
999  if (!channel->gamma)
1000  {
1001  channel->gamma = malloc(sizeof(uint8_t) * 256);
1002  int x;
1003  for(x = 0; x < 256; x++){
1004  channel->gamma[x] = x;
1005  }
1006  }
1007 
1008  channel->wshift = (channel->strip_type >> 24) & 0xff;
1009  channel->rshift = (channel->strip_type >> 16) & 0xff;
1010  channel->gshift = (channel->strip_type >> 8) & 0xff;
1011  channel->bshift = (channel->strip_type >> 0) & 0xff;
1012 
1013  }
1014 
1015  device->dma_cb = (dma_cb_t *)device->mbox.virt_addr;
1016  device->pxl_raw = (uint8_t *)device->mbox.virt_addr + sizeof(dma_cb_t);
1017 
1018  switch (device->driver_mode) {
1019  case PWM:
1020  pwm_raw_init(ws2811);
1021  break;
1022 
1023  case PCM:
1024  pcm_raw_init(ws2811);
1025  break;
1026  }
1027 
1028  memset((dma_cb_t *)device->dma_cb, 0, sizeof(dma_cb_t));
1029 
1030  // Cache the DMA control block bus address
1031  device->dma_cb_addr = addr_to_bus(device, device->dma_cb);
1032 
1033  // Map the physical registers into userspace
1034  if (map_registers(ws2811))
1035  {
1036  ws2811_cleanup(ws2811);
1037  return WS2811_ERROR_MAP_REGISTERS;
1038  }
1039 
1040  // Initialize the GPIO pins
1041  if (gpio_init(ws2811))
1042  {
1043  unmap_registers(ws2811);
1044  ws2811_cleanup(ws2811);
1045  return WS2811_ERROR_GPIO_INIT;
1046  }
1047 
1048  switch (device->driver_mode) {
1049  case PWM:
1050  // Setup the PWM, clocks, and DMA
1051  if (setup_pwm(ws2811))
1052  {
1053  unmap_registers(ws2811);
1054  ws2811_cleanup(ws2811);
1055  return WS2811_ERROR_PWM_SETUP;
1056  }
1057  break;
1058  case PCM:
1059  // Setup the PCM, clock, and DMA
1060  if (setup_pcm(ws2811))
1061  {
1062  unmap_registers(ws2811);
1063  ws2811_cleanup(ws2811);
1064  return WS2811_ERROR_PCM_SETUP;
1065  }
1066  break;
1067  }
1068 
1069  return WS2811_SUCCESS;
1070 }
1071 
1079 void ws2811_fini(ws2811_t *ws2811)
1080 {
1081  volatile pcm_t *pcm = ws2811->device->pcm;
1082 
1083  ws2811_wait(ws2811);
1084  switch (ws2811->device->driver_mode) {
1085  case PWM:
1086  stop_pwm(ws2811);
1087  break;
1088  case PCM:
1089  while (!(pcm->cs & RPI_PCM_CS_TXE)) ; // Wait till TX FIFO is empty
1090  stop_pcm(ws2811);
1091  break;
1092  }
1093 
1094  unmap_registers(ws2811);
1095 
1096  ws2811_cleanup(ws2811);
1097 }
1098 
1107 {
1108  volatile dma_t *dma = ws2811->device->dma;
1109 
1110  if (ws2811->device->driver_mode == SPI) // Nothing to do for SPI
1111  {
1112  return WS2811_SUCCESS;
1113  }
1114 
1115  while ((dma->cs & RPI_DMA_CS_ACTIVE) &&
1116  !(dma->cs & RPI_DMA_CS_ERROR))
1117  {
1118  usleep(10);
1119  }
1120 
1121  if (dma->cs & RPI_DMA_CS_ERROR)
1122  {
1123  fprintf(stderr, "DMA Error: %08x\n", dma->debug);
1124  return WS2811_ERROR_DMA;
1125  }
1126 
1127  return WS2811_SUCCESS;
1128 }
1129 
1139 {
1140  volatile uint8_t *pxl_raw = ws2811->device->pxl_raw;
1141  int driver_mode = ws2811->device->driver_mode;
1142  int bitpos;
1143  int i, k, l, chan;
1144  unsigned j;
1145  ws2811_return_t ret = WS2811_SUCCESS;
1146  uint32_t protocol_time = 0;
1147  static uint64_t previous_timestamp = 0;
1148 
1149  bitpos = (driver_mode == SPI ? 7 : 31);
1150 
1151  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++) // Channel
1152  {
1153  ws2811_channel_t *channel = &ws2811->channel[chan];
1154 
1155  int wordpos = chan; // PWM & PCM
1156  int bytepos = 0; // SPI
1157  const int scale = (channel->brightness & 0xff) + 1;
1158  uint8_t array_size = 3; // Assume 3 color LEDs, RGB
1159 
1160  // If our shift mask includes the highest nibble, then we have 4 LEDs, RBGW.
1161  if (channel->strip_type & SK6812_SHIFT_WMASK)
1162  {
1163  array_size = 4;
1164  }
1165 
1166  // 1.25µs per bit
1167  const uint32_t channel_protocol_time = channel->count * array_size * 8 * 1.25;
1168 
1169  // Only using the channel which takes the longest as both run in parallel
1170  if (channel_protocol_time > protocol_time)
1171  {
1172  protocol_time = channel_protocol_time;
1173  }
1174 
1175  for (i = 0; i < channel->count; i++) // Led
1176  {
1177  uint8_t color[] =
1178  {
1179  channel->gamma[(((channel->leds[i] >> channel->rshift) & 0xff) * scale) >> 8], // red
1180  channel->gamma[(((channel->leds[i] >> channel->gshift) & 0xff) * scale) >> 8], // green
1181  channel->gamma[(((channel->leds[i] >> channel->bshift) & 0xff) * scale) >> 8], // blue
1182  channel->gamma[(((channel->leds[i] >> channel->wshift) & 0xff) * scale) >> 8], // white
1183  };
1184 
1185  for (j = 0; j < array_size; j++) // Color
1186  {
1187  for (k = 7; k >= 0; k--) // Bit
1188  {
1189  // Inversion is handled by hardware for PWM, otherwise by software here
1190  uint8_t symbol = SYMBOL_LOW;
1191  if ((driver_mode != PWM) && channel->invert) symbol = SYMBOL_LOW_INV;
1192 
1193  if (color[j] & (1 << k))
1194  {
1195  symbol = SYMBOL_HIGH;
1196  if ((driver_mode != PWM) && channel->invert) symbol = SYMBOL_HIGH_INV;
1197  }
1198 
1199  for (l = 2; l >= 0; l--) // Symbol
1200  {
1201  uint32_t *wordptr = &((uint32_t *)pxl_raw)[wordpos]; // PWM & PCM
1202  volatile uint8_t *byteptr = &pxl_raw[bytepos]; // SPI
1203 
1204  if (driver_mode == SPI)
1205  {
1206  *byteptr &= ~(1 << bitpos);
1207  if (symbol & (1 << l))
1208  {
1209  *byteptr |= (1 << bitpos);
1210  }
1211  }
1212  else // PWM & PCM
1213  {
1214  *wordptr &= ~(1 << bitpos);
1215  if (symbol & (1 << l))
1216  {
1217  *wordptr |= (1 << bitpos);
1218  }
1219  }
1220 
1221  bitpos--;
1222  if (bitpos < 0)
1223  {
1224  if (driver_mode == SPI)
1225  {
1226  bytepos++;
1227  bitpos = 7;
1228  }
1229  else // PWM & PCM
1230  {
1231  // Every other word is on the same channel for PWM
1232  wordpos += (driver_mode == PWM ? 2 : 1);
1233  bitpos = 31;
1234  }
1235  }
1236  }
1237  }
1238  }
1239  }
1240  }
1241 
1242  // Wait for any previous DMA operation to complete.
1243  if ((ret = ws2811_wait(ws2811)) != WS2811_SUCCESS)
1244  {
1245  return ret;
1246  }
1247 
1248  if (ws2811->render_wait_time != 0) {
1249  const uint64_t current_timestamp = get_microsecond_timestamp();
1250  uint64_t time_diff = current_timestamp - previous_timestamp;
1251 
1252  if (ws2811->render_wait_time > time_diff) {
1253  usleep(ws2811->render_wait_time - time_diff);
1254  }
1255  }
1256 
1257  if (driver_mode != SPI)
1258  {
1259  dma_start(ws2811);
1260  }
1261  else
1262  {
1263  ret = spi_transfer(ws2811);
1264  }
1265 
1266  // LED_RESET_WAIT_TIME is added to allow enough time for the reset to occur.
1267  previous_timestamp = get_microsecond_timestamp();
1268  ws2811->render_wait_time = protocol_time + LED_RESET_WAIT_TIME;
1269 
1270  return ret;
1271 }
1272 
1273 const char * ws2811_get_return_t_str(const ws2811_return_t state)
1274 {
1275  const int index = -state;
1276  static const char * const ret_state_str[] = { WS2811_RETURN_STATES(WS2811_RETURN_STATES_STRING) };
1277 
1278  if (index < (int)(sizeof(ret_state_str) / sizeof(ret_state_str[0])))
1279  {
1280  return ret_state_str[index];
1281  }
1282 
1283  return "";
1284 }
1285 
1286 
1287 void ws2811_set_custom_gamma_factor(ws2811_t *ws2811, double gamma_factor)
1288 {
1289  int chan, counter;
1290  for (chan = 0; chan < RPI_PWM_CHANNELS; chan++)
1291  {
1292  ws2811_channel_t *channel = &ws2811->channel[chan];
1293 
1294  if (channel->gamma)
1295  {
1296  for(counter = 0; counter < 256; counter++)
1297  {
1298 
1299  channel->gamma[counter] = (gamma_factor > 0)? (int)(pow((float)counter / (float)255.00, gamma_factor) * 255.00 + 0.5) : counter;
1300 
1301  }
1302  }
1303 
1304  }
1305 }
const rpi_hw_t * rpi_hw_detect(void)
Definition: rpihw.c:513
#define RPI_PCM_MODE_FSLEN(val)
Definition: pcm.h:90
struct ws2811_device * device
Definition: ws2811.h:89
int mbox_open(void)
Definition: mailbox.c:263
#define RPI_DMA_CS_ACTIVE
Definition: dma.h:71
uint8_t bshift
Definition: ws2811.h:82
static void stop_pcm(ws2811_t *ws2811)
Definition: ws2811.c:316
void ws2811_cleanup(ws2811_t *ws2811)
Definition: ws2811.c:622
uint8_t gshift
Definition: ws2811.h:81
static int setup_pcm(ws2811_t *ws2811)
Definition: ws2811.c:422
#define PWM_OFFSET
Definition: pwm.h:103
uint32_t hwver
Definition: rpihw.h:42
uint32_t ws2811_led_t
Definition: ws2811.h:68
static int gpio_init(ws2811_t *ws2811)
Definition: ws2811.c:529
#define CM_CLK_DIV_PASSWD
Definition: clk.h:52
#define RPI_PWM_CTL_MODE2
Definition: pwm.h:65
#define RPI_DMA_CS_PRIORITY(val)
Definition: dma.h:63
#define PCM_OFFSET
Definition: pcm.h:134
volatile pwm_t * pwm
Definition: ws2811.c:107
void mbox_close(int file_desc)
Definition: mailbox.c:290
uint32_t mem_lock(int file_desc, uint32_t handle)
Definition: mailbox.c:152
ws2811_channel_t channel[RPI_PWM_CHANNELS]
Definition: ws2811.h:93
#define RPI_PWM_CHANNELS
Definition: pwm.h:54
int handle
Definition: ws2811.c:95
#define PCMFUN_DOUT
Definition: pcm.h:141
#define PWM
Definition: ws2811.c:85
static ws2811_return_t spi_transfer(ws2811_t *ws2811)
Definition: ws2811.c:859
#define RPI_PWM_DMAC_PANIC(val)
Definition: pwm.h:91
ws2811_return_t
Definition: ws2811.h:116
#define RPI_DMA_TI_SRC_INC
Definition: dma.h:81
static uint64_t get_microsecond_timestamp()
Definition: ws2811.c:123
#define CM_PCM_OFFSET
Definition: clk.h:62
void pcm_raw_init(ws2811_t *ws2811)
Definition: ws2811.c:602
#define RPI_DMA_CS_INT
Definition: dma.h:69
#define RPI_PWM_CTL_MODE1
Definition: pwm.h:73
volatile pcm_t * pcm
Definition: ws2811.c:108
static int set_driver_mode(ws2811_t *ws2811, int gpionum)
Definition: ws2811.c:664
#define WS2811_RETURN_STATES(X)
Definition: ws2811.h:96
#define RPI_PWM_CTL_POLA1
Definition: pwm.h:70
#define RPI_DMA_TI_WAIT_RESP
Definition: dma.h:86
void pwm_raw_init(ws2811_t *ws2811)
Definition: ws2811.c:574
unsigned size
Definition: ws2811.c:98
#define CM_CLK_CTL_BUSY
Definition: clk.h:40
#define PCM
Definition: ws2811.c:86
uint32_t videocore_base
Definition: rpihw.h:44
Definition: rpihw.h:36
#define SK6812_SHIFT_WMASK
Definition: ws2811.h:53
#define RPI_PCM_CS_TXON
Definition: pcm.h:75
#define RPI_PCM_CS_EN
Definition: pcm.h:77
uint32_t dmanum_to_offset(int dmanum)
Definition: dma.c:66
#define SYMBOL_LOW
Definition: ws2811.c:77
#define LED_RESET_WAIT_TIME
Definition: ws2811.c:68
#define SYMBOL_HIGH_INV
Definition: ws2811.c:80
uint32_t type
Definition: rpihw.h:37
#define WS2811_RETURN_STATES_STRING(state, name, str)
Definition: ws2811.h:114
#define RPI_PCM_MODE_FLEN(val)
Definition: pcm.h:89
#define RPI_PCM_CS_DMAEN
Definition: pcm.h:70
#define SYMBOL_LOW_INV
Definition: ws2811.c:81
unsigned mem_ref
Definition: ws2811.c:96
#define DEV_MEM
Definition: mailbox.h:33
static int check_hwver_and_gpionum(ws2811_t *ws2811)
Definition: ws2811.c:692
volatile cm_clk_t * cm_clk
Definition: ws2811.c:113
int spi_fd
Definition: ws2811.c:109
#define RPI_DMA_CS_ERROR
Definition: dma.h:64
volatile uint8_t * pxl_raw
Definition: ws2811.c:105
#define RPI_PWM_DMAC_DREQ(val)
Definition: pwm.h:92
uint8_t * virt_addr
Definition: ws2811.c:99
struct ws2811_device ws2811_device_t
#define SPI
Definition: ws2811.c:87
#define RPI_DMA_CS_RESET
Definition: dma.h:58
ws2811_led_t * leds
Definition: ws2811.h:77
#define PWM_PERIPH_PHYS
Definition: pwm.h:104
unsigned bus_addr
Definition: ws2811.c:97
void * mapmem(uint32_t base, uint32_t size, const char *mem_dev)
Definition: mailbox.c:46
#define RPI_PCM_TXC_CH1EN
Definition: pcm.h:102
volatile gpio_t * gpio
Definition: ws2811.c:112
volatile dma_cb_t * dma_cb
Definition: ws2811.c:110
ws2811_return_t ws2811_init(ws2811_t *ws2811)
Definition: ws2811.c:894
uint64_t render_wait_time
Definition: ws2811.h:88
#define RPI_DMA_TI_NO_WIDE_BURSTS
Definition: dma.h:74
void * unmapmem(void *addr, uint32_t size)
Definition: mailbox.c:69
#define RPI_PCM_TXC_CH1WID(val)
Definition: pcm.h:104
#define RPI_PWM_CTL_USEF1
Definition: pwm.h:69
#define OSC_FREQ
Definition: ws2811.c:58
uint32_t mem_alloc(int file_desc, uint32_t size, uint32_t align, uint32_t flags)
Definition: mailbox.c:109
static void stop_pwm(ws2811_t *ws2811)
Definition: ws2811.c:292
volatile dma_t * dma
Definition: ws2811.c:106
int pcm_pin_alt(int pcmfun, int pinnum)
Definition: pcm.c:109
uint8_t rshift
Definition: ws2811.h:80
ws2811_return_t ws2811_render(ws2811_t *ws2811)
Definition: ws2811.c:1138
uint32_t freq
Definition: ws2811.h:91
#define RPI_PWM_CTL_PWEN1
Definition: pwm.h:74
#define RPI_PCM_DREQ_TX_PANIC(val)
Definition: pcm.h:110
ws2811_return_t ws2811_wait(ws2811_t *ws2811)
Definition: ws2811.c:1106
#define SYMBOL_HIGH
Definition: ws2811.c:76
#define RPI_HWVER_TYPE_PI4
Definition: rpihw.h:41
static uint32_t addr_to_bus(ws2811_device_t *device, const volatile void *virt)
Definition: ws2811.c:276
#define RPI_PWM_CTL_CLRF1
Definition: pwm.h:68
static int map_registers(ws2811_t *ws2811)
Definition: ws2811.c:164
static int setup_pwm(ws2811_t *ws2811)
Definition: ws2811.c:340
const char * ws2811_get_return_t_str(const ws2811_return_t state)
Definition: ws2811.c:1273
void ws2811_fini(ws2811_t *ws2811)
Definition: ws2811.c:1079
int strip_type
Definition: ws2811.h:76
#define RPI_DMA_TI_PERMAP(val)
Definition: dma.h:76
uint32_t mem_unlock(int file_desc, uint32_t handle)
Definition: mailbox.c:173
#define CM_CLK_CTL_KILL
Definition: clk.h:41
#define CM_CLK_CTL_ENAB
Definition: clk.h:42
static void gpio_function_set(volatile gpio_t *gpio, uint8_t pin, uint8_t function)
Definition: gpio.h:69
#define RPI_PCM_TXC_CH1WEX
Definition: pcm.h:101
#define PWM_BYTE_COUNT(leds, freq)
Definition: ws2811.c:71
uint8_t * gamma
Definition: ws2811.h:83
int max_count
Definition: ws2811.c:115
int driver_mode
Definition: ws2811.c:104
static int max_channel_led_count(ws2811_t *ws2811)
Definition: ws2811.c:141
#define RPI_PWM_CTL_PWEN2
Definition: pwm.h:66
#define DEV_GPIOMEM
Definition: mailbox.h:34
#define RPI_PCM_DREQ_TX(val)
Definition: pcm.h:112
uint32_t periph_base
Definition: rpihw.h:43
const rpi_hw_t * rpi_hw
Definition: ws2811.h:90
#define RPI_PWM_DMAC_ENAB
Definition: pwm.h:90
static void unmap_registers(ws2811_t *ws2811)
Definition: ws2811.c:238
#define RPI_PWM_CTL_USEF2
Definition: pwm.h:61
#define PCM_PERIPH_PHYS
Definition: pcm.h:135
#define PCM_BYTE_COUNT(leds, freq)
Definition: ws2811.c:73
int dmanum
Definition: ws2811.h:92
uint8_t wshift
Definition: ws2811.h:79
uint8_t brightness
Definition: ws2811.h:78
#define RPI_DMA_CS_PANIC_PRIORITY(val)
Definition: dma.h:62
#define RPI_PCM_CS_TXE
Definition: pcm.h:61
#define RPI_DMA_TI_DEST_DREQ
Definition: dma.h:83
#define CM_PWM_OFFSET
Definition: clk.h:63
#define RPI_PCM_TXC_CH1POS(val)
Definition: pcm.h:103
#define PAGE_SIZE
Definition: dma.h:120
static ws2811_return_t spi_init(ws2811_t *ws2811)
Definition: ws2811.c:752
#define WS2811_STRIP_RGB
Definition: ws2811.h:56
#define RPI_DMA_CS_WAIT_OUTSTANDING_WRITES
Definition: dma.h:61
static void dma_start(ws2811_t *ws2811)
Definition: ws2811.c:496
uint32_t mem_free(int file_desc, uint32_t handle)
Definition: mailbox.c:132
#define RPI_PWM_CTL_POLA2
Definition: pwm.h:62
#define CM_CLK_CTL_SRC_OSC
Definition: clk.h:44
int pwm_pin_alt(int chan, int pinnum)
Definition: pwm.c:89
#define OSC_FREQ_PI4
Definition: ws2811.c:59
#define BUS_TO_PHYS(x)
Definition: ws2811.c:56
#define RPI_PCM_CS_TXCLR
Definition: pcm.h:74
videocore_mbox_t mbox
Definition: ws2811.c:114
#define CM_CLK_DIV_DIVI(val)
Definition: clk.h:53
void ws2811_set_custom_gamma_factor(ws2811_t *ws2811, double gamma_factor)
Definition: ws2811.c:1287
#define CM_CLK_CTL_PASSWD
Definition: clk.h:37
struct videocore_mbox videocore_mbox_t
#define RPI_DMA_CS_END
Definition: dma.h:70
#define GPIO_OFFSET
Definition: gpio.h:66
uint32_t dma_cb_addr
Definition: ws2811.c:111


ws281x
Author(s): Alexey Rogachevskiy , Oleg Kalachev
autogenerated on Wed Jun 15 2022 02:46:00