Classes | Macros | Typedefs | Functions
ws2811.c File Reference
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <signal.h>
#include <linux/types.h>
#include <linux/spi/spidev.h>
#include <time.h>
#include <math.h>
#include "mailbox.h"
#include "clk.h"
#include "gpio.h"
#include "dma.h"
#include "pwm.h"
#include "pcm.h"
#include "rpihw.h"
#include "ws2811.h"
Include dependency graph for ws2811.c:

Go to the source code of this file.

Classes

struct  videocore_mbox
 
struct  ws2811_device
 

Macros

#define BUS_TO_PHYS(x)   ((x)&~0xC0000000)
 
#define LED_BIT_COUNT(leds, freq)
 
#define LED_COLOURS   4
 
#define LED_RESET_uS   55
 
#define LED_RESET_WAIT_TIME   300
 
#define NONE   0
 
#define OSC_FREQ   19200000
 
#define OSC_FREQ_PI4   54000000
 
#define PCM   2
 
#define PCM_BYTE_COUNT(leds, freq)   ((((LED_BIT_COUNT(leds, freq) >> 3) & ~0x7) + 4) + 4)
 
#define PWM   1
 
#define PWM_BYTE_COUNT(leds, freq)
 
#define SPI   3
 
#define SYMBOL_HIGH   0x6
 
#define SYMBOL_HIGH_INV   0x1
 
#define SYMBOL_LOW   0x4
 
#define SYMBOL_LOW_INV   0x3
 

Typedefs

typedef struct videocore_mbox videocore_mbox_t
 
typedef struct ws2811_device ws2811_device_t
 

Functions

static uint32_t addr_to_bus (ws2811_device_t *device, const volatile void *virt)
 
static int check_hwver_and_gpionum (ws2811_t *ws2811)
 
static void dma_start (ws2811_t *ws2811)
 
static uint64_t get_microsecond_timestamp ()
 
static int gpio_init (ws2811_t *ws2811)
 
static int map_registers (ws2811_t *ws2811)
 
static int max_channel_led_count (ws2811_t *ws2811)
 
void pcm_raw_init (ws2811_t *ws2811)
 
void pwm_raw_init (ws2811_t *ws2811)
 
static int set_driver_mode (ws2811_t *ws2811, int gpionum)
 
static int setup_pcm (ws2811_t *ws2811)
 
static int setup_pwm (ws2811_t *ws2811)
 
static ws2811_return_t spi_init (ws2811_t *ws2811)
 
static ws2811_return_t spi_transfer (ws2811_t *ws2811)
 
static void stop_pcm (ws2811_t *ws2811)
 
static void stop_pwm (ws2811_t *ws2811)
 
static void unmap_registers (ws2811_t *ws2811)
 
void ws2811_cleanup (ws2811_t *ws2811)
 
void ws2811_fini (ws2811_t *ws2811)
 
const char * ws2811_get_return_t_str (const ws2811_return_t state)
 
ws2811_return_t ws2811_init (ws2811_t *ws2811)
 
ws2811_return_t ws2811_render (ws2811_t *ws2811)
 
void ws2811_set_custom_gamma_factor (ws2811_t *ws2811, double gamma_factor)
 
ws2811_return_t ws2811_wait (ws2811_t *ws2811)
 

Macro Definition Documentation

◆ BUS_TO_PHYS

#define BUS_TO_PHYS (   x)    ((x)&~0xC0000000)

Definition at line 56 of file ws2811.c.

◆ LED_BIT_COUNT

#define LED_BIT_COUNT (   leds,
  freq 
)
Value:
((leds * LED_COLOURS * 8 * 3) + ((LED_RESET_uS * \
(freq * 3)) / 1000000))

Definition at line 64 of file ws2811.c.

◆ LED_COLOURS

#define LED_COLOURS   4

Definition at line 62 of file ws2811.c.

◆ LED_RESET_uS

#define LED_RESET_uS   55

Definition at line 63 of file ws2811.c.

◆ LED_RESET_WAIT_TIME

#define LED_RESET_WAIT_TIME   300

Definition at line 68 of file ws2811.c.

◆ NONE

#define NONE   0

Definition at line 84 of file ws2811.c.

◆ OSC_FREQ

#define OSC_FREQ   19200000

Definition at line 58 of file ws2811.c.

◆ OSC_FREQ_PI4

#define OSC_FREQ_PI4   54000000

Definition at line 59 of file ws2811.c.

◆ PCM

#define PCM   2

Definition at line 86 of file ws2811.c.

◆ PCM_BYTE_COUNT

#define PCM_BYTE_COUNT (   leds,
  freq 
)    ((((LED_BIT_COUNT(leds, freq) >> 3) & ~0x7) + 4) + 4)

Definition at line 73 of file ws2811.c.

◆ PWM

#define PWM   1

Definition at line 85 of file ws2811.c.

◆ PWM_BYTE_COUNT

#define PWM_BYTE_COUNT (   leds,
  freq 
)
Value:
(((((LED_BIT_COUNT(leds, freq) >> 3) & ~0x7) + 4) + 4) * \
RPI_PWM_CHANNELS)

Definition at line 71 of file ws2811.c.

◆ SPI

#define SPI   3

Definition at line 87 of file ws2811.c.

◆ SYMBOL_HIGH

#define SYMBOL_HIGH   0x6

Definition at line 76 of file ws2811.c.

◆ SYMBOL_HIGH_INV

#define SYMBOL_HIGH_INV   0x1

Definition at line 80 of file ws2811.c.

◆ SYMBOL_LOW

#define SYMBOL_LOW   0x4

Definition at line 77 of file ws2811.c.

◆ SYMBOL_LOW_INV

#define SYMBOL_LOW_INV   0x3

Definition at line 81 of file ws2811.c.

Typedef Documentation

◆ videocore_mbox_t

◆ ws2811_device_t

Function Documentation

◆ addr_to_bus()

static uint32_t addr_to_bus ( ws2811_device_t device,
const volatile void *  virt 
)
static

Given a userspace address pointer, return the matching bus address used by DMA. Note: The bus address is not the same as the CPU physical address.

Parameters
addrUserspace virtual address pointer.
Returns
Bus address for use by DMA.

Definition at line 276 of file ws2811.c.

◆ check_hwver_and_gpionum()

static int check_hwver_and_gpionum ( ws2811_t ws2811)
static

Definition at line 692 of file ws2811.c.

◆ dma_start()

static void dma_start ( ws2811_t ws2811)
static

Start the DMA feeding the PWM FIFO. This will stream the entire DMA buffer out of both PWM channels.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 496 of file ws2811.c.

◆ get_microsecond_timestamp()

static uint64_t get_microsecond_timestamp ( )
static

Provides monotonic timestamp in microseconds.

Returns
Current timestamp in microseconds or 0 on error.

Definition at line 123 of file ws2811.c.

◆ gpio_init()

static int gpio_init ( ws2811_t ws2811)
static

Initialize the application selected GPIO pins for PWM/PCM operation.

Parameters
ws2811ws2811 instance pointer.
Returns
0 on success, -1 on unsupported pin

Definition at line 529 of file ws2811.c.

◆ map_registers()

static int map_registers ( ws2811_t ws2811)
static

Map all devices into userspace memory. Not called for SPI

Parameters
ws2811ws2811 instance pointer.
Returns
0 on success, -1 otherwise.

Definition at line 164 of file ws2811.c.

◆ max_channel_led_count()

static int max_channel_led_count ( ws2811_t ws2811)
static

Iterate through the channels and find the largest led count.

Parameters
ws2811ws2811 instance pointer.
Returns
Maximum number of LEDs in all channels.

Definition at line 141 of file ws2811.c.

◆ pcm_raw_init()

void pcm_raw_init ( ws2811_t ws2811)

Initialize the PCM DMA buffer with all zeros. The DMA buffer length is assumed to be a word multiple.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 602 of file ws2811.c.

◆ pwm_raw_init()

void pwm_raw_init ( ws2811_t ws2811)

Initialize the PWM DMA buffer with all zeros, inverted operation will be handled by hardware. The DMA buffer length is assumed to be a word multiple.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 574 of file ws2811.c.

◆ set_driver_mode()

static int set_driver_mode ( ws2811_t ws2811,
int  gpionum 
)
static

Definition at line 664 of file ws2811.c.

◆ setup_pcm()

static int setup_pcm ( ws2811_t ws2811)
static

Setup the PCM controller with one 32-bit channel in a 32-bit frame using DMA to feed the PCM FIFO.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 422 of file ws2811.c.

◆ setup_pwm()

static int setup_pwm ( ws2811_t ws2811)
static

Setup the PWM controller in serial mode on both channels using DMA to feed the PWM FIFO.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 340 of file ws2811.c.

◆ spi_init()

static ws2811_return_t spi_init ( ws2811_t ws2811)
static

Definition at line 752 of file ws2811.c.

◆ spi_transfer()

static ws2811_return_t spi_transfer ( ws2811_t ws2811)
static

Definition at line 859 of file ws2811.c.

◆ stop_pcm()

static void stop_pcm ( ws2811_t ws2811)
static

Stop the PCM controller.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 316 of file ws2811.c.

◆ stop_pwm()

static void stop_pwm ( ws2811_t ws2811)
static

Stop the PWM controller.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 292 of file ws2811.c.

◆ unmap_registers()

static void unmap_registers ( ws2811_t ws2811)
static

Unmap all devices from virtual memory.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 238 of file ws2811.c.

◆ ws2811_cleanup()

void ws2811_cleanup ( ws2811_t ws2811)

Cleanup previously allocated device memory and buffers.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 622 of file ws2811.c.

◆ ws2811_fini()

void ws2811_fini ( ws2811_t ws2811)

Shut down DMA, PWM, and cleanup memory.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 1079 of file ws2811.c.

◆ ws2811_get_return_t_str()

const char* ws2811_get_return_t_str ( const ws2811_return_t  state)

Definition at line 1273 of file ws2811.c.

◆ ws2811_init()

ws2811_return_t ws2811_init ( ws2811_t ws2811)

Allocate and initialize memory, buffers, pages, PWM, DMA, and GPIO.

Parameters
ws2811ws2811 instance pointer.
Returns
0 on success, -1 otherwise.

Definition at line 894 of file ws2811.c.

◆ ws2811_render()

ws2811_return_t ws2811_render ( ws2811_t ws2811)

Render the DMA buffer from the user supplied LED arrays and start the DMA controller. This will update all LEDs on both PWM channels.

Parameters
ws2811ws2811 instance pointer.
Returns
None

Definition at line 1138 of file ws2811.c.

◆ ws2811_set_custom_gamma_factor()

void ws2811_set_custom_gamma_factor ( ws2811_t ws2811,
double  gamma_factor 
)

Definition at line 1287 of file ws2811.c.

◆ ws2811_wait()

ws2811_return_t ws2811_wait ( ws2811_t ws2811)

Wait for any executing DMA operation to complete before returning.

Parameters
ws2811ws2811 instance pointer.
Returns
0 on success, -1 on DMA competion error

Definition at line 1106 of file ws2811.c.

LED_RESET_uS
#define LED_RESET_uS
Definition: ws2811.c:63
LED_BIT_COUNT
#define LED_BIT_COUNT(leds, freq)
Definition: ws2811.c:64
LED_COLOURS
#define LED_COLOURS
Definition: ws2811.c:62


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