Classes | Defines | Typedefs | Functions | Variables
pigpio.c File Reference
#include <stdio.h>
#include <string.h>
#include <strings.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdarg.h>
#include <ctype.h>
#include <syslog.h>
#include <poll.h>
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#include <signal.h>
#include <errno.h>
#include <time.h>
#include <sys/ioctl.h>
#include <limits.h>
#include <pthread.h>
#include <sys/time.h>
#include <sys/mman.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/file.h>
#include <sys/socket.h>
#include <sys/sysmacros.h>
#include <netinet/tcp.h>
#include <arpa/inet.h>
#include <sys/select.h>
#include <fnmatch.h>
#include <glob.h>
#include "pigpio.h"
#include "command.h"
#include "custom.cext"
Include dependency graph for pigpio.c:

Go to the source code of this file.

Classes

struct  clkCfg_t
struct  clkInf_t
struct  dmaIPage_t
struct  DMAMem_t
struct  dmaOPage_t
struct  dmaPage_t
struct  eventAlert_t
struct  fileInfo_t
struct  gpioAlert_t
struct  gpioCfg_t
struct  gpioGetSamples_t
struct  gpioInfo_t
struct  gpioISR_t
struct  gpioNotify_t
struct  gpioScript_t
struct  gpioSignal_t
struct  gpioStats_t
struct  gpioTimer_t
struct  i2cInfo_t
struct  my_i2c_rdwr_ioctl_data_t
union  my_smbus_data
struct  my_smbus_ioctl_data
struct  serInfo_t
struct  spiInfo_t
struct  wfRx_t
struct  wfRxI2C_t
struct  wfRxSerial_t
struct  wfRxSPI_t
struct  wfStats_t

Defines

#define _GNU_SOURCE
#define AUX_BASE   (pi_peri_phys + 0x00215000)
#define AUX_ENABLES   1
#define AUX_IRQ   0
#define AUX_LEN   0xD8
#define AUX_MU_BAUD_REG   26
#define AUX_MU_CNTL_REG   24
#define AUX_MU_IER_REG   17
#define AUX_MU_IIR_REG   18
#define AUX_MU_IO_REG   16
#define AUX_MU_LCR_REG   19
#define AUX_MU_LSR_REG   21
#define AUX_MU_MCR_REG   20
#define AUX_MU_MSR_REG   22
#define AUX_MU_SCRATCH   23
#define AUX_MU_STAT_REG   25
#define AUX_SPI0_CNTL0_REG   32
#define AUX_SPI0_CNTL1_REG   33
#define AUX_SPI0_IO_REG   40
#define AUX_SPI0_PEEK_REG   35
#define AUX_SPI0_STAT_REG   34
#define AUX_SPI0_TX_HOLD   44
#define AUX_SPI1_CNTL0_REG   48
#define AUX_SPI1_CNTL1_REG   49
#define AUX_SPI1_IO_REG   56
#define AUX_SPI1_PEEK_REG   51
#define AUX_SPI1_STAT_REG   50
#define AUX_SPI1_TX_HOLD   60
#define AUXENB_SPI1   (1<<1)
#define AUXENB_SPI2   (1<<2)
#define AUXENB_UART   (1<<0)
#define AUXSPI_CNTL0_CLR_FIFOS   (1<<9)
#define AUXSPI_CNTL0_CS(x)   ((x)<<17)
#define AUXSPI_CNTL0_DOUT_HOLD(x)   ((x)<<12)
#define AUXSPI_CNTL0_ENABLE   (1<<11)
#define AUXSPI_CNTL0_IN_RISING(x)   ((x)<<10)
#define AUXSPI_CNTL0_INVERT_CLK(x)   ((x)<<7)
#define AUXSPI_CNTL0_MSB_FIRST(x)   ((x)<<6)
#define AUXSPI_CNTL0_OUT_RISING(x)   ((x)<<8)
#define AUXSPI_CNTL0_POSTINP   (1<<16)
#define AUXSPI_CNTL0_SHIFT_LEN(x)   ((x)<<0)
#define AUXSPI_CNTL0_SPEED(x)   ((x)<<20)
#define AUXSPI_CNTL0_VAR_CS   (1<<15)
#define AUXSPI_CNTL0_VAR_WIDTH   (1<<14)
#define AUXSPI_CNTL1_CS_HIGH(x)   ((x)<<8)
#define AUXSPI_CNTL1_DONE_IRQ   (1<<6)
#define AUXSPI_CNTL1_KEEP_INPUT   (1<<0)
#define AUXSPI_CNTL1_MSB_FIRST(x)   ((x)<<1)
#define AUXSPI_CNTL1_TX_IRQ   (1<<7)
#define AUXSPI_STAT_BITS(x)   ((x)<<0)
#define AUXSPI_STAT_BUSY   (1<<6)
#define AUXSPI_STAT_RX_EMPTY   (1<<7)
#define AUXSPI_STAT_RX_FIFO(x)   ((x)<<20)
#define AUXSPI_STAT_TX_EMPTY   (1<<9)
#define AUXSPI_STAT_TX_FIFO(x)   ((x)<<28)
#define AUXSPI_STAT_TX_FULL   (1<<10)
#define BANK   (gpio>>5)
#define BCM_PASSWD   (0x5A<<24)
#define BILLION   1000000000
#define BIT   (1<<(gpio&0x1F))
#define BLOCK_SIZE   (PAGES_PER_BLOCK*PAGE_SIZE)
#define BPD   4
#define BSCS_BASE   (pi_peri_phys + 0x00214000)
#define BSCS_LEN   0x40
#define BUS_TO_PHYS(x)   ((x)&~0xC0000000)
#define CBS_PER_CYCLE   ((PULSE_PER_CYCLE*3)+2)
#define CBS_PER_IPAGE   117
#define CBS_PER_OPAGE   118
#define CHECK_INITED
#define CHECK_INITED_RET_NIL
#define CHECK_INITED_RET_NULL_PTR
#define CHECK_NOT_INITED
#define CLK_BASE   (pi_peri_phys + 0x00101000)
#define CLK_CTL_BUSY   (1 <<7)
#define CLK_CTL_ENAB   (1 <<4)
#define CLK_CTL_KILL   (1 <<5)
#define CLK_CTL_MASH(x)   ((x)<<9)
#define CLK_CTL_SRC(x)   ((x)<<0)
#define CLK_CTL_SRC_OSC   1
#define CLK_CTL_SRC_PLLD   6
#define CLK_DIV_DIVF(x)   ((x)<< 0)
#define CLK_DIV_DIVI(x)   ((x)<<12)
#define CLK_GP0_CTL   28
#define CLK_GP0_DIV   29
#define CLK_GP1_CTL   30
#define CLK_GP1_DIV   31
#define CLK_GP2_CTL   32
#define CLK_GP2_DIV   33
#define CLK_LEN   0xA8
#define CLK_OSC_FREQ   19200000
#define CLK_PCMCTL   38
#define CLK_PCMDIV   39
#define CLK_PLLD_FREQ   500000000
#define CLK_PWMCTL   40
#define CLK_PWMDIV   41
#define CLK_SRCS   2
#define CYCLES_PER_BLOCK   80
#define DBG(level, format, arg...)   DO_DBG(level, format, ## arg)
#define DBG_ALWAYS   0
#define DBG_DMACBS   2
#define DBG_FAST_TICK   7
#define DBG_INTERNAL   5
#define DBG_MAX_LEVEL   8
#define DBG_MIN_LEVEL   0
#define DBG_SCRIPT   3
#define DBG_SLOW_TICK   6
#define DBG_STARTUP   1
#define DBG_USER   4
#define DEFAULT_PWM_IDX   5
#define DMA15_BASE   (pi_peri_phys + 0x00E05000)
#define DMA_ACTIVATE   (1<< 0)
#define DMA_BASE   (pi_peri_phys + 0x00007000)
#define DMA_BURST_LENGTH(x)   ((x)<<12)
#define DMA_CHANNEL_RESET   (1<<31)
#define DMA_CONBLK_AD   1
#define DMA_CS   0
#define DMA_DEBUG   8
#define DMA_DEBUG_FIFO_ERR   (1<<1)
#define DMA_DEBUG_RD_LST_NOT_SET_ERR   (1<<0)
#define DMA_DEBUG_READ_ERR   (1<<2)
#define DMA_DEST_DREQ   (1<< 6)
#define DMA_DEST_IGNORE   (1<< 7)
#define DMA_DEST_INC   (1<< 4)
#define DMA_DEST_WIDTH   (1<< 5)
#define DMA_ENABLE   (0xFF0/4)
#define DMA_END_FLAG   (1<< 1)
#define DMA_INTERRUPT_STATUS   (1<< 2)
#define DMA_LEN   0x1000 /* allow access to all channels */
#define DMA_LITE_FIRST   7
#define DMA_LITE_MAX   0xfffc
#define DMA_NO_WIDE_BURSTS   (1<<26)
#define DMA_PANIC_PRIORITY(x)   ((x)<<20)
#define DMA_PERIPHERAL_MAPPING(x)   ((x)<<16)
#define DMA_PRIORITY(x)   ((x)<<16)
#define DMA_SRC_DREQ   (1<<10)
#define DMA_SRC_IGNORE   (1<<11)
#define DMA_SRC_INC   (1<< 8)
#define DMA_SRC_WIDTH   (1<< 9)
#define DMA_WAIT_ON_WRITES   (1<<28)
#define DMA_WAIT_RESP   (1<< 3)
#define DMAI_PAGES   (PAGES_PER_BLOCK * bufferBlocks)
#define DMAO_PAGES   (PAGES_PER_BLOCK * PI_WAVE_BLOCKS)
#define DO_DBG(level, format, arg...)
#define FLUSH_PAGES   1024
#define GPAFEN0   34
#define GPAFEN1   35
#define GPAREN0   31
#define GPAREN1   32
#define GPCLR0   10
#define GPCLR1   11
#define GPEDS0   16
#define GPEDS1   17
#define GPFEN0   22
#define GPFEN1   23
#define GPFSEL0   0
#define GPHEN0   25
#define GPHEN1   26
#define GPIO_BASE   (pi_peri_phys + 0x00200000)
#define GPIO_HW_CLK   4
#define GPIO_HW_PWM   5
#define GPIO_I2C   7
#define GPIO_LEN   0xB4
#define GPIO_PWM   2
#define GPIO_SERVO   3
#define GPIO_SPI   6
#define GPIO_UNDEFINED   0
#define GPIO_WRITE   1
#define GPLEN0   28
#define GPLEN1   29
#define GPLEV0   13
#define GPLEV1   14
#define GPPUD   37
#define GPPUDCLK0   38
#define GPPUDCLK1   39
#define GPREN0   19
#define GPREN1   20
#define GPSET0   7
#define GPSET1   8
#define LVS_PER_IPAGE   38
#define MAX_EMITS   (PIPE_BUF / sizeof(gpioReport_t))
#define MAX_REPORT   250
#define MAX_SAMPLE   4000
#define MB_ALLOCATE_MEMORY_TAG   0x3000C
#define MB_DEV1   "/dev/vcio"
#define MB_DEV2   "/dev/pigpio-mb"
#define MB_DEV_MAJOR   100
#define MB_END_TAG   0
#define MB_IOCTL   _IOWR(MB_DEV_MAJOR, 0, char *)
#define MB_LOCK_MEMORY_TAG   0x3000D
#define MB_PROCESS_REQUEST   0
#define MB_RELEASE_MEMORY_TAG   0x3000F
#define MB_UNLOCK_MEMORY_TAG   0x3000E
#define MILLION   1000000
#define NORMAL_DMA   (DMA_NO_WIDE_BURSTS | DMA_WAIT_RESP)
#define NUM_CBS   (CBS_PER_CYCLE * bufferCycles)
#define NUM_WAVE_CBS   (DMAO_PAGES * CBS_PER_OPAGE)
#define NUM_WAVE_OOL   (DMAO_PAGES * OOL_PER_OPAGE)
#define OFF_PER_IPAGE   38
#define ON_PER_IPAGE   2
#define OOL_PER_OPAGE   79
#define PAD_PER_IPAGE   7
#define PADS_BASE   (pi_peri_phys + 0x00100000)
#define PADS_LEN   0x38
#define PAGE_SIZE   4096
#define PAGES_PER_BLOCK   53
#define PCM_BASE   (pi_peri_phys + 0x00203000)
#define PCM_CS   0
#define PCM_CS_DMAEN   (1 <<9)
#define PCM_CS_EN   (1 <<0)
#define PCM_CS_RXCLR   (1 <<4)
#define PCM_CS_RXERR   (1 <<16)
#define PCM_CS_RXON   (1 <<1)
#define PCM_CS_RXSEX   (1 <<23)
#define PCM_CS_RXTHR(x)   ((x)<<7)
#define PCM_CS_STBY   (1 <<25)
#define PCM_CS_SYNC   (1 <<24)
#define PCM_CS_TXCLR   (1 <<3)
#define PCM_CS_TXERR   (1 <<15)
#define PCM_CS_TXON   (1 <<2)
#define PCM_CS_TXTHR(x)   ((x)<<5)
#define PCM_DREQ   5
#define PCM_DREQ_RX_PANIC(x)   ((x)<<16)
#define PCM_DREQ_RX_REQ_L(x)   ((x)<< 0)
#define PCM_DREQ_TX_PANIC(x)   ((x)<<24)
#define PCM_DREQ_TX_REQ_L(x)   ((x)<< 8)
#define PCM_FIFO   1
#define PCM_GRAY   8
#define PCM_GRAY_CLR   (1<<1)
#define PCM_GRAY_EN   (1<<0)
#define PCM_GRAY_FLUSH   (1<<2)
#define PCM_INTEN   6
#define PCM_INTEN_RXERR   (1<<3)
#define PCM_INTEN_RXR   (1<<1)
#define PCM_INTEN_TXERR   (1<<2)
#define PCM_INTEN_TXW   (1<<0)
#define PCM_INTSTC   7
#define PCM_INTSTC_RXERR   (1<<3)
#define PCM_INTSTC_RXR   (1<<1)
#define PCM_INTSTC_TXERR   (1<<2)
#define PCM_INTSTC_TXW   (1<<0)
#define PCM_LEN   0x24
#define PCM_MODE   2
#define PCM_MODE_CLK_DIS   (1 <<28)
#define PCM_MODE_CLKI   (1 <<22)
#define PCM_MODE_CLKM   (1 <<23)
#define PCM_MODE_FLEN(x)   ((x)<<10)
#define PCM_MODE_FRXP   (1 <<25)
#define PCM_MODE_FSI   (1 <<20)
#define PCM_MODE_FSLEN(x)   ((x)<< 0)
#define PCM_MODE_FSM   (1 <<21)
#define PCM_MODE_FTXP   (1 <<24)
#define PCM_MODE_PDME   (1 <<26)
#define PCM_MODE_PDMN   (1 <<27)
#define PCM_RXC   3
#define PCM_RXC_CH1EN   (1 <<30)
#define PCM_RXC_CH1POS(x)   ((x)<<20)
#define PCM_RXC_CH1WEX   (1 <<31)
#define PCM_RXC_CH1WID(x)   ((x)<<16)
#define PCM_RXC_CH2EN   (1 <<14)
#define PCM_RXC_CH2POS(x)   ((x)<< 4)
#define PCM_RXC_CH2WEX   (1 <<15)
#define PCM_RXC_CH2WID(x)   ((x)<< 0)
#define PCM_TIMER   (((PCM_BASE + PCM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS)
#define PCM_TXC   4
#define PCM_TXC_CH1EN   (1 <<30)
#define PCM_TXC_CH1POS(x)   ((x)<<20)
#define PCM_TXC_CH1WEX   (1 <<31)
#define PCM_TXC_CH1WID(x)   ((x)<<16)
#define PCM_TXC_CH2EN   (1 <<14)
#define PCM_TXC_CH2POS(x)   ((x)<< 4)
#define PCM_TXC_CH2WEX   (1 <<15)
#define PCM_TXC_CH2WID(x)   ((x)<< 0)
#define PI_ASPI_CE0   18
#define PI_ASPI_CE1   17
#define PI_ASPI_CE2   16
#define PI_ASPI_MISO   19
#define PI_ASPI_MOSI   20
#define PI_ASPI_SCLK   21
#define PI_ENDING   2
#define PI_FILE_CLOSED   0
#define PI_FILE_OPENED   2
#define PI_FILE_RESERVED   1
#define PI_I2C_CLOSED   0
#define PI_I2C_FUNC_SMBUS_PROC_CALL   0x00800000
#define PI_I2C_FUNC_SMBUS_QUICK   0x00010000
#define PI_I2C_FUNC_SMBUS_READ_BLOCK_DATA   0x01000000
#define PI_I2C_FUNC_SMBUS_READ_BYTE   0x00020000
#define PI_I2C_FUNC_SMBUS_READ_BYTE_DATA   0x00080000
#define PI_I2C_FUNC_SMBUS_READ_I2C_BLOCK   0x04000000
#define PI_I2C_FUNC_SMBUS_READ_WORD_DATA   0x00200000
#define PI_I2C_FUNC_SMBUS_WRITE_BLOCK_DATA   0x02000000
#define PI_I2C_FUNC_SMBUS_WRITE_BYTE   0x00040000
#define PI_I2C_FUNC_SMBUS_WRITE_BYTE_DATA   0x00100000
#define PI_I2C_FUNC_SMBUS_WRITE_I2C_BLOCK   0x08000000
#define PI_I2C_FUNC_SMBUS_WRITE_WORD_DATA   0x00400000
#define PI_I2C_FUNCS   0x0705
#define PI_I2C_OPENED   2
#define PI_I2C_RDWR   0x0707
#define PI_I2C_RESERVED   1
#define PI_I2C_RETRIES   0x0701
#define PI_I2C_SLAVE   0x0703
#define PI_I2C_SMBUS   0x0720
#define PI_I2C_SMBUS_BLOCK_DATA   5
#define PI_I2C_SMBUS_BLOCK_MAX   32
#define PI_I2C_SMBUS_BLOCK_PROC_CALL   7
#define PI_I2C_SMBUS_BYTE   1
#define PI_I2C_SMBUS_BYTE_DATA   2
#define PI_I2C_SMBUS_I2C_BLOCK_BROKEN   6
#define PI_I2C_SMBUS_I2C_BLOCK_DATA   8
#define PI_I2C_SMBUS_I2C_BLOCK_MAX   32
#define PI_I2C_SMBUS_PROC_CALL   4
#define PI_I2C_SMBUS_QUICK   0
#define PI_I2C_SMBUS_READ   1
#define PI_I2C_SMBUS_WORD_DATA   3
#define PI_I2C_SMBUS_WRITE   0
#define PI_I2C_TIMEOUT   0x0702
#define PI_MASH_MAX_FREQ   23800000
#define PI_MAX_PATH   512
#define PI_NOTIFY_CLOSED   0
#define PI_NOTIFY_CLOSING   2
#define PI_NOTIFY_OPENED   3
#define PI_NOTIFY_PAUSED   5
#define PI_NOTIFY_RESERVED   1
#define PI_NOTIFY_RUNNING   4
#define PI_PERI_BUS   0x7E000000
#define PI_RUNNING   1
#define PI_SCRIPT_DELETE   2
#define PI_SCRIPT_DYING   3
#define PI_SCRIPT_FREE   0
#define PI_SCRIPT_HALT   0
#define PI_SCRIPT_IN_USE   2
#define PI_SCRIPT_RESERVED   1
#define PI_SCRIPT_RUN   1
#define PI_SCRIPT_STACK_SIZE   256
#define PI_SER_CLOSED   0
#define PI_SER_OPENED   2
#define PI_SER_RESERVED   1
#define PI_SPI_CE0   8
#define PI_SPI_CE1   7
#define PI_SPI_CLOSED   0
#define PI_SPI_FLAGS_CHANNEL(x)   ((x&7)<<29)
#define PI_SPI_FLAGS_GET_3WIRE(x)   (((x)>>9)&1)
#define PI_SPI_FLAGS_GET_3WREN(x)   (((x)>>10)&15)
#define PI_SPI_FLAGS_GET_AUX_SPI(x)   (((x)>>8)&1)
#define PI_SPI_FLAGS_GET_BITLEN(x)   (((x)>>16)&63)
#define PI_SPI_FLAGS_GET_CHANNEL(x)   (((x)>>29)&7)
#define PI_SPI_FLAGS_GET_CPHA(x)   ((x)&1)
#define PI_SPI_FLAGS_GET_CPOL(x)   ((x)&2)
#define PI_SPI_FLAGS_GET_CSPOL(x)   ((x)&4)
#define PI_SPI_FLAGS_GET_CSPOLS(x)   (((x)>>2)&7)
#define PI_SPI_FLAGS_GET_MODE(x)   ((x)&3)
#define PI_SPI_FLAGS_GET_RESVD(x)   (((x)>>5)&7)
#define PI_SPI_FLAGS_GET_RX_LSB(x)   (((x)>>15)&1)
#define PI_SPI_FLAGS_GET_TX_LSB(x)   (((x)>>14)&1)
#define PI_SPI_MISO   9
#define PI_SPI_MOSI   10
#define PI_SPI_OPENED   2
#define PI_SPI_RESERVED   1
#define PI_SPI_SCLK   11
#define PI_STARTING   0
#define PI_THREAD_NONE   0
#define PI_THREAD_RUNNING   2
#define PI_THREAD_STARTED   1
#define PI_WF_MICROS   1
#define PI_WFRX_I2C_SCL   3
#define PI_WFRX_I2C_SDA   2
#define PI_WFRX_NONE   0
#define PI_WFRX_SERIAL   1
#define PI_WFRX_SPI_CS   7
#define PI_WFRX_SPI_MISO   5
#define PI_WFRX_SPI_MOSI   6
#define PI_WFRX_SPI_SCLK   4
#define PULSE_PER_CYCLE   25
#define PWM_BASE   (pi_peri_phys + 0x0020C000)
#define PWM_CTL   0
#define PWM_CTL_CLRF1   (1<<6)
#define PWM_CTL_MODE1   (1<<1)
#define PWM_CTL_MSEN1   (1<<7)
#define PWM_CTL_MSEN2   (1<<15)
#define PWM_CTL_PWEN1   (1<<0)
#define PWM_CTL_PWEN2   (1<<8)
#define PWM_CTL_USEF1   (1<<5)
#define PWM_DAT1   5
#define PWM_DAT2   9
#define PWM_DMAC   2
#define PWM_DMAC_DREQ(x)   (x)
#define PWM_DMAC_ENAB   (1 <<31)
#define PWM_DMAC_PANIC(x)   ((x)<< 8)
#define PWM_FIFO   6
#define PWM_FREQS   18
#define PWM_LEN   0x28
#define PWM_RNG1   4
#define PWM_RNG2   8
#define PWM_STA   1
#define PWM_TIMER   (((PWM_BASE + PWM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS)
#define SER_CHECK_INITED   CHECK_INITED
#define SOFT_ERROR(x, format, arg...)
#define SPI_BASE   (pi_peri_phys + 0x00204000)
#define SPI_CLK   2
#define SPI_CS   0
#define SPI_CS0   0
#define SPI_CS1   1
#define SPI_CS2   2
#define SPI_CS_ADCS   (1<<11)
#define SPI_CS_CLEAR(x)   ((x)<<4)
#define SPI_CS_CS(x)   ((x)<<0)
#define SPI_CS_CSPOL(x)   ((x)<<6)
#define SPI_CS_CSPOLS(x)   ((x)<<21)
#define SPI_CS_DMA_LEN   (1<<24)
#define SPI_CS_DMAEN   (1<<8)
#define SPI_CS_DONE   (1<<16)
#define SPI_CS_INTD   (1<<9)
#define SPI_CS_INTR   (1<<10)
#define SPI_CS_LEN   (1<<13)
#define SPI_CS_LEN_LONG   (1<<25)
#define SPI_CS_MODE(x)   ((x)<<2)
#define SPI_CS_REN   (1<<12)
#define SPI_CS_RXD   (1<<17)
#define SPI_CS_RXF   (1<<20)
#define SPI_CS_RXR   (1<<19)
#define SPI_CS_TA   (1<<7)
#define SPI_CS_TXD   (1<<18)
#define SPI_DC   5
#define SPI_DC_RDREQ(x)   ((x)<<16)
#define SPI_DC_RPANIC(x)   ((x)<<24)
#define SPI_DC_TDREQ(x)   ((x)<<0)
#define SPI_DC_TPANIC(x)   ((x)<<8)
#define SPI_DLEN   3
#define SPI_FIFO   1
#define SPI_LEN   0x18
#define SPI_LTOH   4
#define SPI_MODE0   0
#define SPI_MODE1   1
#define SPI_MODE2   2
#define SPI_MODE3   3
#define SRX_BUF_SIZE   8192
#define STACK_SIZE   (256*1024)
#define SUPERCYCLE   800
#define SUPERLEVEL   20000
#define SYST_BASE   (pi_peri_phys + 0x00003000)
#define SYST_CHI   2
#define SYST_CLO   1
#define SYST_CS   0
#define SYST_LEN   0x1C
#define TCK_PER_IPAGE   2
#define THOUSAND   1000
#define TICKSLOTS   50
#define TIMED_DMA(x)   (DMA_DEST_DREQ | DMA_PERIPHERAL_MAPPING(x))
#define TIMER_ADD(a, b, result)
#define TIMER_SUB(a, b, result)
#define WCB_CHAIN_CBS   60
#define WCB_CHAIN_OOL   60
#define WCB_CNT_CBS   13
#define WCB_CNT_OOL   68
#define WCB_CNT_PER_PAGE   2
#define WCB_COUNTER_CBS   (WCB_CNT_PER_PAGE * WCB_CNT_CBS)
#define WCB_COUNTER_OOL   (WCB_CNT_PER_PAGE * WCB_CNT_OOL)
#define WCB_COUNTERS   (WCB_CNT_PER_PAGE * PI_WAVE_COUNT_PAGES)

Typedefs

typedef void(* callbk_t )()

Functions

static void _spiRXBits (char *buf, int pos, int bitlen, int msbf, uint32_t bits)
static uint32_t _spiTXBits (char *buf, int pos, int bitlen, int msbf)
static int addrAllowed (struct sockaddr *saddr)
static void alertEmit (gpioSample_t *sample, int numSamples, uint32_t changedBits, uint32_t eTick)
static void alertGlitchFilter (gpioSample_t *sample, int numSamples)
static void alertNoiseFilter (gpioSample_t *sample, int numSamples)
static void alertWdogCheck (gpioSample_t *sample, int numSamples)
int bbI2CClose (unsigned SDA)
int bbI2COpen (unsigned SDA, unsigned SCL, unsigned baud)
int bbI2CZip (unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
int bbSPIClose (unsigned CS)
int bbSPIOpen (unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spiFlags)
static void bbSPIStart (wfRx_t *w)
static void bbSPIStop (wfRx_t *w)
int bbSPIXfer (unsigned CS, char *inBuf, char *outBuf, unsigned count)
static uint8_t bbSPIXferByte (wfRx_t *w, char txByte)
void bscInit (int mode)
void bscTerm (int mode)
int bscXfer (bsc_xfer_t *xfer)
static int chainGetCB (int n)
static int chainGetCntCB (int counter)
static uint32_t chainGetCntVal (int counter, int slot)
static uint32_t chainGetCntValPadr (int counter, int slot)
static uint32_t chainGetValPadr (int n)
static void chainMakeCounter (unsigned counter, unsigned blklen, unsigned blocks, unsigned count, uint32_t repeat, uint32_t next)
static void chainSetCntVal (int counter, int slot, uint32_t value)
static void chainSetVal (int n, uint32_t val)
static int chooseBestClock (clkInf_t *clkInf, unsigned f, unsigned numc, unsigned *cf)
static void clear_CS (wfRx_t *w)
static void clear_SCL (wfRx_t *w)
static void clear_SCLK (wfRx_t *w)
static void clear_SDA (wfRx_t *w)
static void closeOrphanedNotifications (int slot, int fd)
static rawCbs_tdmaCB2adr (int pos)
static uint32_t dmaCbAdr (int pos)
static void dmaCbPrint (int pos)
static unsigned dmaCurrentSlot (unsigned pos)
static void dmaDelayCb (int b)
static uint32_t dmaGpioOffAdr (int pos)
static void dmaGpioOffCb (int b, int pos)
static uint32_t dmaGpioOnAdr (int pos)
static void dmaGpioOnCb (int b, int pos)
static void dmaInitCbs (void)
static unsigned dmaNowAtICB (void)
static int dmaNowAtOCB (void)
static uint32_t dmaPwmDataAdr (int pos)
static uint32_t dmaReadLevelsAdr (int pos)
static void dmaReadLevelsCb (int b, int pos)
static uint32_t dmaTickAdr (int pos)
static void dmaTickCb (int b, int pos)
int eventMonitor (unsigned handle, uint32_t bits)
int eventSetFunc (unsigned event, eventFunc_t f)
int eventSetFuncEx (unsigned event, eventFuncEx_t f, void *userdata)
int eventTrigger (unsigned event)
int fileApprove (char *filename)
int fileClose (unsigned handle)
int fileList (char *fpat, char *buf, unsigned count)
int fileOpen (char *file, unsigned mode)
int fileRead (unsigned handle, char *buf, unsigned count)
int fileSeek (unsigned handle, int32_t seekOffset, int seekFrom)
int fileWrite (unsigned handle, char *buf, unsigned count)
static void flushMemory (void)
int getBitInBytes (int bitPos, char *buf, int numBits)
int gpioCfgBufferSize (unsigned millis)
int gpioCfgClock (unsigned micros, unsigned peripheral, unsigned source)
int gpioCfgDMAchannel (unsigned DMAchannel)
int gpioCfgDMAchannels (unsigned primaryChannel, unsigned secondaryChannel)
uint32_t gpioCfgGetInternals (void)
int gpioCfgInterfaces (unsigned ifFlags)
int gpioCfgInternals (unsigned cfgWhat, unsigned cfgVal)
int gpioCfgMemAlloc (unsigned memAllocMode)
int gpioCfgNetAddr (int numSockAddr, uint32_t *sockAddr)
int gpioCfgPermissions (uint64_t updateMask)
int gpioCfgSetInternals (uint32_t cfgVal)
int gpioCfgSocketPort (unsigned port)
uint32_t gpioDelay (uint32_t micros)
int gpioDeleteScript (unsigned script_id)
int gpioGetMode (unsigned gpio)
int gpioGetPad (unsigned pad)
int gpioGetPWMdutycycle (unsigned gpio)
int gpioGetPWMfrequency (unsigned gpio)
int gpioGetPWMrange (unsigned gpio)
int gpioGetPWMrealRange (unsigned gpio)
int gpioGetServoPulsewidth (unsigned gpio)
int gpioGlitchFilter (unsigned gpio, unsigned steady)
int gpioHardwareClock (unsigned gpio, unsigned frequency)
int gpioHardwarePWM (unsigned gpio, unsigned frequency, unsigned dutycycle)
unsigned gpioHardwareRevision (void)
int gpioInitialise (void)
int gpioNoiseFilter (unsigned gpio, unsigned steady, unsigned active)
int gpioNotifyBegin (unsigned handle, uint32_t bits)
int gpioNotifyClose (unsigned handle)
int gpioNotifyOpen (void)
static int gpioNotifyOpenInBand (int fd)
int gpioNotifyOpenWithSize (int bufSize)
int gpioNotifyPause (unsigned handle)
int gpioPWM (unsigned gpio, unsigned val)
int gpioRead (unsigned gpio)
uint32_t gpioRead_Bits_0_31 (void)
uint32_t gpioRead_Bits_32_53 (void)
int gpioRunScript (unsigned script_id, unsigned numParam, uint32_t *param)
int gpioScriptStatus (unsigned script_id, uint32_t *param)
int gpioSerialRead (unsigned gpio, void *buf, size_t bufSize)
int gpioSerialReadClose (unsigned gpio)
int gpioSerialReadInvert (unsigned gpio, unsigned invert)
int gpioSerialReadOpen (unsigned gpio, unsigned baud, unsigned data_bits)
int gpioServo (unsigned gpio, unsigned val)
int gpioSetAlertFunc (unsigned gpio, gpioAlertFunc_t f)
int gpioSetAlertFuncEx (unsigned gpio, gpioAlertFuncEx_t f, void *userdata)
int gpioSetGetSamplesFunc (gpioGetSamplesFunc_t f, uint32_t bits)
int gpioSetGetSamplesFuncEx (gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata)
int gpioSetISRFunc (unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f)
int gpioSetISRFuncEx (unsigned gpio, unsigned edge, int timeout, gpioAlertFuncEx_t f, void *userdata)
int gpioSetMode (unsigned gpio, unsigned mode)
int gpioSetPad (unsigned pad, unsigned padStrength)
int gpioSetPullUpDown (unsigned gpio, unsigned pud)
int gpioSetPWMfrequency (unsigned gpio, unsigned frequency)
int gpioSetPWMrange (unsigned gpio, unsigned range)
int gpioSetSignalFunc (unsigned signum, gpioSignalFunc_t f)
int gpioSetSignalFuncEx (unsigned signum, gpioSignalFuncEx_t f, void *userdata)
int gpioSetTimerFunc (unsigned id, unsigned millis, gpioTimerFunc_t f)
int gpioSetTimerFuncEx (unsigned id, unsigned millis, gpioTimerFuncEx_t f, void *userdata)
int gpioSetWatchdog (unsigned gpio, unsigned timeout)
int gpioSleep (unsigned timetype, int seconds, int micros)
pthread_t * gpioStartThread (gpioThreadFunc_t f, void *userdata)
int gpioStopScript (unsigned script_id)
void gpioStopThread (pthread_t *pth)
int gpioStoreScript (char *script)
void gpioTerminate (void)
uint32_t gpioTick (void)
int gpioTime (unsigned timetype, int *seconds, int *micros)
int gpioTrigger (unsigned gpio, unsigned pulseLen, unsigned level)
int gpioUpdateScript (unsigned script_id, unsigned numParam, uint32_t *param)
unsigned gpioVersion (void)
int gpioWaveAddGeneric (unsigned numPulses, gpioPulse_t *pulses)
int gpioWaveAddNew (void)
int gpioWaveAddSerial (unsigned gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *bstr)
int gpioWaveChain (char *buf, unsigned bufSize)
int gpioWaveClear (void)
int gpioWaveCreate (void)
int gpioWaveDelete (unsigned wave_id)
int gpioWaveGetCbs (void)
int gpioWaveGetHighCbs (void)
int gpioWaveGetHighMicros (void)
int gpioWaveGetHighPulses (void)
int gpioWaveGetMaxCbs (void)
int gpioWaveGetMaxMicros (void)
int gpioWaveGetMaxPulses (void)
int gpioWaveGetMicros (void)
int gpioWaveGetPulses (void)
int gpioWaveTxAt (void)
int gpioWaveTxBusy (void)
int gpioWaveTxSend (unsigned wave_id, unsigned wave_mode)
int gpioWaveTxStart (unsigned wave_mode)
int gpioWaveTxStop (void)
int gpioWrite (unsigned gpio, unsigned level)
int gpioWrite_Bits_0_31_Clear (uint32_t bits)
int gpioWrite_Bits_0_31_Set (uint32_t bits)
int gpioWrite_Bits_32_53_Clear (uint32_t bits)
int gpioWrite_Bits_32_53_Set (uint32_t bits)
static void I2C_clock_stretch (wfRx_t *w)
static void I2C_delay (wfRx_t *w)
int i2cBlockProcessCall (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2cClose (unsigned handle)
static int I2CGetBit (wfRx_t *w)
static uint8_t I2CGetByte (wfRx_t *w, int nack)
int i2cOpen (unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags)
int i2cProcessCall (unsigned handle, unsigned reg, unsigned wVal)
static void I2CPutBit (wfRx_t *w, int bit)
static int I2CPutByte (wfRx_t *w, int byte)
int i2cReadBlockData (unsigned handle, unsigned reg, char *buf)
int i2cReadByte (unsigned handle)
int i2cReadByteData (unsigned handle, unsigned reg)
int i2cReadDevice (unsigned handle, char *buf, unsigned count)
int i2cReadI2CBlockData (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2cReadWordData (unsigned handle, unsigned reg)
int i2cSegments (unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs)
static void I2CStart (wfRx_t *w)
static void I2CStop (wfRx_t *w)
void i2cSwitchCombined (int setting)
int i2cWriteBlockData (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2cWriteByte (unsigned handle, unsigned bVal)
int i2cWriteByteData (unsigned handle, unsigned reg, unsigned bVal)
int i2cWriteDevice (unsigned handle, char *buf, unsigned count)
int i2cWriteI2CBlockData (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2cWriteQuick (unsigned handle, unsigned bit)
int i2cWriteWordData (unsigned handle, unsigned reg, unsigned wVal)
int i2cZip (unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
static int initAllocDMAMem (void)
static void initCheckLockFile (void)
static int initCheckPermitted (void)
static void initClearGlobals (void)
static void initClock (int mainClock)
static void initDMAgo (volatile uint32_t *dmaAddr, uint32_t cbAddr)
static int initGrabLockFile (void)
static void initHWClk (int clkCtl, int clkDiv, int clkSrc, int divI, int divF, int MASH)
int initInitialise (void)
static uint32_t * initMapMem (int fd, uint32_t addr, uint32_t len)
static int initMboxBlock (int block)
static int initPagemapBlock (int block)
static void initPCM (unsigned bits)
static int initPeripherals (void)
static void initPWM (unsigned bits)
static void initReleaseResources (void)
static int initZaps (int pmapFd, void *virtualBase, int basePage, int pages)
static int intEventSetFunc (unsigned event, void *f, int user, void *userdata)
static int intGpioSetAlertFunc (unsigned gpio, void *f, int user, void *userdata)
static int intGpioSetISRFunc (unsigned gpio, unsigned edge, int timeout, void *f, int user, void *userdata)
static int intGpioSetTimerFunc (unsigned id, unsigned millis, void *f, int user, void *userdata)
static void intNotifyBits (void)
static void intScriptBits (void)
static void intScriptEventBits (void)
static unsigned mbAllocateMemory (int fd, unsigned size, unsigned align, unsigned flags)
static void mbClose (int fd)
static int mbCreate (char *dev)
static int mbDMAAlloc (DMAMem_t *DMAMemP, unsigned size, uint32_t pi_mem_flag)
static void mbDMAFree (DMAMem_t *DMAMemP)
static unsigned mbLockMemory (int fd, unsigned handle)
static void * mbMapMem (unsigned base, unsigned size)
static int mbOpen (void)
static int mbProperty (int fd, void *buf)
static unsigned mbReleaseMemory (int fd, unsigned handle)
static unsigned mbUnlockMemory (int fd, unsigned handle)
static int mbUnmapMem (void *addr, unsigned size)
static int my_smbus_access (int fd, char rw, uint8_t cmd, int size, union my_smbus_data *data)
static char * myBuf2Str (unsigned count, char *buf)
static void myClearGpioOff (unsigned gpio, int pos)
static void myClearGpioOn (unsigned gpio, int pos)
static void myCreatePipe (char *name, int perm)
static int myDoCommand (uint32_t *p, unsigned bufSize, char *buf)
static uint32_t myGetLevel (int pos)
static uint32_t myGetTick (int pos)
static uint32_t myGpioDelay (uint32_t micros)
static int myGpioRead (unsigned gpio)
static void myGpioSetMode (unsigned gpio, unsigned mode)
static void myGpioSetPwm (unsigned gpio, int oldVal, int newVal)
static void myGpioSetServo (unsigned gpio, int oldVal, int newVal)
static void myGpioSleep (int seconds, int micros)
static void myGpioWrite (unsigned gpio, unsigned level)
static int myI2CGetPar (char *inBuf, int *inPos, int inLen, int *esc)
static void myLvsPageSlot (int pos, int *page, int *slot)
static void myOffPageSlot (int pos, int *page, int *slot)
int myPathBad (char *name)
static int myPermit (unsigned gpio)
int myScriptNameValid (char *name)
static void mySetGpioOff (unsigned gpio, int pos)
static void mySetGpioOn (unsigned gpio, int pos)
static void myTckPageSlot (int pos, int *page, int *slot)
static char * myTimeStamp ()
static void notifyMutex (int lock)
static void * pthAlertThread (void *x)
static void * pthFifoThread (void *x)
static void * pthISRThread (void *x)
static void * pthScript (void *x)
static void * pthSocketThread (void *x)
static void * pthSocketThreadHandler (void *fdC)
static void * pthTimerTick (void *x)
void putBitInBytes (int bitPos, char *buf, int bit)
void rawDumpScript (unsigned script_id)
void rawDumpWave (void)
int rawWaveAddGeneric (unsigned numIn1, rawWave_t *in1)
int rawWaveAddSPI (rawSPI_t *spi, unsigned offset, unsigned spiSS, char *buf, unsigned spiTxBits, unsigned spiBitFirst, unsigned spiBitLast, unsigned spiBits)
unsigned rawWaveCB (void)
rawCbs_trawWaveCBAdr (int cbNum)
uint32_t rawWaveGetIn (int pos)
uint32_t rawWaveGetOOL (int pos)
uint32_t rawWaveGetOut (int pos)
rawWaveInfo_t rawWaveInfo (int wave_id)
void rawWaveSetIn (int pos, uint32_t value)
void rawWaveSetOOL (int pos, uint32_t value)
void rawWaveSetOut (int pos, uint32_t value)
static int read_SDA (wfRx_t *w)
static int scrEvtWait (gpioScript_t *s, uint32_t bits)
static int scrPop (gpioScript_t *s, int *SP, int *S)
static void scrPush (gpioScript_t *s, int *SP, int *S, int val)
static void scrSwap (int *v1, int *v2)
static int scrSys (char *cmd, uint32_t p1, uint32_t p2)
static int scrWait (gpioScript_t *s, uint32_t bits)
int serClose (unsigned handle)
int serDataAvailable (unsigned handle)
int serOpen (char *tty, unsigned serBaud, unsigned serFlags)
int serRead (unsigned handle, char *buf, unsigned count)
int serReadByte (unsigned handle)
int serWrite (unsigned handle, char *buf, unsigned count)
int serWriteByte (unsigned handle, unsigned bVal)
static void set_CS (wfRx_t *w)
static void set_SCLK (wfRx_t *w)
static void set_SDA (wfRx_t *w)
int shell (char *scriptName, char *scriptString)
static void sigHandler (int signum)
static void sigSetHandler (void)
static void SPI_delay (wfRx_t *w)
static void spiACS (int channel, int on)
static int spiAnyOpen (uint32_t flags)
int spiClose (unsigned handle)
static void spiGo (unsigned speed, uint32_t flags, char *txBuf, char *rxBuf, unsigned count)
static void spiGoA (unsigned speed, uint32_t flags, char *txBuf, char *rxBuf, unsigned count)
static void spiGoS (unsigned speed, uint32_t flags, char *txBuf, char *rxBuf, unsigned count)
static void spiInit (uint32_t flags)
static void spinWhileStarting (void)
int spiOpen (unsigned spiChan, unsigned baud, unsigned spiFlags)
int spiRead (unsigned handle, char *buf, unsigned count)
static void spiTerm (uint32_t flags)
int spiWrite (unsigned handle, char *buf, unsigned count)
int spiXfer (unsigned handle, char *txBuf, char *rxBuf, unsigned count)
static void stopHardwarePWM (void)
static void switchFunctionOff (unsigned gpio)
void time_sleep (double seconds)
double time_time (void)
static int wave2Cbs (unsigned wave_mode, int *CB, int *BOOL, int *TOOL)
static void waveBitDelay (unsigned baud, unsigned bits, unsigned stops, unsigned *bitDelay)
static uint32_t waveCbPOadr (int pos)
static void waveCBsOOLs (int *numCBs, int *numBOOLs, int *numTOOLs)
static int waveDelayCBs (uint32_t delay)
static void waveOOLPageSlot (int pos, int *page, int *slot)
static uint32_t waveOOLPOadr (int pos)
static void waveRxBit (int gpio, int level, uint32_t tick)
static void waveRxSerial (wfRx_t *w, int level, uint32_t tick)
static void waveSetOOL (int pos, uint32_t OOL)
static void wfRx_lock (int i)
static void wfRx_unlock (int i)

Variables

unsigned alert_delays []
static volatile uint32_t alertBits = 0
static volatile uint32_t * auxReg = MAP_FAILED
static uint32_t bscFR
static volatile uint32_t * bscsReg = MAP_FAILED
static unsigned bufferBlocks
static unsigned bufferCycles
static const clkCfg_t clkCfg []
static const uint8_t clkDef [PI_MAX_GPIO+1]
static volatile uint32_t * clkReg = MAP_FAILED
static dmaPage_t ** dmaBus = MAP_FAILED
static dmaIPage_t ** dmaIBus = MAP_FAILED
static volatile uint32_t * dmaIn = MAP_FAILED
static dmaIPage_t ** dmaIVirt = MAP_FAILED
static DMAMem_tdmaMboxBlk = MAP_FAILED
static dmaOPage_t ** dmaOBus = MAP_FAILED
static volatile uint32_t * dmaOut = MAP_FAILED
static dmaOPage_t ** dmaOVirt = MAP_FAILED
static uintptr_t ** dmaPMapBlk = MAP_FAILED
static volatile uint32_t * dmaReg = MAP_FAILED
static dmaPage_t ** dmaVirt = MAP_FAILED
static eventAlert_t eventAlert [PI_MAX_EVENT+1]
static int fdLock = -1
static int fdMbox = -1
static int fdMem = -1
static int fdPmap = -1
static int fdSock = -1
static fileInfo_t fileInfo [PI_FILE_SLOTS]
static volatile uint32_t gFilterBits = 0
static gpioAlert_t gpioAlert [PI_MAX_USER_GPIO+1]
static volatile gpioCfg_t gpioCfg
static gpioGetSamples_t gpioGetSamples
static gpioInfo_t gpioInfo [PI_MAX_GPIO+1]
static gpioISR_t gpioISR [PI_MAX_GPIO+1]
static uint64_t gpioMask
static int gpioMaskSet = 0
static gpioNotify_t gpioNotify [PI_NOTIFY_SLOTS]
static volatile uint32_t * gpioReg = MAP_FAILED
static gpioScript_t gpioScript [PI_MAX_SCRIPTS]
static gpioSignal_t gpioSignal [PI_MAX_SIGNUM+1]
static volatile gpioStats_t gpioStats
static gpioTimer_t gpioTimer [PI_MAX_TIMER+1]
static uint32_t hw_clk_freq [3]
static uint32_t hw_pwm_duty [2]
static uint32_t hw_pwm_freq [2]
static uint32_t hw_pwm_real_range [2]
static i2cInfo_t i2cInfo [PI_I2C_SLOTS]
static FILE * inpFifo = NULL
static int libInitialised = 0
static struct timespec libStarted
static volatile uint32_t monitorBits = 0
static volatile uint32_t nFilterBits = 0
static volatile uint32_t notifyBits = 0
static int numSockNetAddr = 0
static unsigned old_mode_ace0
static unsigned old_mode_ace1
static unsigned old_mode_ace2
static unsigned old_mode_amiso
static unsigned old_mode_amosi
static unsigned old_mode_asclk
static unsigned old_mode_ce0
static unsigned old_mode_ce1
static unsigned old_mode_miso
static unsigned old_mode_mosi
static unsigned old_mode_sclk
static uint32_t old_spi_clk
static uint32_t old_spi_cntl0
static uint32_t old_spi_cntl1
static uint32_t old_spi_cs
static FILE * outFifo = NULL
static volatile uint32_t * padsReg = MAP_FAILED
static volatile uint32_t * pcmReg = MAP_FAILED
static volatile uint32_t pi_dram_bus = 0x40000000
static volatile uint32_t pi_mem_flag = 0x0C
static volatile uint32_t pi_peri_phys = 0x20000000
static volatile uint32_t piCores = 0
static pthread_t pthAlert
static int pthAlertRunning = PI_THREAD_NONE
static pthread_t pthFifo
static int pthFifoRunning = PI_THREAD_NONE
static pthread_t pthSocket
static int pthSocketRunning = PI_THREAD_NONE
static int PWMClockInited = 0
static const uint16_t pwmCycles [PWM_FREQS]
static const uint8_t PWMDef [PI_MAX_GPIO+1]
static int pwmFreq [PWM_FREQS]
static const uint16_t pwmRealRange [PWM_FREQS]
static volatile uint32_t * pwmReg = MAP_FAILED
static uint32_t reportedLevel = 0
static volatile int runState = PI_STARTING
static volatile uint32_t scriptBits = 0
static volatile uint32_t scriptEventBits = 0
static serInfo_t serInfo [PI_SER_SLOTS]
static uint32_t sockNetAddr [MAX_CONNECT_ADDRESSES]
static uint32_t spi_dummy
static spiInfo_t spiInfo [PI_SPI_SLOTS]
static volatile uint32_t * spiReg = MAP_FAILED
static volatile uint32_t * systReg = MAP_FAILED
static int waveClockInited = 0
static uint32_t * waveEndPtr = NULL
static rawWaveInfo_t waveInfo [PI_MAX_WAVES]
static int waveOutBotCB = PI_WAVE_COUNT_PAGES*CBS_PER_OPAGE
static int waveOutBotOOL = PI_WAVE_COUNT_PAGES*OOL_PER_OPAGE
static int waveOutCount = 0
static int waveOutTopOOL = NUM_WAVE_OOL
static volatile uint32_t wdogBits = 0
static rawWave_t wf [3][PI_WAVE_MAX_PULSES]
static int wfc [3] = {0, 0, 0}
static int wfcur = 0
static wfRx_t wfRx [PI_MAX_USER_GPIO+1]
static wfStats_t wfStats

Define Documentation

#define _GNU_SOURCE

Definition at line 32 of file pigpio.c.

#define AUX_BASE   (pi_peri_phys + 0x00215000)

Definition at line 302 of file pigpio.c.

#define AUX_ENABLES   1

Definition at line 585 of file pigpio.c.

#define AUX_IRQ   0

Definition at line 584 of file pigpio.c.

#define AUX_LEN   0xD8

Definition at line 314 of file pigpio.c.

#define AUX_MU_BAUD_REG   26

Definition at line 597 of file pigpio.c.

#define AUX_MU_CNTL_REG   24

Definition at line 595 of file pigpio.c.

#define AUX_MU_IER_REG   17

Definition at line 588 of file pigpio.c.

#define AUX_MU_IIR_REG   18

Definition at line 589 of file pigpio.c.

#define AUX_MU_IO_REG   16

Definition at line 587 of file pigpio.c.

#define AUX_MU_LCR_REG   19

Definition at line 590 of file pigpio.c.

#define AUX_MU_LSR_REG   21

Definition at line 592 of file pigpio.c.

#define AUX_MU_MCR_REG   20

Definition at line 591 of file pigpio.c.

#define AUX_MU_MSR_REG   22

Definition at line 593 of file pigpio.c.

#define AUX_MU_SCRATCH   23

Definition at line 594 of file pigpio.c.

#define AUX_MU_STAT_REG   25

Definition at line 596 of file pigpio.c.

#define AUX_SPI0_CNTL0_REG   32

Definition at line 599 of file pigpio.c.

#define AUX_SPI0_CNTL1_REG   33

Definition at line 600 of file pigpio.c.

#define AUX_SPI0_IO_REG   40

Definition at line 604 of file pigpio.c.

#define AUX_SPI0_PEEK_REG   35

Definition at line 602 of file pigpio.c.

#define AUX_SPI0_STAT_REG   34

Definition at line 601 of file pigpio.c.

#define AUX_SPI0_TX_HOLD   44

Definition at line 605 of file pigpio.c.

#define AUX_SPI1_CNTL0_REG   48

Definition at line 607 of file pigpio.c.

#define AUX_SPI1_CNTL1_REG   49

Definition at line 608 of file pigpio.c.

#define AUX_SPI1_IO_REG   56

Definition at line 612 of file pigpio.c.

#define AUX_SPI1_PEEK_REG   51

Definition at line 610 of file pigpio.c.

#define AUX_SPI1_STAT_REG   50

Definition at line 609 of file pigpio.c.

#define AUX_SPI1_TX_HOLD   60

Definition at line 613 of file pigpio.c.

#define AUXENB_SPI1   (1<<1)

Definition at line 616 of file pigpio.c.

#define AUXENB_SPI2   (1<<2)

Definition at line 615 of file pigpio.c.

#define AUXENB_UART   (1<<0)

Definition at line 617 of file pigpio.c.

#define AUXSPI_CNTL0_CLR_FIFOS   (1<<9)

Definition at line 627 of file pigpio.c.

#define AUXSPI_CNTL0_CS (   x)    ((x)<<17)

Definition at line 620 of file pigpio.c.

#define AUXSPI_CNTL0_DOUT_HOLD (   x)    ((x)<<12)

Definition at line 624 of file pigpio.c.

#define AUXSPI_CNTL0_ENABLE   (1<<11)

Definition at line 625 of file pigpio.c.

#define AUXSPI_CNTL0_IN_RISING (   x)    ((x)<<10)

Definition at line 626 of file pigpio.c.

#define AUXSPI_CNTL0_INVERT_CLK (   x)    ((x)<<7)

Definition at line 629 of file pigpio.c.

#define AUXSPI_CNTL0_MSB_FIRST (   x)    ((x)<<6)

Definition at line 630 of file pigpio.c.

#define AUXSPI_CNTL0_OUT_RISING (   x)    ((x)<<8)

Definition at line 628 of file pigpio.c.

#define AUXSPI_CNTL0_POSTINP   (1<<16)

Definition at line 621 of file pigpio.c.

#define AUXSPI_CNTL0_SHIFT_LEN (   x)    ((x)<<0)

Definition at line 631 of file pigpio.c.

#define AUXSPI_CNTL0_SPEED (   x)    ((x)<<20)

Definition at line 619 of file pigpio.c.

#define AUXSPI_CNTL0_VAR_CS   (1<<15)

Definition at line 622 of file pigpio.c.

#define AUXSPI_CNTL0_VAR_WIDTH   (1<<14)

Definition at line 623 of file pigpio.c.

#define AUXSPI_CNTL1_CS_HIGH (   x)    ((x)<<8)

Definition at line 633 of file pigpio.c.

#define AUXSPI_CNTL1_DONE_IRQ   (1<<6)

Definition at line 635 of file pigpio.c.

#define AUXSPI_CNTL1_KEEP_INPUT   (1<<0)

Definition at line 637 of file pigpio.c.

#define AUXSPI_CNTL1_MSB_FIRST (   x)    ((x)<<1)

Definition at line 636 of file pigpio.c.

#define AUXSPI_CNTL1_TX_IRQ   (1<<7)

Definition at line 634 of file pigpio.c.

#define AUXSPI_STAT_BITS (   x)    ((x)<<0)

Definition at line 645 of file pigpio.c.

#define AUXSPI_STAT_BUSY   (1<<6)

Definition at line 644 of file pigpio.c.

#define AUXSPI_STAT_RX_EMPTY   (1<<7)

Definition at line 643 of file pigpio.c.

#define AUXSPI_STAT_RX_FIFO (   x)    ((x)<<20)

Definition at line 640 of file pigpio.c.

#define AUXSPI_STAT_TX_EMPTY   (1<<9)

Definition at line 642 of file pigpio.c.

#define AUXSPI_STAT_TX_FIFO (   x)    ((x)<<28)

Definition at line 639 of file pigpio.c.

#define AUXSPI_STAT_TX_FULL   (1<<10)

Definition at line 641 of file pigpio.c.

#define BANK   (gpio>>5)

Definition at line 195 of file pigpio.c.

#define BCM_PASSWD   (0x5A<<24)

Definition at line 486 of file pigpio.c.

#define BILLION   1000000000

Definition at line 193 of file pigpio.c.

#define BIT   (1<<(gpio&0x1F))

Definition at line 197 of file pigpio.c.

Definition at line 726 of file pigpio.c.

#define BPD   4

Definition at line 771 of file pigpio.c.

#define BSCS_BASE   (pi_peri_phys + 0x00214000)

Definition at line 303 of file pigpio.c.

#define BSCS_LEN   0x40

Definition at line 315 of file pigpio.c.

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

Definition at line 829 of file pigpio.c.

#define CBS_PER_CYCLE   ((PULSE_PER_CYCLE*3)+2)

Definition at line 719 of file pigpio.c.

#define CBS_PER_IPAGE   117

Definition at line 687 of file pigpio.c.

#define CBS_PER_OPAGE   118

Definition at line 694 of file pigpio.c.

#define CHECK_INITED
Value:
do                                                              \
   {                                                               \
      if (!libInitialised)                                         \
      {                                                            \
         DBG(DBG_ALWAYS,                                           \
           "pigpio uninitialised, call gpioInitialise()");         \
         return PI_NOT_INITIALISED;                                \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 219 of file pigpio.c.

Value:
do                                                              \
   {                                                               \
      if (!libInitialised)                                         \
      {                                                            \
         DBG(DBG_ALWAYS,                                           \
           "pigpio uninitialised, call gpioInitialise()");         \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 243 of file pigpio.c.

Value:
do                                                              \
   {                                                               \
      if (!libInitialised)                                         \
      {                                                            \
         DBG(DBG_ALWAYS,                                           \
           "pigpio uninitialised, call gpioInitialise()");         \
         return (NULL);                                            \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 231 of file pigpio.c.

Value:
do                                                              \
   {                                                               \
      if (libInitialised)                                          \
      {                                                            \
         DBG(DBG_ALWAYS,                                           \
            "pigpio initialised, call gpioTerminate()");           \
         return PI_INITIALISED;                                    \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 254 of file pigpio.c.

#define CLK_BASE   (pi_peri_phys + 0x00101000)

Definition at line 304 of file pigpio.c.

#define CLK_CTL_BUSY   (1 <<7)

Definition at line 489 of file pigpio.c.

#define CLK_CTL_ENAB   (1 <<4)

Definition at line 491 of file pigpio.c.

#define CLK_CTL_KILL   (1 <<5)

Definition at line 490 of file pigpio.c.

#define CLK_CTL_MASH (   x)    ((x)<<9)

Definition at line 488 of file pigpio.c.

#define CLK_CTL_SRC (   x)    ((x)<<0)

Definition at line 492 of file pigpio.c.

#define CLK_CTL_SRC_OSC   1

Definition at line 496 of file pigpio.c.

#define CLK_CTL_SRC_PLLD   6

Definition at line 497 of file pigpio.c.

#define CLK_DIV_DIVF (   x)    ((x)<< 0)

Definition at line 503 of file pigpio.c.

#define CLK_DIV_DIVI (   x)    ((x)<<12)

Definition at line 502 of file pigpio.c.

#define CLK_GP0_CTL   28

Definition at line 505 of file pigpio.c.

#define CLK_GP0_DIV   29

Definition at line 506 of file pigpio.c.

#define CLK_GP1_CTL   30

Definition at line 507 of file pigpio.c.

#define CLK_GP1_DIV   31

Definition at line 508 of file pigpio.c.

#define CLK_GP2_CTL   32

Definition at line 509 of file pigpio.c.

#define CLK_GP2_DIV   33

Definition at line 510 of file pigpio.c.

#define CLK_LEN   0xA8

Definition at line 316 of file pigpio.c.

#define CLK_OSC_FREQ   19200000

Definition at line 499 of file pigpio.c.

#define CLK_PCMCTL   38

Definition at line 512 of file pigpio.c.

#define CLK_PCMDIV   39

Definition at line 513 of file pigpio.c.

#define CLK_PLLD_FREQ   500000000

Definition at line 500 of file pigpio.c.

#define CLK_PWMCTL   40

Definition at line 515 of file pigpio.c.

#define CLK_PWMDIV   41

Definition at line 516 of file pigpio.c.

#define CLK_SRCS   2

Definition at line 494 of file pigpio.c.

#define CYCLES_PER_BLOCK   80

Definition at line 682 of file pigpio.c.

#define DBG (   level,
  format,
  arg... 
)    DO_DBG(level, format, ## arg)

Definition at line 200 of file pigpio.c.

#define DBG_ALWAYS   0

Definition at line 657 of file pigpio.c.

#define DBG_DMACBS   2

Definition at line 659 of file pigpio.c.

#define DBG_FAST_TICK   7

Definition at line 664 of file pigpio.c.

#define DBG_INTERNAL   5

Definition at line 662 of file pigpio.c.

#define DBG_MAX_LEVEL   8

Definition at line 665 of file pigpio.c.

#define DBG_MIN_LEVEL   0

Definition at line 656 of file pigpio.c.

#define DBG_SCRIPT   3

Definition at line 660 of file pigpio.c.

#define DBG_SLOW_TICK   6

Definition at line 663 of file pigpio.c.

#define DBG_STARTUP   1

Definition at line 658 of file pigpio.c.

#define DBG_USER   4

Definition at line 661 of file pigpio.c.

#define DEFAULT_PWM_IDX   5

Definition at line 776 of file pigpio.c.

#define DMA15_BASE   (pi_peri_phys + 0x00E05000)

Definition at line 306 of file pigpio.c.

#define DMA_ACTIVATE   (1<< 0)

Definition at line 369 of file pigpio.c.

#define DMA_BASE   (pi_peri_phys + 0x00007000)

Definition at line 305 of file pigpio.c.

#define DMA_BURST_LENGTH (   x)    ((x)<<12)

Definition at line 374 of file pigpio.c.

#define DMA_CHANNEL_RESET   (1<<31)

Definition at line 363 of file pigpio.c.

#define DMA_CONBLK_AD   1

Definition at line 359 of file pigpio.c.

#define DMA_CS   0

Definition at line 358 of file pigpio.c.

#define DMA_DEBUG   8

Definition at line 360 of file pigpio.c.

#define DMA_DEBUG_FIFO_ERR   (1<<1)

Definition at line 386 of file pigpio.c.

#define DMA_DEBUG_RD_LST_NOT_SET_ERR   (1<<0)

Definition at line 387 of file pigpio.c.

#define DMA_DEBUG_READ_ERR   (1<<2)

Definition at line 385 of file pigpio.c.

#define DMA_DEST_DREQ   (1<< 6)

Definition at line 380 of file pigpio.c.

#define DMA_DEST_IGNORE   (1<< 7)

Definition at line 379 of file pigpio.c.

#define DMA_DEST_INC   (1<< 4)

Definition at line 382 of file pigpio.c.

#define DMA_DEST_WIDTH   (1<< 5)

Definition at line 381 of file pigpio.c.

#define DMA_ENABLE   (0xFF0/4)

Definition at line 325 of file pigpio.c.

#define DMA_END_FLAG   (1<< 1)

Definition at line 368 of file pigpio.c.

#define DMA_INTERRUPT_STATUS   (1<< 2)

Definition at line 367 of file pigpio.c.

#define DMA_LEN   0x1000 /* allow access to all channels */

Definition at line 317 of file pigpio.c.

#define DMA_LITE_FIRST   7

Definition at line 389 of file pigpio.c.

#define DMA_LITE_MAX   0xfffc

Definition at line 390 of file pigpio.c.

#define DMA_NO_WIDE_BURSTS   (1<<26)

Definition at line 372 of file pigpio.c.

#define DMA_PANIC_PRIORITY (   x)    ((x)<<20)

Definition at line 365 of file pigpio.c.

#define DMA_PERIPHERAL_MAPPING (   x)    ((x)<<16)

Definition at line 373 of file pigpio.c.

#define DMA_PRIORITY (   x)    ((x)<<16)

Definition at line 366 of file pigpio.c.

#define DMA_SRC_DREQ   (1<<10)

Definition at line 376 of file pigpio.c.

#define DMA_SRC_IGNORE   (1<<11)

Definition at line 375 of file pigpio.c.

#define DMA_SRC_INC   (1<< 8)

Definition at line 378 of file pigpio.c.

#define DMA_SRC_WIDTH   (1<< 9)

Definition at line 377 of file pigpio.c.

#define DMA_WAIT_ON_WRITES   (1<<28)

Definition at line 364 of file pigpio.c.

#define DMA_WAIT_RESP   (1<< 3)

Definition at line 383 of file pigpio.c.

Definition at line 728 of file pigpio.c.

Definition at line 730 of file pigpio.c.

#define DO_DBG (   level,
  format,
  arg... 
)
Value:
{                                                               \
      if ((gpioCfg.dbgLevel >= level) &&                           \
         (!(gpioCfg.internals & PI_CFG_NOSIGHANDLER)))             \
         fprintf(stderr, "%s %s: " format "\n" ,                   \
            myTimeStamp(), __FUNCTION__ , ## arg);                 \
   }

Definition at line 205 of file pigpio.c.

#define FLUSH_PAGES   1024

Definition at line 820 of file pigpio.c.

#define GPAFEN0   34

Definition at line 351 of file pigpio.c.

#define GPAFEN1   35

Definition at line 352 of file pigpio.c.

#define GPAREN0   31

Definition at line 349 of file pigpio.c.

#define GPAREN1   32

Definition at line 350 of file pigpio.c.

#define GPCLR0   10

Definition at line 332 of file pigpio.c.

#define GPCLR1   11

Definition at line 333 of file pigpio.c.

#define GPEDS0   16

Definition at line 338 of file pigpio.c.

#define GPEDS1   17

Definition at line 339 of file pigpio.c.

#define GPFEN0   22

Definition at line 343 of file pigpio.c.

#define GPFEN1   23

Definition at line 344 of file pigpio.c.

#define GPFSEL0   0

Definition at line 327 of file pigpio.c.

#define GPHEN0   25

Definition at line 345 of file pigpio.c.

#define GPHEN1   26

Definition at line 346 of file pigpio.c.

#define GPIO_BASE   (pi_peri_phys + 0x00200000)

Definition at line 307 of file pigpio.c.

#define GPIO_HW_CLK   4

Definition at line 671 of file pigpio.c.

#define GPIO_HW_PWM   5

Definition at line 672 of file pigpio.c.

#define GPIO_I2C   7

Definition at line 674 of file pigpio.c.

#define GPIO_LEN   0xB4

Definition at line 318 of file pigpio.c.

#define GPIO_PWM   2

Definition at line 669 of file pigpio.c.

#define GPIO_SERVO   3

Definition at line 670 of file pigpio.c.

#define GPIO_SPI   6

Definition at line 673 of file pigpio.c.

#define GPIO_UNDEFINED   0

Definition at line 667 of file pigpio.c.

#define GPIO_WRITE   1

Definition at line 668 of file pigpio.c.

#define GPLEN0   28

Definition at line 347 of file pigpio.c.

#define GPLEN1   29

Definition at line 348 of file pigpio.c.

#define GPLEV0   13

Definition at line 335 of file pigpio.c.

#define GPLEV1   14

Definition at line 336 of file pigpio.c.

#define GPPUD   37

Definition at line 354 of file pigpio.c.

#define GPPUDCLK0   38

Definition at line 355 of file pigpio.c.

#define GPPUDCLK1   39

Definition at line 356 of file pigpio.c.

#define GPREN0   19

Definition at line 341 of file pigpio.c.

#define GPREN1   20

Definition at line 342 of file pigpio.c.

#define GPSET0   7

Definition at line 329 of file pigpio.c.

#define GPSET1   8

Definition at line 330 of file pigpio.c.

#define LVS_PER_IPAGE   38

Definition at line 688 of file pigpio.c.

#define MAX_EMITS   (PIPE_BUF / sizeof(gpioReport_t))

Definition at line 778 of file pigpio.c.

#define MAX_REPORT   250

Definition at line 773 of file pigpio.c.

#define MAX_SAMPLE   4000

Definition at line 774 of file pigpio.c.

#define MB_ALLOCATE_MEMORY_TAG   0x3000C

Definition at line 834 of file pigpio.c.

#define MB_DEV1   "/dev/vcio"

Definition at line 826 of file pigpio.c.

#define MB_DEV2   "/dev/pigpio-mb"

Definition at line 827 of file pigpio.c.

#define MB_DEV_MAJOR   100

Definition at line 822 of file pigpio.c.

#define MB_END_TAG   0

Definition at line 831 of file pigpio.c.

#define MB_IOCTL   _IOWR(MB_DEV_MAJOR, 0, char *)

Definition at line 824 of file pigpio.c.

#define MB_LOCK_MEMORY_TAG   0x3000D

Definition at line 835 of file pigpio.c.

#define MB_PROCESS_REQUEST   0

Definition at line 832 of file pigpio.c.

#define MB_RELEASE_MEMORY_TAG   0x3000F

Definition at line 837 of file pigpio.c.

#define MB_UNLOCK_MEMORY_TAG   0x3000E

Definition at line 836 of file pigpio.c.

#define MILLION   1000000

Definition at line 192 of file pigpio.c.

Definition at line 649 of file pigpio.c.

Definition at line 721 of file pigpio.c.

Definition at line 733 of file pigpio.c.

Definition at line 732 of file pigpio.c.

#define OFF_PER_IPAGE   38

Definition at line 689 of file pigpio.c.

#define ON_PER_IPAGE   2

Definition at line 691 of file pigpio.c.

#define OOL_PER_OPAGE   79

Definition at line 695 of file pigpio.c.

#define PAD_PER_IPAGE   7

Definition at line 692 of file pigpio.c.

#define PADS_BASE   (pi_peri_phys + 0x00100000)

Definition at line 308 of file pigpio.c.

#define PADS_LEN   0x38

Definition at line 319 of file pigpio.c.

#define PAGE_SIZE   4096

Definition at line 678 of file pigpio.c.

#define PAGES_PER_BLOCK   53

Definition at line 685 of file pigpio.c.

#define PCM_BASE   (pi_peri_phys + 0x00203000)

Definition at line 309 of file pigpio.c.

#define PCM_CS   0

Definition at line 413 of file pigpio.c.

#define PCM_CS_DMAEN   (1 <<9)

Definition at line 428 of file pigpio.c.

#define PCM_CS_EN   (1 <<0)

Definition at line 435 of file pigpio.c.

#define PCM_CS_RXCLR   (1 <<4)

Definition at line 431 of file pigpio.c.

#define PCM_CS_RXERR   (1 <<16)

Definition at line 426 of file pigpio.c.

#define PCM_CS_RXON   (1 <<1)

Definition at line 434 of file pigpio.c.

#define PCM_CS_RXSEX   (1 <<23)

Definition at line 425 of file pigpio.c.

#define PCM_CS_RXTHR (   x)    ((x)<<7)

Definition at line 429 of file pigpio.c.

#define PCM_CS_STBY   (1 <<25)

Definition at line 423 of file pigpio.c.

#define PCM_CS_SYNC   (1 <<24)

Definition at line 424 of file pigpio.c.

#define PCM_CS_TXCLR   (1 <<3)

Definition at line 432 of file pigpio.c.

#define PCM_CS_TXERR   (1 <<15)

Definition at line 427 of file pigpio.c.

#define PCM_CS_TXON   (1 <<2)

Definition at line 433 of file pigpio.c.

#define PCM_CS_TXTHR (   x)    ((x)<<5)

Definition at line 430 of file pigpio.c.

#define PCM_DREQ   5

Definition at line 418 of file pigpio.c.

#define PCM_DREQ_RX_PANIC (   x)    ((x)<<16)

Definition at line 468 of file pigpio.c.

#define PCM_DREQ_RX_REQ_L (   x)    ((x)<< 0)

Definition at line 470 of file pigpio.c.

#define PCM_DREQ_TX_PANIC (   x)    ((x)<<24)

Definition at line 467 of file pigpio.c.

#define PCM_DREQ_TX_REQ_L (   x)    ((x)<< 8)

Definition at line 469 of file pigpio.c.

#define PCM_FIFO   1

Definition at line 414 of file pigpio.c.

#define PCM_GRAY   8

Definition at line 421 of file pigpio.c.

#define PCM_GRAY_CLR   (1<<1)

Definition at line 483 of file pigpio.c.

#define PCM_GRAY_EN   (1<<0)

Definition at line 484 of file pigpio.c.

#define PCM_GRAY_FLUSH   (1<<2)

Definition at line 482 of file pigpio.c.

#define PCM_INTEN   6

Definition at line 419 of file pigpio.c.

#define PCM_INTEN_RXERR   (1<<3)

Definition at line 472 of file pigpio.c.

#define PCM_INTEN_RXR   (1<<1)

Definition at line 474 of file pigpio.c.

#define PCM_INTEN_TXERR   (1<<2)

Definition at line 473 of file pigpio.c.

#define PCM_INTEN_TXW   (1<<0)

Definition at line 475 of file pigpio.c.

#define PCM_INTSTC   7

Definition at line 420 of file pigpio.c.

#define PCM_INTSTC_RXERR   (1<<3)

Definition at line 477 of file pigpio.c.

#define PCM_INTSTC_RXR   (1<<1)

Definition at line 479 of file pigpio.c.

#define PCM_INTSTC_TXERR   (1<<2)

Definition at line 478 of file pigpio.c.

#define PCM_INTSTC_TXW   (1<<0)

Definition at line 480 of file pigpio.c.

#define PCM_LEN   0x24

Definition at line 320 of file pigpio.c.

#define PCM_MODE   2

Definition at line 415 of file pigpio.c.

#define PCM_MODE_CLK_DIS   (1 <<28)

Definition at line 437 of file pigpio.c.

#define PCM_MODE_CLKI   (1 <<22)

Definition at line 443 of file pigpio.c.

#define PCM_MODE_CLKM   (1 <<23)

Definition at line 442 of file pigpio.c.

#define PCM_MODE_FLEN (   x)    ((x)<<10)

Definition at line 446 of file pigpio.c.

#define PCM_MODE_FRXP   (1 <<25)

Definition at line 440 of file pigpio.c.

#define PCM_MODE_FSI   (1 <<20)

Definition at line 445 of file pigpio.c.

#define PCM_MODE_FSLEN (   x)    ((x)<< 0)

Definition at line 447 of file pigpio.c.

#define PCM_MODE_FSM   (1 <<21)

Definition at line 444 of file pigpio.c.

#define PCM_MODE_FTXP   (1 <<24)

Definition at line 441 of file pigpio.c.

#define PCM_MODE_PDME   (1 <<26)

Definition at line 439 of file pigpio.c.

#define PCM_MODE_PDMN   (1 <<27)

Definition at line 438 of file pigpio.c.

#define PCM_RXC   3

Definition at line 416 of file pigpio.c.

#define PCM_RXC_CH1EN   (1 <<30)

Definition at line 450 of file pigpio.c.

#define PCM_RXC_CH1POS (   x)    ((x)<<20)

Definition at line 451 of file pigpio.c.

#define PCM_RXC_CH1WEX   (1 <<31)

Definition at line 449 of file pigpio.c.

#define PCM_RXC_CH1WID (   x)    ((x)<<16)

Definition at line 452 of file pigpio.c.

#define PCM_RXC_CH2EN   (1 <<14)

Definition at line 454 of file pigpio.c.

#define PCM_RXC_CH2POS (   x)    ((x)<< 4)

Definition at line 455 of file pigpio.c.

#define PCM_RXC_CH2WEX   (1 <<15)

Definition at line 453 of file pigpio.c.

#define PCM_RXC_CH2WID (   x)    ((x)<< 0)

Definition at line 456 of file pigpio.c.

#define PCM_TIMER   (((PCM_BASE + PCM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS)

Definition at line 653 of file pigpio.c.

#define PCM_TXC   4

Definition at line 417 of file pigpio.c.

#define PCM_TXC_CH1EN   (1 <<30)

Definition at line 459 of file pigpio.c.

#define PCM_TXC_CH1POS (   x)    ((x)<<20)

Definition at line 460 of file pigpio.c.

#define PCM_TXC_CH1WEX   (1 <<31)

Definition at line 458 of file pigpio.c.

#define PCM_TXC_CH1WID (   x)    ((x)<<16)

Definition at line 461 of file pigpio.c.

#define PCM_TXC_CH2EN   (1 <<14)

Definition at line 463 of file pigpio.c.

#define PCM_TXC_CH2POS (   x)    ((x)<< 4)

Definition at line 464 of file pigpio.c.

#define PCM_TXC_CH2WEX   (1 <<15)

Definition at line 462 of file pigpio.c.

#define PCM_TXC_CH2WID (   x)    ((x)<< 0)

Definition at line 465 of file pigpio.c.

#define PI_ASPI_CE0   18

Definition at line 575 of file pigpio.c.

#define PI_ASPI_CE1   17

Definition at line 576 of file pigpio.c.

#define PI_ASPI_CE2   16

Definition at line 577 of file pigpio.c.

#define PI_ASPI_MISO   19

Definition at line 578 of file pigpio.c.

#define PI_ASPI_MOSI   20

Definition at line 579 of file pigpio.c.

#define PI_ASPI_SCLK   21

Definition at line 580 of file pigpio.c.

#define PI_ENDING   2

Definition at line 869 of file pigpio.c.

#define PI_FILE_CLOSED   0

Definition at line 749 of file pigpio.c.

#define PI_FILE_OPENED   2

Definition at line 751 of file pigpio.c.

#define PI_FILE_RESERVED   1

Definition at line 750 of file pigpio.c.

#define PI_I2C_CLOSED   0

Definition at line 737 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_PROC_CALL   0x00800000

Definition at line 812 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_QUICK   0x00010000

Definition at line 805 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_READ_BLOCK_DATA   0x01000000

Definition at line 813 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_READ_BYTE   0x00020000

Definition at line 806 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_READ_BYTE_DATA   0x00080000

Definition at line 808 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_READ_I2C_BLOCK   0x04000000

Definition at line 815 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_READ_WORD_DATA   0x00200000

Definition at line 810 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_WRITE_BLOCK_DATA   0x02000000

Definition at line 814 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_WRITE_BYTE   0x00040000

Definition at line 807 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_WRITE_BYTE_DATA   0x00100000

Definition at line 809 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_WRITE_I2C_BLOCK   0x08000000

Definition at line 816 of file pigpio.c.

#define PI_I2C_FUNC_SMBUS_WRITE_WORD_DATA   0x00400000

Definition at line 811 of file pigpio.c.

#define PI_I2C_FUNCS   0x0705

Definition at line 785 of file pigpio.c.

#define PI_I2C_OPENED   2

Definition at line 739 of file pigpio.c.

#define PI_I2C_RDWR   0x0707

Definition at line 786 of file pigpio.c.

#define PI_I2C_RESERVED   1

Definition at line 738 of file pigpio.c.

#define PI_I2C_RETRIES   0x0701

Definition at line 782 of file pigpio.c.

#define PI_I2C_SLAVE   0x0703

Definition at line 784 of file pigpio.c.

#define PI_I2C_SMBUS   0x0720

Definition at line 787 of file pigpio.c.

#define PI_I2C_SMBUS_BLOCK_DATA   5

Definition at line 797 of file pigpio.c.

#define PI_I2C_SMBUS_BLOCK_MAX   32

Definition at line 802 of file pigpio.c.

Definition at line 799 of file pigpio.c.

#define PI_I2C_SMBUS_BYTE   1

Definition at line 793 of file pigpio.c.

#define PI_I2C_SMBUS_BYTE_DATA   2

Definition at line 794 of file pigpio.c.

Definition at line 798 of file pigpio.c.

Definition at line 800 of file pigpio.c.

#define PI_I2C_SMBUS_I2C_BLOCK_MAX   32

Definition at line 803 of file pigpio.c.

#define PI_I2C_SMBUS_PROC_CALL   4

Definition at line 796 of file pigpio.c.

#define PI_I2C_SMBUS_QUICK   0

Definition at line 792 of file pigpio.c.

#define PI_I2C_SMBUS_READ   1

Definition at line 789 of file pigpio.c.

#define PI_I2C_SMBUS_WORD_DATA   3

Definition at line 795 of file pigpio.c.

#define PI_I2C_SMBUS_WRITE   0

Definition at line 790 of file pigpio.c.

#define PI_I2C_TIMEOUT   0x0702

Definition at line 783 of file pigpio.c.

#define PI_MASH_MAX_FREQ   23800000

Definition at line 818 of file pigpio.c.

#define PI_MAX_PATH   512

Definition at line 875 of file pigpio.c.

#define PI_NOTIFY_CLOSED   0

Definition at line 753 of file pigpio.c.

#define PI_NOTIFY_CLOSING   2

Definition at line 755 of file pigpio.c.

#define PI_NOTIFY_OPENED   3

Definition at line 756 of file pigpio.c.

#define PI_NOTIFY_PAUSED   5

Definition at line 758 of file pigpio.c.

#define PI_NOTIFY_RESERVED   1

Definition at line 754 of file pigpio.c.

#define PI_NOTIFY_RUNNING   4

Definition at line 757 of file pigpio.c.

#define PI_PERI_BUS   0x7E000000

Definition at line 300 of file pigpio.c.

#define PI_RUNNING   1

Definition at line 868 of file pigpio.c.

#define PI_SCRIPT_DELETE   2

Definition at line 846 of file pigpio.c.

#define PI_SCRIPT_DYING   3

Definition at line 842 of file pigpio.c.

#define PI_SCRIPT_FREE   0

Definition at line 839 of file pigpio.c.

#define PI_SCRIPT_HALT   0

Definition at line 844 of file pigpio.c.

#define PI_SCRIPT_IN_USE   2

Definition at line 841 of file pigpio.c.

#define PI_SCRIPT_RESERVED   1

Definition at line 840 of file pigpio.c.

#define PI_SCRIPT_RUN   1

Definition at line 845 of file pigpio.c.

#define PI_SCRIPT_STACK_SIZE   256

Definition at line 848 of file pigpio.c.

#define PI_SER_CLOSED   0

Definition at line 745 of file pigpio.c.

#define PI_SER_OPENED   2

Definition at line 747 of file pigpio.c.

#define PI_SER_RESERVED   1

Definition at line 746 of file pigpio.c.

#define PI_SPI_CE0   8

Definition at line 567 of file pigpio.c.

#define PI_SPI_CE1   7

Definition at line 568 of file pigpio.c.

#define PI_SPI_CLOSED   0

Definition at line 741 of file pigpio.c.

#define PI_SPI_FLAGS_CHANNEL (   x)    ((x&7)<<29)

Definition at line 850 of file pigpio.c.

#define PI_SPI_FLAGS_GET_3WIRE (   x)    (((x)>>9)&1)

Definition at line 857 of file pigpio.c.

#define PI_SPI_FLAGS_GET_3WREN (   x)    (((x)>>10)&15)

Definition at line 856 of file pigpio.c.

#define PI_SPI_FLAGS_GET_AUX_SPI (   x)    (((x)>>8)&1)

Definition at line 858 of file pigpio.c.

#define PI_SPI_FLAGS_GET_BITLEN (   x)    (((x)>>16)&63)

Definition at line 853 of file pigpio.c.

#define PI_SPI_FLAGS_GET_CHANNEL (   x)    (((x)>>29)&7)

Definition at line 852 of file pigpio.c.

#define PI_SPI_FLAGS_GET_CPHA (   x)    ((x)&1)

Definition at line 863 of file pigpio.c.

#define PI_SPI_FLAGS_GET_CPOL (   x)    ((x)&2)

Definition at line 864 of file pigpio.c.

#define PI_SPI_FLAGS_GET_CSPOL (   x)    ((x)&4)

Definition at line 865 of file pigpio.c.

#define PI_SPI_FLAGS_GET_CSPOLS (   x)    (((x)>>2)&7)

Definition at line 860 of file pigpio.c.

#define PI_SPI_FLAGS_GET_MODE (   x)    ((x)&3)

Definition at line 861 of file pigpio.c.

#define PI_SPI_FLAGS_GET_RESVD (   x)    (((x)>>5)&7)

Definition at line 859 of file pigpio.c.

#define PI_SPI_FLAGS_GET_RX_LSB (   x)    (((x)>>15)&1)

Definition at line 854 of file pigpio.c.

#define PI_SPI_FLAGS_GET_TX_LSB (   x)    (((x)>>14)&1)

Definition at line 855 of file pigpio.c.

#define PI_SPI_MISO   9

Definition at line 570 of file pigpio.c.

#define PI_SPI_MOSI   10

Definition at line 571 of file pigpio.c.

#define PI_SPI_OPENED   2

Definition at line 743 of file pigpio.c.

#define PI_SPI_RESERVED   1

Definition at line 742 of file pigpio.c.

#define PI_SPI_SCLK   11

Definition at line 569 of file pigpio.c.

#define PI_STARTING   0

Definition at line 867 of file pigpio.c.

#define PI_THREAD_NONE   0

Definition at line 871 of file pigpio.c.

#define PI_THREAD_RUNNING   2

Definition at line 873 of file pigpio.c.

#define PI_THREAD_STARTED   1

Definition at line 872 of file pigpio.c.

#define PI_WF_MICROS   1

Definition at line 769 of file pigpio.c.

#define PI_WFRX_I2C_SCL   3

Definition at line 763 of file pigpio.c.

#define PI_WFRX_I2C_SDA   2

Definition at line 762 of file pigpio.c.

#define PI_WFRX_NONE   0

Definition at line 760 of file pigpio.c.

#define PI_WFRX_SERIAL   1

Definition at line 761 of file pigpio.c.

#define PI_WFRX_SPI_CS   7

Definition at line 767 of file pigpio.c.

#define PI_WFRX_SPI_MISO   5

Definition at line 765 of file pigpio.c.

#define PI_WFRX_SPI_MOSI   6

Definition at line 766 of file pigpio.c.

#define PI_WFRX_SPI_SCLK   4

Definition at line 764 of file pigpio.c.

#define PULSE_PER_CYCLE   25

Definition at line 683 of file pigpio.c.

#define PWM_BASE   (pi_peri_phys + 0x0020C000)

Definition at line 310 of file pigpio.c.

#define PWM_CTL   0

Definition at line 392 of file pigpio.c.

#define PWM_CTL_CLRF1   (1<<6)

Definition at line 404 of file pigpio.c.

#define PWM_CTL_MODE1   (1<<1)

Definition at line 406 of file pigpio.c.

#define PWM_CTL_MSEN1   (1<<7)

Definition at line 403 of file pigpio.c.

#define PWM_CTL_MSEN2   (1<<15)

Definition at line 401 of file pigpio.c.

#define PWM_CTL_PWEN1   (1<<0)

Definition at line 407 of file pigpio.c.

#define PWM_CTL_PWEN2   (1<<8)

Definition at line 402 of file pigpio.c.

#define PWM_CTL_USEF1   (1<<5)

Definition at line 405 of file pigpio.c.

#define PWM_DAT1   5

Definition at line 396 of file pigpio.c.

#define PWM_DAT2   9

Definition at line 399 of file pigpio.c.

#define PWM_DMAC   2

Definition at line 394 of file pigpio.c.

#define PWM_DMAC_DREQ (   x)    (x)

Definition at line 411 of file pigpio.c.

#define PWM_DMAC_ENAB   (1 <<31)

Definition at line 409 of file pigpio.c.

#define PWM_DMAC_PANIC (   x)    ((x)<< 8)

Definition at line 410 of file pigpio.c.

#define PWM_FIFO   6

Definition at line 397 of file pigpio.c.

#define PWM_FREQS   18

Definition at line 680 of file pigpio.c.

#define PWM_LEN   0x28

Definition at line 321 of file pigpio.c.

#define PWM_RNG1   4

Definition at line 395 of file pigpio.c.

#define PWM_RNG2   8

Definition at line 398 of file pigpio.c.

#define PWM_STA   1

Definition at line 393 of file pigpio.c.

#define PWM_TIMER   (((PWM_BASE + PWM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS)

Definition at line 654 of file pigpio.c.

Definition at line 214 of file pigpio.c.

#define SOFT_ERROR (   x,
  format,
  arg... 
)
Value:
do                                                              \
   {                                                               \
      DBG(DBG_ALWAYS, format, ## arg);                             \
      return x;                                                    \
   }                                                               \
   while (0)

Definition at line 266 of file pigpio.c.

#define SPI_BASE   (pi_peri_phys + 0x00204000)

Definition at line 311 of file pigpio.c.

#define SPI_CLK   2

Definition at line 526 of file pigpio.c.

#define SPI_CS   0

Definition at line 524 of file pigpio.c.

#define SPI_CS0   0

Definition at line 561 of file pigpio.c.

#define SPI_CS1   1

Definition at line 562 of file pigpio.c.

#define SPI_CS2   2

Definition at line 563 of file pigpio.c.

#define SPI_CS_ADCS   (1<<11)

Definition at line 541 of file pigpio.c.

#define SPI_CS_CLEAR (   x)    ((x)<<4)

Definition at line 547 of file pigpio.c.

#define SPI_CS_CS (   x)    ((x)<<0)

Definition at line 549 of file pigpio.c.

#define SPI_CS_CSPOL (   x)    ((x)<<6)

Definition at line 546 of file pigpio.c.

#define SPI_CS_CSPOLS (   x)    ((x)<<21)

Definition at line 533 of file pigpio.c.

#define SPI_CS_DMA_LEN   (1<<24)

Definition at line 532 of file pigpio.c.

#define SPI_CS_DMAEN   (1<<8)

Definition at line 544 of file pigpio.c.

#define SPI_CS_DONE   (1<<16)

Definition at line 538 of file pigpio.c.

#define SPI_CS_INTD   (1<<9)

Definition at line 543 of file pigpio.c.

#define SPI_CS_INTR   (1<<10)

Definition at line 542 of file pigpio.c.

#define SPI_CS_LEN   (1<<13)

Definition at line 539 of file pigpio.c.

#define SPI_CS_LEN_LONG   (1<<25)

Definition at line 531 of file pigpio.c.

#define SPI_CS_MODE (   x)    ((x)<<2)

Definition at line 548 of file pigpio.c.

#define SPI_CS_REN   (1<<12)

Definition at line 540 of file pigpio.c.

#define SPI_CS_RXD   (1<<17)

Definition at line 537 of file pigpio.c.

#define SPI_CS_RXF   (1<<20)

Definition at line 534 of file pigpio.c.

#define SPI_CS_RXR   (1<<19)

Definition at line 535 of file pigpio.c.

#define SPI_CS_TA   (1<<7)

Definition at line 545 of file pigpio.c.

#define SPI_CS_TXD   (1<<18)

Definition at line 536 of file pigpio.c.

#define SPI_DC   5

Definition at line 529 of file pigpio.c.

#define SPI_DC_RDREQ (   x)    ((x)<<16)

Definition at line 552 of file pigpio.c.

#define SPI_DC_RPANIC (   x)    ((x)<<24)

Definition at line 551 of file pigpio.c.

#define SPI_DC_TDREQ (   x)    ((x)<<0)

Definition at line 554 of file pigpio.c.

#define SPI_DC_TPANIC (   x)    ((x)<<8)

Definition at line 553 of file pigpio.c.

#define SPI_DLEN   3

Definition at line 527 of file pigpio.c.

#define SPI_FIFO   1

Definition at line 525 of file pigpio.c.

#define SPI_LEN   0x18

Definition at line 322 of file pigpio.c.

#define SPI_LTOH   4

Definition at line 528 of file pigpio.c.

#define SPI_MODE0   0

Definition at line 556 of file pigpio.c.

#define SPI_MODE1   1

Definition at line 557 of file pigpio.c.

#define SPI_MODE2   2

Definition at line 558 of file pigpio.c.

#define SPI_MODE3   3

Definition at line 559 of file pigpio.c.

#define SRX_BUF_SIZE   8192

Definition at line 780 of file pigpio.c.

#define STACK_SIZE   (256*1024)

Definition at line 676 of file pigpio.c.

#define SUPERCYCLE   800

Definition at line 723 of file pigpio.c.

#define SUPERLEVEL   20000

Definition at line 724 of file pigpio.c.

#define SYST_BASE   (pi_peri_phys + 0x00003000)

Definition at line 312 of file pigpio.c.

#define SYST_CHI   2

Definition at line 520 of file pigpio.c.

#define SYST_CLO   1

Definition at line 519 of file pigpio.c.

#define SYST_CS   0

Definition at line 518 of file pigpio.c.

#define SYST_LEN   0x1C

Definition at line 323 of file pigpio.c.

#define TCK_PER_IPAGE   2

Definition at line 690 of file pigpio.c.

#define THOUSAND   1000

Definition at line 191 of file pigpio.c.

#define TICKSLOTS   50

Definition at line 735 of file pigpio.c.

#define TIMED_DMA (   x)    (DMA_DEST_DREQ | DMA_PERIPHERAL_MAPPING(x))

Definition at line 651 of file pigpio.c.

#define TIMER_ADD (   a,
  b,
  result 
)
Value:
do                                                              \
   {                                                               \
      (result)->tv_sec =  (a)->tv_sec  + (b)->tv_sec;              \
      (result)->tv_nsec = (a)->tv_nsec + (b)->tv_nsec;             \
      if ((result)->tv_nsec >= BILLION)                            \
      {                                                            \
        ++(result)->tv_sec;                                        \
        (result)->tv_nsec -= BILLION;                              \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 274 of file pigpio.c.

#define TIMER_SUB (   a,
  b,
  result 
)
Value:
do                                                              \
   {                                                               \
      (result)->tv_sec =  (a)->tv_sec  - (b)->tv_sec;              \
      (result)->tv_nsec = (a)->tv_nsec - (b)->tv_nsec;             \
      if ((result)->tv_nsec < 0)                                   \
      {                                                            \
         --(result)->tv_sec;                                       \
         (result)->tv_nsec += BILLION;                             \
      }                                                            \
   }                                                               \
   while (0)

Definition at line 287 of file pigpio.c.

#define WCB_CHAIN_CBS   60

Definition at line 716 of file pigpio.c.

#define WCB_CHAIN_OOL   60

Definition at line 717 of file pigpio.c.

#define WCB_CNT_CBS   13

Definition at line 712 of file pigpio.c.

#define WCB_CNT_OOL   68

Definition at line 713 of file pigpio.c.

#define WCB_CNT_PER_PAGE   2

Definition at line 710 of file pigpio.c.

Definition at line 715 of file pigpio.c.

Definition at line 714 of file pigpio.c.

Definition at line 711 of file pigpio.c.


Typedef Documentation

typedef void(* callbk_t)()

Definition at line 879 of file pigpio.c.


Function Documentation

static void _spiRXBits ( char *  buf,
int  pos,
int  bitlen,
int  msbf,
uint32_t  bits 
) [static]

Definition at line 4266 of file pigpio.c.

static uint32_t _spiTXBits ( char *  buf,
int  pos,
int  bitlen,
int  msbf 
) [static]

Definition at line 4250 of file pigpio.c.

static int addrAllowed ( struct sockaddr *  saddr) [static]

Definition at line 7017 of file pigpio.c.

static void alertEmit ( gpioSample_t sample,
int  numSamples,
uint32_t  changedBits,
uint32_t  eTick 
) [static]

Definition at line 5704 of file pigpio.c.

static void alertGlitchFilter ( gpioSample_t sample,
int  numSamples 
) [static]

Definition at line 5580 of file pigpio.c.

static void alertNoiseFilter ( gpioSample_t sample,
int  numSamples 
) [static]

Definition at line 5638 of file pigpio.c.

static void alertWdogCheck ( gpioSample_t sample,
int  numSamples 
) [static]

Definition at line 6130 of file pigpio.c.

int bbI2CClose ( unsigned  SDA)

Definition at line 10376 of file pigpio.c.

int bbI2COpen ( unsigned  SDA,
unsigned  SCL,
unsigned  baud 
)

Definition at line 10332 of file pigpio.c.

int bbI2CZip ( unsigned  SDA,
char *  inBuf,
unsigned  inLen,
char *  outBuf,
unsigned  outLen 
)

Definition at line 10410 of file pigpio.c.

int bbSPIClose ( unsigned  CS)

Definition at line 10921 of file pigpio.c.

int bbSPIOpen ( unsigned  CS,
unsigned  MISO,
unsigned  MOSI,
unsigned  SCLK,
unsigned  baud,
unsigned  spiFlags 
)

Definition at line 10806 of file pigpio.c.

static void bbSPIStart ( wfRx_t w) [static]

Definition at line 10696 of file pigpio.c.

static void bbSPIStop ( wfRx_t w) [static]

Definition at line 10707 of file pigpio.c.

int bbSPIXfer ( unsigned  CS,
char *  inBuf,
char *  outBuf,
unsigned  count 
)

Definition at line 10967 of file pigpio.c.

static uint8_t bbSPIXferByte ( wfRx_t w,
char  txByte 
) [static]

Definition at line 10718 of file pigpio.c.

void bscInit ( int  mode)

Definition at line 10554 of file pigpio.c.

void bscTerm ( int  mode)

Definition at line 10572 of file pigpio.c.

int bscXfer ( bsc_xfer_t xfer)

Definition at line 10588 of file pigpio.c.

static int chainGetCB ( int  n) [static]

Definition at line 9584 of file pigpio.c.

static int chainGetCntCB ( int  counter) [static]

Definition at line 9656 of file pigpio.c.

static uint32_t chainGetCntVal ( int  counter,
int  slot 
) [static]

Definition at line 9626 of file pigpio.c.

static uint32_t chainGetCntValPadr ( int  counter,
int  slot 
) [static]

Definition at line 9646 of file pigpio.c.

static uint32_t chainGetValPadr ( int  n) [static]

Definition at line 9611 of file pigpio.c.

static void chainMakeCounter ( unsigned  counter,
unsigned  blklen,
unsigned  blocks,
unsigned  count,
uint32_t  repeat,
uint32_t  next 
) [static]

Definition at line 9664 of file pigpio.c.

static void chainSetCntVal ( int  counter,
int  slot,
uint32_t  value 
) [static]

Definition at line 9636 of file pigpio.c.

static void chainSetVal ( int  n,
uint32_t  val 
) [static]

Definition at line 9597 of file pigpio.c.

static int chooseBestClock ( clkInf_t clkInf,
unsigned  f,
unsigned  numc,
unsigned *  cf 
) [static]

Definition at line 5055 of file pigpio.c.

static void clear_CS ( wfRx_t w) [static]

Definition at line 10676 of file pigpio.c.

static void clear_SCL ( wfRx_t w) [static]

Definition at line 10226 of file pigpio.c.

static void clear_SCLK ( wfRx_t w) [static]

Definition at line 10686 of file pigpio.c.

static void clear_SDA ( wfRx_t w) [static]

Definition at line 10220 of file pigpio.c.

static void closeOrphanedNotifications ( int  slot,
int  fd 
) [static]

Definition at line 11542 of file pigpio.c.

static rawCbs_t* dmaCB2adr ( int  pos) [static]

Definition at line 5117 of file pigpio.c.

static uint32_t dmaCbAdr ( int  pos) [static]

Definition at line 5334 of file pigpio.c.

static void dmaCbPrint ( int  pos) [static]

Definition at line 5129 of file pigpio.c.

static unsigned dmaCurrentSlot ( unsigned  pos) [static]

Definition at line 5268 of file pigpio.c.

static void dmaDelayCb ( int  b) [static]

Definition at line 5406 of file pigpio.c.

static uint32_t dmaGpioOffAdr ( int  pos) [static]

Definition at line 5301 of file pigpio.c.

static void dmaGpioOffCb ( int  b,
int  pos 
) [static]

Definition at line 5376 of file pigpio.c.

static uint32_t dmaGpioOnAdr ( int  pos) [static]

Definition at line 5289 of file pigpio.c.

static void dmaGpioOnCb ( int  b,
int  pos 
) [static]

Definition at line 5346 of file pigpio.c.

static void dmaInitCbs ( void  ) [static]

Definition at line 5430 of file pigpio.c.

static unsigned dmaNowAtICB ( void  ) [static]

Definition at line 5141 of file pigpio.c.

static int dmaNowAtOCB ( void  ) [static]

Definition at line 5185 of file pigpio.c.

static uint32_t dmaPwmDataAdr ( int  pos) [static]

Definition at line 5282 of file pigpio.c.

static uint32_t dmaReadLevelsAdr ( int  pos) [static]

Definition at line 5323 of file pigpio.c.

static void dmaReadLevelsCb ( int  b,
int  pos 
) [static]

Definition at line 5391 of file pigpio.c.

static uint32_t dmaTickAdr ( int  pos) [static]

Definition at line 5312 of file pigpio.c.

static void dmaTickCb ( int  b,
int  pos 
) [static]

Definition at line 5361 of file pigpio.c.

int eventMonitor ( unsigned  handle,
uint32_t  bits 
)

Definition at line 11236 of file pigpio.c.

int eventSetFunc ( unsigned  event,
eventFunc_t  f 
)

Definition at line 11201 of file pigpio.c.

int eventSetFuncEx ( unsigned  event,
eventFuncEx_t  f,
void *  userdata 
)

Definition at line 11218 of file pigpio.c.

int eventTrigger ( unsigned  event)

Definition at line 11256 of file pigpio.c.

int fileApprove ( char *  filename)

Definition at line 12785 of file pigpio.c.

int fileClose ( unsigned  handle)

Definition at line 12948 of file pigpio.c.

int fileList ( char *  fpat,
char *  buf,
unsigned  count 
)

Definition at line 13079 of file pigpio.c.

int fileOpen ( char *  file,
unsigned  mode 
)

Definition at line 12850 of file pigpio.c.

int fileRead ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 13000 of file pigpio.c.

int fileSeek ( unsigned  handle,
int32_t  seekOffset,
int  seekFrom 
)

Definition at line 13035 of file pigpio.c.

int fileWrite ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 12968 of file pigpio.c.

static void flushMemory ( void  ) [static]

Definition at line 1782 of file pigpio.c.

int getBitInBytes ( int  bitPos,
char *  buf,
int  numBits 
)

Definition at line 8235 of file pigpio.c.

int gpioCfgBufferSize ( unsigned  millis)

Definition at line 13325 of file pigpio.c.

int gpioCfgClock ( unsigned  micros,
unsigned  peripheral,
unsigned  source 
)

Definition at line 13342 of file pigpio.c.

int gpioCfgDMAchannel ( unsigned  DMAchannel)

Definition at line 13366 of file pigpio.c.

int gpioCfgDMAchannels ( unsigned  primaryChannel,
unsigned  secondaryChannel 
)

Definition at line 13383 of file pigpio.c.

uint32_t gpioCfgGetInternals ( void  )

Definition at line 13499 of file pigpio.c.

int gpioCfgInterfaces ( unsigned  ifFlags)

Definition at line 13424 of file pigpio.c.

int gpioCfgInternals ( unsigned  cfgWhat,
unsigned  cfgVal 
)

Definition at line 13512 of file pigpio.c.

int gpioCfgMemAlloc ( unsigned  memAllocMode)

Definition at line 13457 of file pigpio.c.

int gpioCfgNetAddr ( int  numSockAddr,
uint32_t *  sockAddr 
)

Definition at line 13474 of file pigpio.c.

int gpioCfgPermissions ( uint64_t  updateMask)

Definition at line 13408 of file pigpio.c.

int gpioCfgSetInternals ( uint32_t  cfgVal)

Definition at line 13504 of file pigpio.c.

int gpioCfgSocketPort ( unsigned  port)

Definition at line 13440 of file pigpio.c.

uint32_t gpioDelay ( uint32_t  micros)

Definition at line 13196 of file pigpio.c.

int gpioDeleteScript ( unsigned  script_id)

Definition at line 12354 of file pigpio.c.

int gpioGetMode ( unsigned  gpio)

Definition at line 8641 of file pigpio.c.

int gpioGetPad ( unsigned  pad)

Definition at line 12741 of file pigpio.c.

int gpioGetPWMdutycycle ( unsigned  gpio)

Definition at line 8776 of file pigpio.c.

int gpioGetPWMfrequency ( unsigned  gpio)

Definition at line 8949 of file pigpio.c.

int gpioGetPWMrange ( unsigned  gpio)

Definition at line 8846 of file pigpio.c.

int gpioGetPWMrealRange ( unsigned  gpio)

Definition at line 8869 of file pigpio.c.

int gpioGetServoPulsewidth ( unsigned  gpio)

Definition at line 9016 of file pigpio.c.

int gpioGlitchFilter ( unsigned  gpio,
unsigned  steady 
)

Definition at line 11904 of file pigpio.c.

int gpioHardwareClock ( unsigned  gpio,
unsigned  frequency 
)

Definition at line 12522 of file pigpio.c.

int gpioHardwarePWM ( unsigned  gpio,
unsigned  frequency,
unsigned  dutycycle 
)

Definition at line 12603 of file pigpio.c.

unsigned gpioHardwareRevision ( void  )

Definition at line 13259 of file pigpio.c.

int gpioInitialise ( void  )

Definition at line 8459 of file pigpio.c.

int gpioNoiseFilter ( unsigned  gpio,
unsigned  steady,
unsigned  active 
)

Definition at line 11874 of file pigpio.c.

int gpioNotifyBegin ( unsigned  handle,
uint32_t  bits 
)

Definition at line 11747 of file pigpio.c.

int gpioNotifyClose ( unsigned  handle)

Definition at line 11795 of file pigpio.c.

int gpioNotifyOpen ( void  )

Definition at line 11635 of file pigpio.c.

static int gpioNotifyOpenInBand ( int  fd) [static]

Definition at line 11642 of file pigpio.c.

int gpioNotifyOpenWithSize ( int  bufSize)

Definition at line 11572 of file pigpio.c.

int gpioNotifyPause ( unsigned  handle)

Definition at line 11771 of file pigpio.c.

int gpioPWM ( unsigned  gpio,
unsigned  val 
)

Definition at line 8744 of file pigpio.c.

int gpioRead ( unsigned  gpio)

Definition at line 8691 of file pigpio.c.

uint32_t gpioRead_Bits_0_31 ( void  )

Definition at line 12443 of file pigpio.c.

uint32_t gpioRead_Bits_32_53 ( void  )

Definition at line 12455 of file pigpio.c.

int gpioRunScript ( unsigned  script_id,
unsigned  numParam,
uint32_t *  param 
)

Definition at line 12219 of file pigpio.c.

int gpioScriptStatus ( unsigned  script_id,
uint32_t *  param 
)

Definition at line 12300 of file pigpio.c.

int gpioSerialRead ( unsigned  gpio,
void *  buf,
size_t  bufSize 
)

Definition at line 11100 of file pigpio.c.

int gpioSerialReadClose ( unsigned  gpio)

Definition at line 11145 of file pigpio.c.

int gpioSerialReadInvert ( unsigned  gpio,
unsigned  invert 
)

Definition at line 11076 of file pigpio.c.

int gpioSerialReadOpen ( unsigned  gpio,
unsigned  baud,
unsigned  data_bits 
)

Definition at line 11021 of file pigpio.c.

int gpioServo ( unsigned  gpio,
unsigned  val 
)

Definition at line 8978 of file pigpio.c.

int gpioSetAlertFunc ( unsigned  gpio,
gpioAlertFunc_t  f 
)

Definition at line 11303 of file pigpio.c.

int gpioSetAlertFuncEx ( unsigned  gpio,
gpioAlertFuncEx_t  f,
void *  userdata 
)

Definition at line 11320 of file pigpio.c.

int gpioSetGetSamplesFunc ( gpioGetSamplesFunc_t  f,
uint32_t  bits 
)

Definition at line 11942 of file pigpio.c.

int gpioSetGetSamplesFuncEx ( gpioGetSamplesFuncEx_t  f,
uint32_t  bits,
void *  userdata 
)

Definition at line 11963 of file pigpio.c.

int gpioSetISRFunc ( unsigned  gpio,
unsigned  edge,
int  timeout,
gpioISRFunc_t  f 
)

Definition at line 11498 of file pigpio.c.

int gpioSetISRFuncEx ( unsigned  gpio,
unsigned  edge,
int  timeout,
gpioAlertFuncEx_t  f,
void *  userdata 
)

Definition at line 11521 of file pigpio.c.

int gpioSetMode ( unsigned  gpio,
unsigned  mode 
)

Definition at line 8607 of file pigpio.c.

int gpioSetPad ( unsigned  pad,
unsigned  padStrength 
)

Definition at line 12717 of file pigpio.c.

int gpioSetPullUpDown ( unsigned  gpio,
unsigned  pud 
)

Definition at line 8661 of file pigpio.c.

int gpioSetPWMfrequency ( unsigned  gpio,
unsigned  frequency 
)

Definition at line 8897 of file pigpio.c.

int gpioSetPWMrange ( unsigned  gpio,
unsigned  range 
)

Definition at line 8807 of file pigpio.c.

int gpioSetSignalFunc ( unsigned  signum,
gpioSignalFunc_t  f 
)

Definition at line 12401 of file pigpio.c.

int gpioSetSignalFuncEx ( unsigned  signum,
gpioSignalFuncEx_t  f,
void *  userdata 
)

Definition at line 12421 of file pigpio.c.

int gpioSetTimerFunc ( unsigned  id,
unsigned  millis,
gpioTimerFunc_t  f 
)

Definition at line 12057 of file pigpio.c.

int gpioSetTimerFuncEx ( unsigned  id,
unsigned  millis,
gpioTimerFuncEx_t  f,
void *  userdata 
)

Definition at line 12077 of file pigpio.c.

int gpioSetWatchdog ( unsigned  gpio,
unsigned  timeout 
)

Definition at line 11850 of file pigpio.c.

int gpioSleep ( unsigned  timetype,
int  seconds,
int  micros 
)

Definition at line 13155 of file pigpio.c.

pthread_t* gpioStartThread ( gpioThreadFunc_t  f,
void *  userdata 
)

Definition at line 12098 of file pigpio.c.

int gpioStopScript ( unsigned  script_id)

Definition at line 12325 of file pigpio.c.

void gpioStopThread ( pthread_t *  pth)

Definition at line 12134 of file pigpio.c.

int gpioStoreScript ( char *  script)

Definition at line 12158 of file pigpio.c.

void gpioTerminate ( void  )

Definition at line 8495 of file pigpio.c.

uint32_t gpioTick ( void  )

Definition at line 13217 of file pigpio.c.

int gpioTime ( unsigned  timetype,
int *  seconds,
int *  micros 
)

Definition at line 13121 of file pigpio.c.

int gpioTrigger ( unsigned  gpio,
unsigned  pulseLen,
unsigned  level 
)

Definition at line 11820 of file pigpio.c.

int gpioUpdateScript ( unsigned  script_id,
unsigned  numParam,
uint32_t *  param 
)

Definition at line 12268 of file pigpio.c.

unsigned gpioVersion ( void  )

Definition at line 13227 of file pigpio.c.

int gpioWaveAddGeneric ( unsigned  numPulses,
gpioPulse_t pulses 
)

Definition at line 9084 of file pigpio.c.

int gpioWaveAddNew ( void  )

Definition at line 9063 of file pigpio.c.

int gpioWaveAddSerial ( unsigned  gpio,
unsigned  baud,
unsigned  data_bits,
unsigned  stop_bits,
unsigned  offset,
unsigned  numBytes,
char *  bstr 
)

Definition at line 9111 of file pigpio.c.

int gpioWaveChain ( char *  buf,
unsigned  bufSize 
)

Definition at line 9764 of file pigpio.c.

int gpioWaveClear ( void  )

Definition at line 9034 of file pigpio.c.

int gpioWaveCreate ( void  )

Definition at line 9388 of file pigpio.c.

int gpioWaveDelete ( unsigned  wave_id)

Definition at line 9484 of file pigpio.c.

int gpioWaveGetCbs ( void  )

Definition at line 10176 of file pigpio.c.

int gpioWaveGetHighCbs ( void  )

Definition at line 10187 of file pigpio.c.

int gpioWaveGetHighMicros ( void  )

Definition at line 10121 of file pigpio.c.

int gpioWaveGetHighPulses ( void  )

Definition at line 10154 of file pigpio.c.

int gpioWaveGetMaxCbs ( void  )

Definition at line 10198 of file pigpio.c.

int gpioWaveGetMaxMicros ( void  )

Definition at line 10132 of file pigpio.c.

int gpioWaveGetMaxPulses ( void  )

Definition at line 10165 of file pigpio.c.

int gpioWaveGetMicros ( void  )

Definition at line 10110 of file pigpio.c.

int gpioWaveGetPulses ( void  )

Definition at line 10143 of file pigpio.c.

int gpioWaveTxAt ( void  )

Definition at line 10070 of file pigpio.c.

int gpioWaveTxBusy ( void  )

Definition at line 10056 of file pigpio.c.

int gpioWaveTxSend ( unsigned  wave_id,
unsigned  wave_mode 
)

Definition at line 9524 of file pigpio.c.

int gpioWaveTxStart ( unsigned  wave_mode)

Definition at line 9513 of file pigpio.c.

int gpioWaveTxStop ( void  )

Definition at line 10094 of file pigpio.c.

int gpioWrite ( unsigned  gpio,
unsigned  level 
)

Definition at line 8707 of file pigpio.c.

int gpioWrite_Bits_0_31_Clear ( uint32_t  bits)

Definition at line 12467 of file pigpio.c.

int gpioWrite_Bits_0_31_Set ( uint32_t  bits)

Definition at line 12495 of file pigpio.c.

int gpioWrite_Bits_32_53_Clear ( uint32_t  bits)

Definition at line 12481 of file pigpio.c.

int gpioWrite_Bits_32_53_Set ( uint32_t  bits)

Definition at line 12509 of file pigpio.c.

static void I2C_clock_stretch ( wfRx_t w) [static]

Definition at line 10237 of file pigpio.c.

static void I2C_delay ( wfRx_t w) [static]

Definition at line 10232 of file pigpio.c.

int i2cBlockProcessCall ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 3731 of file pigpio.c.

int i2cClose ( unsigned  handle)

Definition at line 4017 of file pigpio.c.

static int I2CGetBit ( wfRx_t w) [static]

Definition at line 10287 of file pigpio.c.

static uint8_t I2CGetByte ( wfRx_t w,
int  nack 
) [static]

Definition at line 10316 of file pigpio.c.

int i2cOpen ( unsigned  i2cBus,
unsigned  i2cAddr,
unsigned  i2cFlags 
)

Definition at line 3942 of file pigpio.c.

int i2cProcessCall ( unsigned  handle,
unsigned  reg,
unsigned  wVal 
)

Definition at line 3596 of file pigpio.c.

static void I2CPutBit ( wfRx_t w,
int  bit 
) [static]

Definition at line 10276 of file pigpio.c.

static int I2CPutByte ( wfRx_t w,
int  byte 
) [static]

Definition at line 10301 of file pigpio.c.

int i2cReadBlockData ( unsigned  handle,
unsigned  reg,
char *  buf 
)

Definition at line 3638 of file pigpio.c.

int i2cReadByte ( unsigned  handle)

Definition at line 3368 of file pigpio.c.

int i2cReadByteData ( unsigned  handle,
unsigned  reg 
)

Definition at line 3436 of file pigpio.c.

int i2cReadDevice ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 3913 of file pigpio.c.

int i2cReadI2CBlockData ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 3782 of file pigpio.c.

int i2cReadWordData ( unsigned  handle,
unsigned  reg 
)

Definition at line 3514 of file pigpio.c.

int i2cSegments ( unsigned  handle,
pi_i2c_msg_t segs,
unsigned  numSegs 
)

Definition at line 4060 of file pigpio.c.

static void I2CStart ( wfRx_t w) [static]

Definition at line 10246 of file pigpio.c.

static void I2CStop ( wfRx_t w) [static]

Definition at line 10264 of file pigpio.c.

void i2cSwitchCombined ( int  setting)

Definition at line 4037 of file pigpio.c.

int i2cWriteBlockData ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 3684 of file pigpio.c.

int i2cWriteByte ( unsigned  handle,
unsigned  bVal 
)

Definition at line 3399 of file pigpio.c.

int i2cWriteByteData ( unsigned  handle,
unsigned  reg,
unsigned  bVal 
)

Definition at line 3470 of file pigpio.c.

int i2cWriteDevice ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 3884 of file pigpio.c.

int i2cWriteI2CBlockData ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 3837 of file pigpio.c.

int i2cWriteQuick ( unsigned  handle,
unsigned  bit 
)

Definition at line 3336 of file pigpio.c.

int i2cWriteWordData ( unsigned  handle,
unsigned  reg,
unsigned  wVal 
)

Definition at line 3552 of file pigpio.c.

int i2cZip ( unsigned  handle,
char *  inBuf,
unsigned  inLen,
char *  outBuf,
unsigned  outLen 
)

Definition at line 4090 of file pigpio.c.

static int initAllocDMAMem ( void  ) [static]

Definition at line 7427 of file pigpio.c.

static void initCheckLockFile ( void  ) [static]

Definition at line 7100 of file pigpio.c.

static int initCheckPermitted ( void  ) [static]

Definition at line 7180 of file pigpio.c.

static void initClearGlobals ( void  ) [static]

Definition at line 7763 of file pigpio.c.

static void initClock ( int  mainClock) [static]

Definition at line 7691 of file pigpio.c.

static void initDMAgo ( volatile uint32_t *  dmaAddr,
uint32_t  cbAddr 
) [static]

Definition at line 7738 of file pigpio.c.

static int initGrabLockFile ( void  ) [static]

Definition at line 7133 of file pigpio.c.

static void initHWClk ( int  clkCtl,
int  clkDiv,
int  clkSrc,
int  divI,
int  divF,
int  MASH 
) [static]

Definition at line 7664 of file pigpio.c.

int initInitialise ( void  )

Definition at line 8053 of file pigpio.c.

static uint32_t* initMapMem ( int  fd,
uint32_t  addr,
uint32_t  len 
) [static]

Definition at line 7170 of file pigpio.c.

static int initMboxBlock ( int  block) [static]

Definition at line 7395 of file pigpio.c.

static int initPagemapBlock ( int  block) [static]

Definition at line 7339 of file pigpio.c.

static void initPCM ( unsigned  bits) [static]

Definition at line 7611 of file pigpio.c.

static int initPeripherals ( void  ) [static]

Definition at line 7199 of file pigpio.c.

static void initPWM ( unsigned  bits) [static]

Definition at line 7568 of file pigpio.c.

static void initReleaseResources ( void  ) [static]

Definition at line 7880 of file pigpio.c.

static int initZaps ( int  pmapFd,
void *  virtualBase,
int  basePage,
int  pages 
) [static]

Definition at line 7280 of file pigpio.c.

static int intEventSetFunc ( unsigned  event,
void *  f,
int  user,
void *  userdata 
) [static]

Definition at line 11181 of file pigpio.c.

static int intGpioSetAlertFunc ( unsigned  gpio,
void *  f,
int  user,
void *  userdata 
) [static]

Definition at line 11273 of file pigpio.c.

static int intGpioSetISRFunc ( unsigned  gpio,
unsigned  edge,
int  timeout,
void *  f,
int  user,
void *  userdata 
) [static]

Definition at line 11395 of file pigpio.c.

static int intGpioSetTimerFunc ( unsigned  id,
unsigned  millis,
void *  f,
int  user,
void *  userdata 
) [static]

Definition at line 11986 of file pigpio.c.

static void intNotifyBits ( void  ) [static]

Definition at line 11724 of file pigpio.c.

static void intScriptBits ( void  ) [static]

Definition at line 11684 of file pigpio.c.

static void intScriptEventBits ( void  ) [static]

Definition at line 11705 of file pigpio.c.

static unsigned mbAllocateMemory ( int  fd,
unsigned  size,
unsigned  align,
unsigned  flags 
) [static]

Definition at line 2716 of file pigpio.c.

static void mbClose ( int  fd) [static]

Definition at line 2706 of file pigpio.c.

static int mbCreate ( char *  dev) [static]

Definition at line 2681 of file pigpio.c.

static int mbDMAAlloc ( DMAMem_t DMAMemP,
unsigned  size,
uint32_t  pi_mem_flag 
) [static]

Definition at line 2817 of file pigpio.c.

static void mbDMAFree ( DMAMem_t DMAMemP) [static]

Definition at line 2806 of file pigpio.c.

static unsigned mbLockMemory ( int  fd,
unsigned  handle 
) [static]

Definition at line 2737 of file pigpio.c.

static void* mbMapMem ( unsigned  base,
unsigned  size 
) [static]

Definition at line 2791 of file pigpio.c.

static int mbOpen ( void  ) [static]

Definition at line 2690 of file pigpio.c.

static int mbProperty ( int  fd,
void *  buf 
) [static]

Definition at line 2711 of file pigpio.c.

static unsigned mbReleaseMemory ( int  fd,
unsigned  handle 
) [static]

Definition at line 2773 of file pigpio.c.

static unsigned mbUnlockMemory ( int  fd,
unsigned  handle 
) [static]

Definition at line 2755 of file pigpio.c.

static int mbUnmapMem ( void *  addr,
unsigned  size 
) [static]

Definition at line 2800 of file pigpio.c.

static int my_smbus_access ( int  fd,
char  rw,
uint8_t  cmd,
int  size,
union my_smbus_data data 
) [static]

Definition at line 1598 of file pigpio.c.

static char* myBuf2Str ( unsigned  count,
char *  buf 
) [static]

Definition at line 1579 of file pigpio.c.

static void myClearGpioOff ( unsigned  gpio,
int  pos 
) [static]

Definition at line 2484 of file pigpio.c.

static void myClearGpioOn ( unsigned  gpio,
int  pos 
) [static]

Definition at line 2507 of file pigpio.c.

static void myCreatePipe ( char *  name,
int  perm 
) [static]

Definition at line 1682 of file pigpio.c.

static int myDoCommand ( uint32_t *  p,
unsigned  bufSize,
char *  buf 
) [static]

Definition at line 1833 of file pigpio.c.

static uint32_t myGetLevel ( int  pos) [static]

Definition at line 1721 of file pigpio.c.

static uint32_t myGetTick ( int  pos) [static]

Definition at line 1760 of file pigpio.c.

static uint32_t myGpioDelay ( uint32_t  micros) [static]

Definition at line 1662 of file pigpio.c.

static int myGpioRead ( unsigned  gpio) [static]

Definition at line 1629 of file pigpio.c.

static void myGpioSetMode ( unsigned  gpio,
unsigned  mode 
) [static]

Definition at line 1616 of file pigpio.c.

static void myGpioSetPwm ( unsigned  gpio,
int  oldVal,
int  newVal 
) [static]

Definition at line 2519 of file pigpio.c.

static void myGpioSetServo ( unsigned  gpio,
int  oldVal,
int  newVal 
) [static]

Definition at line 2603 of file pigpio.c.

static void myGpioSleep ( int  seconds,
int  micros 
) [static]

Definition at line 1646 of file pigpio.c.

static void myGpioWrite ( unsigned  gpio,
unsigned  level 
) [static]

Definition at line 1638 of file pigpio.c.

static int myI2CGetPar ( char *  inBuf,
int *  inPos,
int  inLen,
int *  esc 
) [static]

Definition at line 1735 of file pigpio.c.

static void myLvsPageSlot ( int  pos,
int *  page,
int *  slot 
) [static]

Definition at line 1705 of file pigpio.c.

static void myOffPageSlot ( int  pos,
int *  page,
int *  slot 
) [static]

Definition at line 1697 of file pigpio.c.

int myPathBad ( char *  name)

Definition at line 1538 of file pigpio.c.

static int myPermit ( unsigned  gpio) [static]

Definition at line 1772 of file pigpio.c.

int myScriptNameValid ( char *  name)

Definition at line 1493 of file pigpio.c.

static void mySetGpioOff ( unsigned  gpio,
int  pos 
) [static]

Definition at line 2473 of file pigpio.c.

static void mySetGpioOn ( unsigned  gpio,
int  pos 
) [static]

Definition at line 2495 of file pigpio.c.

static void myTckPageSlot ( int  pos,
int *  page,
int *  slot 
) [static]

Definition at line 1713 of file pigpio.c.

static char* myTimeStamp ( ) [static]

Definition at line 1516 of file pigpio.c.

static void notifyMutex ( int  lock) [static]

Definition at line 11563 of file pigpio.c.

static void* pthAlertThread ( void *  x) [static]

Definition at line 6162 of file pigpio.c.

static void* pthFifoThread ( void *  x) [static]

Definition at line 6779 of file pigpio.c.

static void* pthISRThread ( void *  x) [static]

Definition at line 11335 of file pigpio.c.

static void* pthScript ( void *  x) [static]

Definition at line 6511 of file pigpio.c.

static void* pthSocketThread ( void *  x) [static]

Definition at line 7038 of file pigpio.c.

static void* pthSocketThreadHandler ( void *  fdC) [static]

Definition at line 6897 of file pigpio.c.

static void* pthTimerTick ( void *  x) [static]

Definition at line 6751 of file pigpio.c.

void putBitInBytes ( int  bitPos,
char *  buf,
int  bit 
)

Definition at line 8251 of file pigpio.c.

void rawDumpScript ( unsigned  script_id)

Definition at line 8418 of file pigpio.c.

void rawDumpWave ( void  )

Definition at line 8394 of file pigpio.c.

int rawWaveAddGeneric ( unsigned  numIn1,
rawWave_t in1 
)

Definition at line 3204 of file pigpio.c.

int rawWaveAddSPI ( rawSPI_t spi,
unsigned  offset,
unsigned  spiSS,
char *  buf,
unsigned  spiTxBits,
unsigned  spiBitFirst,
unsigned  spiBitLast,
unsigned  spiBits 
)

Definition at line 9244 of file pigpio.c.

unsigned rawWaveCB ( void  )

Definition at line 5232 of file pigpio.c.

rawCbs_t* rawWaveCBAdr ( int  cbNum)

Definition at line 2839 of file pigpio.c.

uint32_t rawWaveGetIn ( int  pos)

Definition at line 8322 of file pigpio.c.

uint32_t rawWaveGetOOL ( int  pos)

Definition at line 8264 of file pigpio.c.

uint32_t rawWaveGetOut ( int  pos)

Definition at line 8293 of file pigpio.c.

rawWaveInfo_t rawWaveInfo ( int  wave_id)

Definition at line 8350 of file pigpio.c.

void rawWaveSetIn ( int  pos,
uint32_t  value 
)

Definition at line 8337 of file pigpio.c.

void rawWaveSetOOL ( int  pos,
uint32_t  value 
)

Definition at line 8279 of file pigpio.c.

void rawWaveSetOut ( int  pos,
uint32_t  value 
)

Definition at line 8308 of file pigpio.c.

static int read_SDA ( wfRx_t w) [static]

Definition at line 10209 of file pigpio.c.

static int scrEvtWait ( gpioScript_t s,
uint32_t  bits 
) [static]

Definition at line 6442 of file pigpio.c.

static int scrPop ( gpioScript_t s,
int *  SP,
int *  S 
) [static]

Definition at line 6402 of file pigpio.c.

static void scrPush ( gpioScript_t s,
int *  SP,
int *  S,
int  val 
) [static]

Definition at line 6418 of file pigpio.c.

static void scrSwap ( int *  v1,
int *  v2 
) [static]

Definition at line 6433 of file pigpio.c.

static int scrSys ( char *  cmd,
uint32_t  p1,
uint32_t  p2 
) [static]

Definition at line 6490 of file pigpio.c.

static int scrWait ( gpioScript_t s,
uint32_t  bits 
) [static]

Definition at line 6466 of file pigpio.c.

int serClose ( unsigned  handle)

Definition at line 4889 of file pigpio.c.

int serDataAvailable ( unsigned  handle)

Definition at line 5033 of file pigpio.c.

int serOpen ( char *  tty,
unsigned  serBaud,
unsigned  serFlags 
)

Definition at line 4800 of file pigpio.c.

int serRead ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 5000 of file pigpio.c.

int serReadByte ( unsigned  handle)

Definition at line 4934 of file pigpio.c.

int serWrite ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 4964 of file pigpio.c.

int serWriteByte ( unsigned  handle,
unsigned  bVal 
)

Definition at line 4909 of file pigpio.c.

static void set_CS ( wfRx_t w) [static]

Definition at line 10671 of file pigpio.c.

static void set_SCLK ( wfRx_t w) [static]

Definition at line 10681 of file pigpio.c.

static void set_SDA ( wfRx_t w) [static]

Definition at line 10215 of file pigpio.c.

int shell ( char *  scriptName,
char *  scriptString 
)

Definition at line 12760 of file pigpio.c.

static void sigHandler ( int  signum) [static]

Definition at line 5477 of file pigpio.c.

static void sigSetHandler ( void  ) [static]

Definition at line 5537 of file pigpio.c.

static void SPI_delay ( wfRx_t w) [static]

Definition at line 10691 of file pigpio.c.

static void spiACS ( int  channel,
int  on 
) [static]

Definition at line 4279 of file pigpio.c.

static int spiAnyOpen ( uint32_t  flags) [static]

Definition at line 4523 of file pigpio.c.

int spiClose ( unsigned  handle)

Definition at line 4714 of file pigpio.c.

static void spiGo ( unsigned  speed,
uint32_t  flags,
char *  txBuf,
char *  rxBuf,
unsigned  count 
) [static]

Definition at line 4499 of file pigpio.c.

static void spiGoA ( unsigned  speed,
uint32_t  flags,
char *  txBuf,
char *  rxBuf,
unsigned  count 
) [static]

Definition at line 4292 of file pigpio.c.

static void spiGoS ( unsigned  speed,
uint32_t  flags,
char *  txBuf,
char *  rxBuf,
unsigned  count 
) [static]

Definition at line 4395 of file pigpio.c.

static void spiInit ( uint32_t  flags) [static]

Definition at line 4538 of file pigpio.c.

static void spinWhileStarting ( void  ) [static]

Definition at line 1822 of file pigpio.c.

int spiOpen ( unsigned  spiChan,
unsigned  baud,
unsigned  spiFlags 
)

Definition at line 4654 of file pigpio.c.

int spiRead ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 4734 of file pigpio.c.

static void spiTerm ( uint32_t  flags) [static]

Definition at line 4613 of file pigpio.c.

int spiWrite ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 4755 of file pigpio.c.

int spiXfer ( unsigned  handle,
char *  txBuf,
char *  rxBuf,
unsigned  count 
)

Definition at line 4776 of file pigpio.c.

static void stopHardwarePWM ( void  ) [static]

Definition at line 8586 of file pigpio.c.

static void switchFunctionOff ( unsigned  gpio) [static]

Definition at line 8558 of file pigpio.c.

void time_sleep ( double  seconds)

Definition at line 8374 of file pigpio.c.

double time_time ( void  )

Definition at line 8360 of file pigpio.c.

static int wave2Cbs ( unsigned  wave_mode,
int *  CB,
int *  BOOL,
int *  TOOL 
) [static]

Definition at line 2966 of file pigpio.c.

static void waveBitDelay ( unsigned  baud,
unsigned  bits,
unsigned  stops,
unsigned *  bitDelay 
) [static]

Definition at line 2897 of file pigpio.c.

static uint32_t waveCbPOadr ( int  pos) [static]

Definition at line 2852 of file pigpio.c.

static void waveCBsOOLs ( int *  numCBs,
int *  numBOOLs,
int *  numTOOLs 
) [static]

Definition at line 2932 of file pigpio.c.

static int waveDelayCBs ( uint32_t  delay) [static]

Definition at line 2919 of file pigpio.c.

static void waveOOLPageSlot ( int  pos,
int *  page,
int *  slot 
) [static]

Definition at line 2864 of file pigpio.c.

static uint32_t waveOOLPOadr ( int  pos) [static]

Definition at line 2884 of file pigpio.c.

static void waveRxBit ( int  gpio,
int  level,
uint32_t  tick 
) [static]

Definition at line 3192 of file pigpio.c.

static void waveRxSerial ( wfRx_t w,
int  level,
uint32_t  tick 
) [static]

Definition at line 3118 of file pigpio.c.

static void waveSetOOL ( int  pos,
uint32_t  OOL 
) [static]

Definition at line 2873 of file pigpio.c.

static void wfRx_lock ( int  i) [static]

Definition at line 1808 of file pigpio.c.

static void wfRx_unlock ( int  i) [static]

Definition at line 1815 of file pigpio.c.


Variable Documentation

unsigned alert_delays[]
Initial value:
{
   900000, 225000, 240000, 257142, 276923, 300000,  327272,  360000,
   400000, 450000, 514285, 600000, 720000, 900000, 1200000, 1800000
}

Definition at line 5572 of file pigpio.c.

volatile uint32_t alertBits = 0 [static]

Definition at line 1252 of file pigpio.c.

volatile uint32_t* auxReg = MAP_FAILED [static]

Definition at line 1317 of file pigpio.c.

uint32_t bscFR [static]

Definition at line 1381 of file pigpio.c.

volatile uint32_t* bscsReg = MAP_FAILED [static]

Definition at line 1318 of file pigpio.c.

unsigned bufferBlocks [static]

Definition at line 1353 of file pigpio.c.

unsigned bufferCycles [static]

Definition at line 1354 of file pigpio.c.

const clkCfg_t clkCfg[] [static]
Initial value:
{
   
      {   0,    0}, 
      {   1,   17}, 
      {   1,   16}, 
      {   0,    0}, 
      {   1,   15}, 
      {   1,   14}, 
      {   0,    0}, 
      {   0,    0}, 
      {   1,   13}, 
      {   0,    0}, 
      {   1,   12}, 
}

Definition at line 1447 of file pigpio.c.

const uint8_t clkDef[PI_MAX_GPIO+1] [static]
Initial value:
{
 
      0x00, 0x00, 0x00, 0x00, 0x84, 0x94, 0xA4, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x82, 0x92, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x84, 0x00, 0x84, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x94, 0xA4, 0x94, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x00, 0x00,
}

Definition at line 1385 of file pigpio.c.

volatile uint32_t* clkReg = MAP_FAILED [static]

Definition at line 1319 of file pigpio.c.

dmaPage_t* * dmaBus = MAP_FAILED [static]

Definition at line 1309 of file pigpio.c.

dmaIPage_t* * dmaIBus = MAP_FAILED [static]

Definition at line 1312 of file pigpio.c.

volatile uint32_t* dmaIn = MAP_FAILED [static]

Definition at line 1328 of file pigpio.c.

dmaIPage_t* * dmaIVirt = MAP_FAILED [static]

Definition at line 1311 of file pigpio.c.

DMAMem_t* dmaMboxBlk = MAP_FAILED [static]

Definition at line 1306 of file pigpio.c.

dmaOPage_t* * dmaOBus = MAP_FAILED [static]

Definition at line 1315 of file pigpio.c.

volatile uint32_t* dmaOut = MAP_FAILED [static]

Definition at line 1329 of file pigpio.c.

dmaOPage_t* * dmaOVirt = MAP_FAILED [static]

Definition at line 1314 of file pigpio.c.

uintptr_t* * dmaPMapBlk = MAP_FAILED [static]

Definition at line 1307 of file pigpio.c.

volatile uint32_t* dmaReg = MAP_FAILED [static]

Definition at line 1320 of file pigpio.c.

dmaPage_t* * dmaVirt = MAP_FAILED [static]

Definition at line 1308 of file pigpio.c.

Definition at line 1270 of file pigpio.c.

int fdLock = -1 [static]

Definition at line 1300 of file pigpio.c.

int fdMbox = -1 [static]

Definition at line 1304 of file pigpio.c.

int fdMem = -1 [static]

Definition at line 1301 of file pigpio.c.

int fdPmap = -1 [static]

Definition at line 1303 of file pigpio.c.

int fdSock = -1 [static]

Definition at line 1302 of file pigpio.c.

Definition at line 1280 of file pigpio.c.

volatile uint32_t gFilterBits = 0 [static]

Definition at line 1256 of file pigpio.c.

Definition at line 1268 of file pigpio.c.

volatile gpioCfg_t gpioCfg [static]

Definition at line 1274 of file pigpio.c.

Definition at line 1276 of file pigpio.c.

Definition at line 1272 of file pigpio.c.

uint64_t gpioMask [static]

Definition at line 1226 of file pigpio.c.

int gpioMaskSet = 0 [static]

Definition at line 1222 of file pigpio.c.

Definition at line 1278 of file pigpio.c.

volatile uint32_t* gpioReg = MAP_FAILED [static]

Definition at line 1321 of file pigpio.c.

Definition at line 1285 of file pigpio.c.

Definition at line 1287 of file pigpio.c.

volatile gpioStats_t gpioStats [static]

Definition at line 1220 of file pigpio.c.

Definition at line 1289 of file pigpio.c.

uint32_t hw_clk_freq[3] [static]

Definition at line 1331 of file pigpio.c.

uint32_t hw_pwm_duty[2] [static]

Definition at line 1333 of file pigpio.c.

uint32_t hw_pwm_freq[2] [static]

Definition at line 1332 of file pigpio.c.

uint32_t hw_pwm_real_range[2] [static]

Definition at line 1334 of file pigpio.c.

Definition at line 1281 of file pigpio.c.

FILE* inpFifo = NULL [static]

Definition at line 1297 of file pigpio.c.

int libInitialised = 0 [static]

Definition at line 1205 of file pigpio.c.

struct timespec libStarted [static]

Definition at line 1209 of file pigpio.c.

volatile uint32_t monitorBits = 0 [static]

Definition at line 1253 of file pigpio.c.

volatile uint32_t nFilterBits = 0 [static]

Definition at line 1257 of file pigpio.c.

volatile uint32_t notifyBits = 0 [static]

Definition at line 1254 of file pigpio.c.

int numSockNetAddr = 0 [static]

Definition at line 1213 of file pigpio.c.

unsigned old_mode_ace0 [static]

Definition at line 1371 of file pigpio.c.

unsigned old_mode_ace1 [static]

Definition at line 1372 of file pigpio.c.

unsigned old_mode_ace2 [static]

Definition at line 1373 of file pigpio.c.

unsigned old_mode_amiso [static]

Definition at line 1375 of file pigpio.c.

unsigned old_mode_amosi [static]

Definition at line 1376 of file pigpio.c.

unsigned old_mode_asclk [static]

Definition at line 1374 of file pigpio.c.

unsigned old_mode_ce0 [static]

Definition at line 1362 of file pigpio.c.

unsigned old_mode_ce1 [static]

Definition at line 1363 of file pigpio.c.

unsigned old_mode_miso [static]

Definition at line 1365 of file pigpio.c.

unsigned old_mode_mosi [static]

Definition at line 1366 of file pigpio.c.

unsigned old_mode_sclk [static]

Definition at line 1364 of file pigpio.c.

uint32_t old_spi_clk [static]

Definition at line 1369 of file pigpio.c.

uint32_t old_spi_cntl0 [static]

Definition at line 1378 of file pigpio.c.

uint32_t old_spi_cntl1 [static]

Definition at line 1379 of file pigpio.c.

uint32_t old_spi_cs [static]

Definition at line 1368 of file pigpio.c.

FILE* outFifo = NULL [static]

Definition at line 1298 of file pigpio.c.

volatile uint32_t* padsReg = MAP_FAILED [static]

Definition at line 1322 of file pigpio.c.

volatile uint32_t* pcmReg = MAP_FAILED [static]

Definition at line 1323 of file pigpio.c.

volatile uint32_t pi_dram_bus = 0x40000000 [static]

Definition at line 1202 of file pigpio.c.

volatile uint32_t pi_mem_flag = 0x0C [static]

Definition at line 1203 of file pigpio.c.

volatile uint32_t pi_peri_phys = 0x20000000 [static]

Definition at line 1201 of file pigpio.c.

volatile uint32_t piCores = 0 [static]

Definition at line 1200 of file pigpio.c.

pthread_t pthAlert [static]

Definition at line 1356 of file pigpio.c.

Definition at line 1264 of file pigpio.c.

pthread_t pthFifo [static]

Definition at line 1357 of file pigpio.c.

Definition at line 1265 of file pigpio.c.

pthread_t pthSocket [static]

Definition at line 1358 of file pigpio.c.

Definition at line 1266 of file pigpio.c.

int PWMClockInited = 0 [static]

Definition at line 1218 of file pigpio.c.

const uint16_t pwmCycles[PWM_FREQS] [static]
Initial value:
   {  1,    2,    4,    5,    8,   10,   16,    20,    25,
     32,   40,   50,   80,  100,  160,  200,   400,   800}

Definition at line 1463 of file pigpio.c.

const uint8_t PWMDef[PI_MAX_GPIO+1] [static]
Initial value:
{
   
      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x84, 0x94, 0x00, 0x00, 0x00, 0x00, 0x82, 0x92,
      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
      0x84, 0x94, 0x00, 0x00, 0x00, 0x94, 0x00, 0x00, 0x00, 0x00,
      0x00, 0x00, 0x85, 0x95,
}

Definition at line 1417 of file pigpio.c.

int pwmFreq[PWM_FREQS] [static]

Definition at line 1291 of file pigpio.c.

const uint16_t pwmRealRange[PWM_FREQS] [static]
Initial value:
   { 25,   50,  100,  125,  200,  250,  400,   500,   625,
    800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000}

Definition at line 1467 of file pigpio.c.

volatile uint32_t* pwmReg = MAP_FAILED [static]

Definition at line 1324 of file pigpio.c.

uint32_t reportedLevel = 0 [static]

Definition at line 1215 of file pigpio.c.

volatile int runState = PI_STARTING [static]

Definition at line 1262 of file pigpio.c.

volatile uint32_t scriptBits = 0 [static]

Definition at line 1255 of file pigpio.c.

volatile uint32_t scriptEventBits = 0 [static]

Definition at line 1260 of file pigpio.c.

Definition at line 1282 of file pigpio.c.

uint32_t sockNetAddr[MAX_CONNECT_ADDRESSES] [static]

Definition at line 1211 of file pigpio.c.

uint32_t spi_dummy [static]

Definition at line 1360 of file pigpio.c.

Definition at line 1283 of file pigpio.c.

volatile uint32_t* spiReg = MAP_FAILED [static]

Definition at line 1325 of file pigpio.c.

volatile uint32_t* systReg = MAP_FAILED [static]

Definition at line 1326 of file pigpio.c.

int waveClockInited = 0 [static]

Definition at line 1217 of file pigpio.c.

uint32_t* waveEndPtr = NULL [static]

Definition at line 1250 of file pigpio.c.

Definition at line 1241 of file pigpio.c.

Definition at line 1245 of file pigpio.c.

Definition at line 1246 of file pigpio.c.

int waveOutCount = 0 [static]

Definition at line 1248 of file pigpio.c.

int waveOutTopOOL = NUM_WAVE_OOL [static]

Definition at line 1247 of file pigpio.c.

volatile uint32_t wdogBits = 0 [static]

Definition at line 1258 of file pigpio.c.

Definition at line 1228 of file pigpio.c.

int wfc[3] = {0, 0, 0} [static]

Definition at line 1230 of file pigpio.c.

int wfcur = 0 [static]

Definition at line 1232 of file pigpio.c.

Definition at line 1243 of file pigpio.c.

wfStats_t wfStats [static]
Initial value:

Definition at line 1234 of file pigpio.c.



cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:57