Go to the documentation of this file.
34 #define PIGPIO_VERSION 67
380 #define PI_INPFIFO "/dev/pigpio"
381 #define PI_OUTFIFO "/dev/pigout"
382 #define PI_ERRFIFO "/dev/pigerr"
384 #define PI_ENVPORT "PIGPIO_PORT"
385 #define PI_ENVADDR "PIGPIO_ADDR"
387 #define PI_LOCKFILE "/var/run/pigpio.pid"
389 #define PI_I2C_COMBINED "/sys/module/i2c_bcm2708/parameters/combined"
429 #define WAVE_FLAG_READ 1
430 #define WAVE_FLAG_TICK 2
499 #define BSC_FIFO_SIZE 512
557 #define PI_MIN_GPIO 0
558 #define PI_MAX_GPIO 53
562 #define PI_MAX_USER_GPIO 31
593 #define PI_PUD_DOWN 1
598 #define PI_DEFAULT_DUTYCYCLE_RANGE 255
602 #define PI_MIN_DUTYCYCLE_RANGE 25
603 #define PI_MAX_DUTYCYCLE_RANGE 40000
607 #define PI_SERVO_OFF 0
608 #define PI_MIN_SERVO_PULSEWIDTH 500
609 #define PI_MAX_SERVO_PULSEWIDTH 2500
613 #define PI_HW_PWM_MIN_FREQ 1
614 #define PI_HW_PWM_MAX_FREQ 125000000
615 #define PI_HW_PWM_RANGE 1000000
619 #define PI_HW_CLK_MIN_FREQ 4689
620 #define PI_HW_CLK_MAX_FREQ 250000000
622 #define PI_NOTIFY_SLOTS 32
624 #define PI_NTFY_FLAGS_EVENT (1 <<7)
625 #define PI_NTFY_FLAGS_ALIVE (1 <<6)
626 #define PI_NTFY_FLAGS_WDOG (1 <<5)
627 #define PI_NTFY_FLAGS_BIT(x) (((x)<<0)&31)
629 #define PI_WAVE_BLOCKS 4
630 #define PI_WAVE_MAX_PULSES (PI_WAVE_BLOCKS * 3000)
631 #define PI_WAVE_MAX_CHARS (PI_WAVE_BLOCKS * 300)
633 #define PI_BB_I2C_MIN_BAUD 50
634 #define PI_BB_I2C_MAX_BAUD 500000
636 #define PI_BB_SPI_MIN_BAUD 50
637 #define PI_BB_SPI_MAX_BAUD 250000
639 #define PI_BB_SER_MIN_BAUD 50
640 #define PI_BB_SER_MAX_BAUD 250000
642 #define PI_BB_SER_NORMAL 0
643 #define PI_BB_SER_INVERT 1
645 #define PI_WAVE_MIN_BAUD 50
646 #define PI_WAVE_MAX_BAUD 1000000
648 #define PI_SPI_MIN_BAUD 32000
649 #define PI_SPI_MAX_BAUD 125000000
651 #define PI_MIN_WAVE_DATABITS 1
652 #define PI_MAX_WAVE_DATABITS 32
654 #define PI_MIN_WAVE_HALFSTOPBITS 2
655 #define PI_MAX_WAVE_HALFSTOPBITS 8
657 #define PI_WAVE_MAX_MICROS (30 * 60 * 1000000)
659 #define PI_MAX_WAVES 250
661 #define PI_MAX_WAVE_CYCLES 65535
662 #define PI_MAX_WAVE_DELAY 65535
664 #define PI_WAVE_COUNT_PAGES 10
668 #define PI_WAVE_MODE_ONE_SHOT 0
669 #define PI_WAVE_MODE_REPEAT 1
670 #define PI_WAVE_MODE_ONE_SHOT_SYNC 2
671 #define PI_WAVE_MODE_REPEAT_SYNC 3
675 #define PI_WAVE_NOT_FOUND 9998
676 #define PI_NO_TX_WAVE 9999
680 #define PI_FILE_SLOTS 16
681 #define PI_I2C_SLOTS 64
682 #define PI_SPI_SLOTS 32
683 #define PI_SER_SLOTS 16
685 #define PI_MAX_I2C_ADDR 0x7F
687 #define PI_NUM_AUX_SPI_CHANNEL 3
688 #define PI_NUM_STD_SPI_CHANNEL 2
690 #define PI_MAX_I2C_DEVICE_COUNT (1<<16)
691 #define PI_MAX_SPI_DEVICE_COUNT (1<<16)
695 #define PI_I2C_RDRW_IOCTL_MAX_MSGS 42
699 #define PI_I2C_M_WR 0x0000
700 #define PI_I2C_M_RD 0x0001
701 #define PI_I2C_M_TEN 0x0010
702 #define PI_I2C_M_RECV_LEN 0x0400
703 #define PI_I2C_M_NO_RD_ACK 0x0800
704 #define PI_I2C_M_IGNORE_NAK 0x1000
705 #define PI_I2C_M_REV_DIR_ADDR 0x2000
706 #define PI_I2C_M_NOSTART 0x4000
712 #define PI_I2C_START 2
713 #define PI_I2C_COMBINED_ON 2
714 #define PI_I2C_STOP 3
715 #define PI_I2C_COMBINED_OFF 3
716 #define PI_I2C_ADDR 4
717 #define PI_I2C_FLAGS 5
718 #define PI_I2C_READ 6
719 #define PI_I2C_WRITE 7
723 #define PI_SPI_FLAGS_BITLEN(x) ((x&63)<<16)
724 #define PI_SPI_FLAGS_RX_LSB(x) ((x&1)<<15)
725 #define PI_SPI_FLAGS_TX_LSB(x) ((x&1)<<14)
726 #define PI_SPI_FLAGS_3WREN(x) ((x&15)<<10)
727 #define PI_SPI_FLAGS_3WIRE(x) ((x&1)<<9)
728 #define PI_SPI_FLAGS_AUX_SPI(x) ((x&1)<<8)
729 #define PI_SPI_FLAGS_RESVD(x) ((x&7)<<5)
730 #define PI_SPI_FLAGS_CSPOLS(x) ((x&7)<<2)
731 #define PI_SPI_FLAGS_MODE(x) ((x&3))
747 #define BSC_GPUSTAT 12
749 #define BSC_DEBUG_I2C 14
750 #define BSC_DEBUG_SPI 15
752 #define BSC_CR_TESTFIFO 2048
753 #define BSC_CR_RXE 512
754 #define BSC_CR_TXE 256
755 #define BSC_CR_BRK 128
756 #define BSC_CR_CPOL 16
757 #define BSC_CR_CPHA 8
762 #define BSC_FR_RXBUSY 32
763 #define BSC_FR_TXFE 16
764 #define BSC_FR_RXFF 8
765 #define BSC_FR_TXFF 4
766 #define BSC_FR_RXFE 2
767 #define BSC_FR_TXBUSY 1
771 #define BSC_SDA_MOSI 18
772 #define BSC_SCL_SCLK 19
778 #define PI_MAX_BUSY_DELAY 100
782 #define PI_MIN_WDOG_TIMEOUT 0
783 #define PI_MAX_WDOG_TIMEOUT 60000
787 #define PI_MIN_TIMER 0
788 #define PI_MAX_TIMER 9
793 #define PI_MAX_MS 60000
795 #define PI_MAX_SCRIPTS 32
797 #define PI_MAX_SCRIPT_TAGS 50
798 #define PI_MAX_SCRIPT_VARS 150
799 #define PI_MAX_SCRIPT_PARAMS 10
803 #define PI_SCRIPT_INITING 0
804 #define PI_SCRIPT_HALTED 1
805 #define PI_SCRIPT_RUNNING 2
806 #define PI_SCRIPT_WAITING 3
807 #define PI_SCRIPT_FAILED 4
811 #define PI_MIN_SIGNUM 0
812 #define PI_MAX_SIGNUM 63
816 #define PI_TIME_RELATIVE 0
817 #define PI_TIME_ABSOLUTE 1
819 #define PI_MAX_MICS_DELAY 1000000
820 #define PI_MAX_MILS_DELAY 60000
824 #define PI_BUF_MILLIS_MIN 100
825 #define PI_BUF_MILLIS_MAX 10000
831 #define PI_CLOCK_PWM 0
832 #define PI_CLOCK_PCM 1
836 #define PI_MIN_DMA_CHANNEL 0
837 #define PI_MAX_DMA_CHANNEL 14
841 #define PI_MIN_SOCKET_PORT 1024
842 #define PI_MAX_SOCKET_PORT 32000
847 #define PI_DISABLE_FIFO_IF 1
848 #define PI_DISABLE_SOCK_IF 2
849 #define PI_LOCALHOST_SOCK_IF 4
850 #define PI_DISABLE_ALERT 8
854 #define PI_MEM_ALLOC_AUTO 0
855 #define PI_MEM_ALLOC_PAGEMAP 1
856 #define PI_MEM_ALLOC_MAILBOX 2
860 #define PI_MAX_STEADY 300000
861 #define PI_MAX_ACTIVE 1000000
865 #define PI_CFG_DBG_LEVEL 0
866 #define PI_CFG_ALERT_FREQ 4
867 #define PI_CFG_RT_PRIORITY (1<<8)
868 #define PI_CFG_STATS (1<<9)
869 #define PI_CFG_NOSIGHANDLER (1<<10)
871 #define PI_CFG_ILLEGAL_VAL (1<<11)
876 #define RISING_EDGE 0
877 #define FALLING_EDGE 1
878 #define EITHER_EDGE 2
885 #define PI_MIN_PAD_STRENGTH 1
886 #define PI_MAX_PAD_STRENGTH 16
890 #define PI_FILE_NONE 0
891 #define PI_FILE_MIN 1
892 #define PI_FILE_READ 1
893 #define PI_FILE_WRITE 2
895 #define PI_FILE_APPEND 4
896 #define PI_FILE_CREATE 8
897 #define PI_FILE_TRUNC 16
898 #define PI_FILE_MAX 31
900 #define PI_FROM_START 0
901 #define PI_FROM_CURRENT 1
902 #define PI_FROM_END 2
906 #define MAX_CONNECT_ADDRESSES 256
910 #define PI_MAX_EVENT 31
914 #define PI_EVENT_BSC 31
1051 int gpioWrite(
unsigned gpio,
unsigned level);
1073 int gpioPWM(
unsigned user_gpio,
unsigned dutycycle);
1287 int gpioServo(
unsigned user_gpio,
unsigned pulsewidth);
1479 unsigned gpio,
unsigned edge,
int timeout,
gpioISRFunc_t f);
1838 (
unsigned user_gpio,
2248 int gpioSerialRead(
unsigned user_gpio,
void *buf,
size_t bufSize);
2284 int i2cOpen(
unsigned i2cBus,
unsigned i2cAddr,
unsigned i2cFlags);
2504 unsigned handle,
unsigned i2cReg,
char *buf,
unsigned count);
2554 unsigned handle,
unsigned i2cReg,
char *buf,
unsigned count);
2584 unsigned handle,
unsigned i2cReg,
char *buf,
unsigned count);
2608 unsigned handle,
unsigned i2cReg,
char *buf,
unsigned count);
2758 int bbI2COpen(
unsigned SDA,
unsigned SCL,
unsigned baud);
2993 unsigned CS,
unsigned MISO,
unsigned MOSI,
unsigned SCLK,
2994 unsigned baud,
unsigned spiFlags);
3147 int spiOpen(
unsigned spiChan,
unsigned baud,
unsigned spiFlags);
3277 int spiXfer(
unsigned handle,
char *txBuf,
char *rxBuf,
unsigned count);
3296 int serOpen(
char *sertty,
unsigned baud,
unsigned serFlags);
3411 int gpioTrigger(
unsigned user_gpio,
unsigned pulseLen,
unsigned level);
3472 int gpioNoiseFilter(
unsigned user_gpio,
unsigned steady,
unsigned active);
3728 int gpioRunScript(
unsigned script_id,
unsigned numPar, uint32_t *param);
3746 int gpioRunScript(
unsigned script_id,
unsigned numPar, uint32_t *param);
3766 int gpioUpdateScript(
unsigned script_id,
unsigned numPar, uint32_t *param);
4000 int gpioHardwarePWM(
unsigned gpio,
unsigned PWMfreq,
unsigned PWMduty);
4052 int gpioTime(
unsigned timetype,
int *seconds,
int *micros);
4081 int gpioSleep(
unsigned timetype,
int seconds,
int micros);
4219 int gpioSetPad(
unsigned pad,
unsigned padStrength);
4340 int shell(
char *scriptName,
char *scriptString);
4381 #pragma GCC diagnostic push
4383 #pragma GCC diagnostic ignored "-Wcomment"
4491 #pragma GCC diagnostic pop
4587 #pragma GCC diagnostic push
4589 #pragma GCC diagnostic ignored "-Wcomment"
4592 int fileList(
char *fpat,
char *buf,
unsigned count);
4643 #pragma GCC diagnostic pop
4683 unsigned cfgMicros,
unsigned cfgPeripheral,
unsigned cfgSource);
4735 unsigned primaryChannel,
unsigned secondaryChannel);
4894 int gpioCustom1(
unsigned arg1,
unsigned arg2,
char *argx,
unsigned argc);
4912 int gpioCustom2(
unsigned arg1,
char *argx,
unsigned argc,
4913 char *retBuf,
unsigned retMax);
4942 unsigned spiBitFirst,
4943 unsigned spiBitLast,
6061 #define PI_CMD_MODES 0
6062 #define PI_CMD_MODEG 1
6063 #define PI_CMD_PUD 2
6064 #define PI_CMD_READ 3
6065 #define PI_CMD_WRITE 4
6066 #define PI_CMD_PWM 5
6067 #define PI_CMD_PRS 6
6068 #define PI_CMD_PFS 7
6069 #define PI_CMD_SERVO 8
6070 #define PI_CMD_WDOG 9
6071 #define PI_CMD_BR1 10
6072 #define PI_CMD_BR2 11
6073 #define PI_CMD_BC1 12
6074 #define PI_CMD_BC2 13
6075 #define PI_CMD_BS1 14
6076 #define PI_CMD_BS2 15
6077 #define PI_CMD_TICK 16
6078 #define PI_CMD_HWVER 17
6079 #define PI_CMD_NO 18
6080 #define PI_CMD_NB 19
6081 #define PI_CMD_NP 20
6082 #define PI_CMD_NC 21
6083 #define PI_CMD_PRG 22
6084 #define PI_CMD_PFG 23
6085 #define PI_CMD_PRRG 24
6086 #define PI_CMD_HELP 25
6087 #define PI_CMD_PIGPV 26
6088 #define PI_CMD_WVCLR 27
6089 #define PI_CMD_WVAG 28
6090 #define PI_CMD_WVAS 29
6091 #define PI_CMD_WVGO 30
6092 #define PI_CMD_WVGOR 31
6093 #define PI_CMD_WVBSY 32
6094 #define PI_CMD_WVHLT 33
6095 #define PI_CMD_WVSM 34
6096 #define PI_CMD_WVSP 35
6097 #define PI_CMD_WVSC 36
6098 #define PI_CMD_TRIG 37
6099 #define PI_CMD_PROC 38
6100 #define PI_CMD_PROCD 39
6101 #define PI_CMD_PROCR 40
6102 #define PI_CMD_PROCS 41
6103 #define PI_CMD_SLRO 42
6104 #define PI_CMD_SLR 43
6105 #define PI_CMD_SLRC 44
6106 #define PI_CMD_PROCP 45
6107 #define PI_CMD_MICS 46
6108 #define PI_CMD_MILS 47
6109 #define PI_CMD_PARSE 48
6110 #define PI_CMD_WVCRE 49
6111 #define PI_CMD_WVDEL 50
6112 #define PI_CMD_WVTX 51
6113 #define PI_CMD_WVTXR 52
6114 #define PI_CMD_WVNEW 53
6116 #define PI_CMD_I2CO 54
6117 #define PI_CMD_I2CC 55
6118 #define PI_CMD_I2CRD 56
6119 #define PI_CMD_I2CWD 57
6120 #define PI_CMD_I2CWQ 58
6121 #define PI_CMD_I2CRS 59
6122 #define PI_CMD_I2CWS 60
6123 #define PI_CMD_I2CRB 61
6124 #define PI_CMD_I2CWB 62
6125 #define PI_CMD_I2CRW 63
6126 #define PI_CMD_I2CWW 64
6127 #define PI_CMD_I2CRK 65
6128 #define PI_CMD_I2CWK 66
6129 #define PI_CMD_I2CRI 67
6130 #define PI_CMD_I2CWI 68
6131 #define PI_CMD_I2CPC 69
6132 #define PI_CMD_I2CPK 70
6134 #define PI_CMD_SPIO 71
6135 #define PI_CMD_SPIC 72
6136 #define PI_CMD_SPIR 73
6137 #define PI_CMD_SPIW 74
6138 #define PI_CMD_SPIX 75
6140 #define PI_CMD_SERO 76
6141 #define PI_CMD_SERC 77
6142 #define PI_CMD_SERRB 78
6143 #define PI_CMD_SERWB 79
6144 #define PI_CMD_SERR 80
6145 #define PI_CMD_SERW 81
6146 #define PI_CMD_SERDA 82
6148 #define PI_CMD_GDC 83
6149 #define PI_CMD_GPW 84
6151 #define PI_CMD_HC 85
6152 #define PI_CMD_HP 86
6154 #define PI_CMD_CF1 87
6155 #define PI_CMD_CF2 88
6157 #define PI_CMD_BI2CC 89
6158 #define PI_CMD_BI2CO 90
6159 #define PI_CMD_BI2CZ 91
6161 #define PI_CMD_I2CZ 92
6163 #define PI_CMD_WVCHA 93
6165 #define PI_CMD_SLRI 94
6167 #define PI_CMD_CGI 95
6168 #define PI_CMD_CSI 96
6170 #define PI_CMD_FG 97
6171 #define PI_CMD_FN 98
6173 #define PI_CMD_NOIB 99
6175 #define PI_CMD_WVTXM 100
6176 #define PI_CMD_WVTAT 101
6178 #define PI_CMD_PADS 102
6179 #define PI_CMD_PADG 103
6181 #define PI_CMD_FO 104
6182 #define PI_CMD_FC 105
6183 #define PI_CMD_FR 106
6184 #define PI_CMD_FW 107
6185 #define PI_CMD_FS 108
6186 #define PI_CMD_FL 109
6188 #define PI_CMD_SHELL 110
6190 #define PI_CMD_BSPIC 111
6191 #define PI_CMD_BSPIO 112
6192 #define PI_CMD_BSPIX 113
6194 #define PI_CMD_BSCX 114
6196 #define PI_CMD_EVM 115
6197 #define PI_CMD_EVT 116
6199 #define PI_CMD_PROCU 117
6215 #define PI_CMD_SCRIPT 800
6217 #define PI_CMD_ADD 800
6218 #define PI_CMD_AND 801
6219 #define PI_CMD_CALL 802
6220 #define PI_CMD_CMDR 803
6221 #define PI_CMD_CMDW 804
6222 #define PI_CMD_CMP 805
6223 #define PI_CMD_DCR 806
6224 #define PI_CMD_DCRA 807
6225 #define PI_CMD_DIV 808
6226 #define PI_CMD_HALT 809
6227 #define PI_CMD_INR 810
6228 #define PI_CMD_INRA 811
6229 #define PI_CMD_JM 812
6230 #define PI_CMD_JMP 813
6231 #define PI_CMD_JNZ 814
6232 #define PI_CMD_JP 815
6233 #define PI_CMD_JZ 816
6234 #define PI_CMD_TAG 817
6235 #define PI_CMD_LD 818
6236 #define PI_CMD_LDA 819
6237 #define PI_CMD_LDAB 820
6238 #define PI_CMD_MLT 821
6239 #define PI_CMD_MOD 822
6240 #define PI_CMD_NOP 823
6241 #define PI_CMD_OR 824
6242 #define PI_CMD_POP 825
6243 #define PI_CMD_POPA 826
6244 #define PI_CMD_PUSH 827
6245 #define PI_CMD_PUSHA 828
6246 #define PI_CMD_RET 829
6247 #define PI_CMD_RL 830
6248 #define PI_CMD_RLA 831
6249 #define PI_CMD_RR 832
6250 #define PI_CMD_RRA 833
6251 #define PI_CMD_STA 834
6252 #define PI_CMD_STAB 835
6253 #define PI_CMD_SUB 836
6254 #define PI_CMD_SYS 837
6255 #define PI_CMD_WAIT 838
6256 #define PI_CMD_X 839
6257 #define PI_CMD_XA 840
6258 #define PI_CMD_XOR 841
6259 #define PI_CMD_EVTWT 842
6263 #define PI_INIT_FAILED -1 // gpioInitialise failed
6264 #define PI_BAD_USER_GPIO -2 // GPIO not 0-31
6265 #define PI_BAD_GPIO -3 // GPIO not 0-53
6266 #define PI_BAD_MODE -4 // mode not 0-7
6267 #define PI_BAD_LEVEL -5 // level not 0-1
6268 #define PI_BAD_PUD -6 // pud not 0-2
6269 #define PI_BAD_PULSEWIDTH -7 // pulsewidth not 0 or 500-2500
6270 #define PI_BAD_DUTYCYCLE -8 // dutycycle outside set range
6271 #define PI_BAD_TIMER -9 // timer not 0-9
6272 #define PI_BAD_MS -10 // ms not 10-60000
6273 #define PI_BAD_TIMETYPE -11 // timetype not 0-1
6274 #define PI_BAD_SECONDS -12 // seconds < 0
6275 #define PI_BAD_MICROS -13 // micros not 0-999999
6276 #define PI_TIMER_FAILED -14 // gpioSetTimerFunc failed
6277 #define PI_BAD_WDOG_TIMEOUT -15 // timeout not 0-60000
6278 #define PI_NO_ALERT_FUNC -16 // DEPRECATED
6279 #define PI_BAD_CLK_PERIPH -17 // clock peripheral not 0-1
6280 #define PI_BAD_CLK_SOURCE -18 // DEPRECATED
6281 #define PI_BAD_CLK_MICROS -19 // clock micros not 1, 2, 4, 5, 8, or 10
6282 #define PI_BAD_BUF_MILLIS -20 // buf millis not 100-10000
6283 #define PI_BAD_DUTYRANGE -21 // dutycycle range not 25-40000
6284 #define PI_BAD_DUTY_RANGE -21 // DEPRECATED (use PI_BAD_DUTYRANGE)
6285 #define PI_BAD_SIGNUM -22 // signum not 0-63
6286 #define PI_BAD_PATHNAME -23 // can't open pathname
6287 #define PI_NO_HANDLE -24 // no handle available
6288 #define PI_BAD_HANDLE -25 // unknown handle
6289 #define PI_BAD_IF_FLAGS -26 // ifFlags > 4
6290 #define PI_BAD_CHANNEL -27 // DMA channel not 0-14
6291 #define PI_BAD_PRIM_CHANNEL -27 // DMA primary channel not 0-14
6292 #define PI_BAD_SOCKET_PORT -28 // socket port not 1024-32000
6293 #define PI_BAD_FIFO_COMMAND -29 // unrecognized fifo command
6294 #define PI_BAD_SECO_CHANNEL -30 // DMA secondary channel not 0-6
6295 #define PI_NOT_INITIALISED -31 // function called before gpioInitialise
6296 #define PI_INITIALISED -32 // function called after gpioInitialise
6297 #define PI_BAD_WAVE_MODE -33 // waveform mode not 0-3
6298 #define PI_BAD_CFG_INTERNAL -34 // bad parameter in gpioCfgInternals call
6299 #define PI_BAD_WAVE_BAUD -35 // baud rate not 50-250K(RX)/50-1M(TX)
6300 #define PI_TOO_MANY_PULSES -36 // waveform has too many pulses
6301 #define PI_TOO_MANY_CHARS -37 // waveform has too many chars
6302 #define PI_NOT_SERIAL_GPIO -38 // no bit bang serial read on GPIO
6303 #define PI_BAD_SERIAL_STRUC -39 // bad (null) serial structure parameter
6304 #define PI_BAD_SERIAL_BUF -40 // bad (null) serial buf parameter
6305 #define PI_NOT_PERMITTED -41 // GPIO operation not permitted
6306 #define PI_SOME_PERMITTED -42 // one or more GPIO not permitted
6307 #define PI_BAD_WVSC_COMMND -43 // bad WVSC subcommand
6308 #define PI_BAD_WVSM_COMMND -44 // bad WVSM subcommand
6309 #define PI_BAD_WVSP_COMMND -45 // bad WVSP subcommand
6310 #define PI_BAD_PULSELEN -46 // trigger pulse length not 1-100
6311 #define PI_BAD_SCRIPT -47 // invalid script
6312 #define PI_BAD_SCRIPT_ID -48 // unknown script id
6313 #define PI_BAD_SER_OFFSET -49 // add serial data offset > 30 minutes
6314 #define PI_GPIO_IN_USE -50 // GPIO already in use
6315 #define PI_BAD_SERIAL_COUNT -51 // must read at least a byte at a time
6316 #define PI_BAD_PARAM_NUM -52 // script parameter id not 0-9
6317 #define PI_DUP_TAG -53 // script has duplicate tag
6318 #define PI_TOO_MANY_TAGS -54 // script has too many tags
6319 #define PI_BAD_SCRIPT_CMD -55 // illegal script command
6320 #define PI_BAD_VAR_NUM -56 // script variable id not 0-149
6321 #define PI_NO_SCRIPT_ROOM -57 // no more room for scripts
6322 #define PI_NO_MEMORY -58 // can't allocate temporary memory
6323 #define PI_SOCK_READ_FAILED -59 // socket read failed
6324 #define PI_SOCK_WRIT_FAILED -60 // socket write failed
6325 #define PI_TOO_MANY_PARAM -61 // too many script parameters (> 10)
6326 #define PI_NOT_HALTED -62 // DEPRECATED
6327 #define PI_SCRIPT_NOT_READY -62 // script initialising
6328 #define PI_BAD_TAG -63 // script has unresolved tag
6329 #define PI_BAD_MICS_DELAY -64 // bad MICS delay (too large)
6330 #define PI_BAD_MILS_DELAY -65 // bad MILS delay (too large)
6331 #define PI_BAD_WAVE_ID -66 // non existent wave id
6332 #define PI_TOO_MANY_CBS -67 // No more CBs for waveform
6333 #define PI_TOO_MANY_OOL -68 // No more OOL for waveform
6334 #define PI_EMPTY_WAVEFORM -69 // attempt to create an empty waveform
6335 #define PI_NO_WAVEFORM_ID -70 // no more waveforms
6336 #define PI_I2C_OPEN_FAILED -71 // can't open I2C device
6337 #define PI_SER_OPEN_FAILED -72 // can't open serial device
6338 #define PI_SPI_OPEN_FAILED -73 // can't open SPI device
6339 #define PI_BAD_I2C_BUS -74 // bad I2C bus
6340 #define PI_BAD_I2C_ADDR -75 // bad I2C address
6341 #define PI_BAD_SPI_CHANNEL -76 // bad SPI channel
6342 #define PI_BAD_FLAGS -77 // bad i2c/spi/ser open flags
6343 #define PI_BAD_SPI_SPEED -78 // bad SPI speed
6344 #define PI_BAD_SER_DEVICE -79 // bad serial device name
6345 #define PI_BAD_SER_SPEED -80 // bad serial baud rate
6346 #define PI_BAD_PARAM -81 // bad i2c/spi/ser parameter
6347 #define PI_I2C_WRITE_FAILED -82 // i2c write failed
6348 #define PI_I2C_READ_FAILED -83 // i2c read failed
6349 #define PI_BAD_SPI_COUNT -84 // bad SPI count
6350 #define PI_SER_WRITE_FAILED -85 // ser write failed
6351 #define PI_SER_READ_FAILED -86 // ser read failed
6352 #define PI_SER_READ_NO_DATA -87 // ser read no data available
6353 #define PI_UNKNOWN_COMMAND -88 // unknown command
6354 #define PI_SPI_XFER_FAILED -89 // spi xfer/read/write failed
6355 #define PI_BAD_POINTER -90 // bad (NULL) pointer
6356 #define PI_NO_AUX_SPI -91 // no auxiliary SPI on Pi A or B
6357 #define PI_NOT_PWM_GPIO -92 // GPIO is not in use for PWM
6358 #define PI_NOT_SERVO_GPIO -93 // GPIO is not in use for servo pulses
6359 #define PI_NOT_HCLK_GPIO -94 // GPIO has no hardware clock
6360 #define PI_NOT_HPWM_GPIO -95 // GPIO has no hardware PWM
6361 #define PI_BAD_HPWM_FREQ -96 // hardware PWM frequency not 1-125M
6362 #define PI_BAD_HPWM_DUTY -97 // hardware PWM dutycycle not 0-1M
6363 #define PI_BAD_HCLK_FREQ -98 // hardware clock frequency not 4689-250M
6364 #define PI_BAD_HCLK_PASS -99 // need password to use hardware clock 1
6365 #define PI_HPWM_ILLEGAL -100 // illegal, PWM in use for main clock
6366 #define PI_BAD_DATABITS -101 // serial data bits not 1-32
6367 #define PI_BAD_STOPBITS -102 // serial (half) stop bits not 2-8
6368 #define PI_MSG_TOOBIG -103 // socket/pipe message too big
6369 #define PI_BAD_MALLOC_MODE -104 // bad memory allocation mode
6370 #define PI_TOO_MANY_SEGS -105 // too many I2C transaction segments
6371 #define PI_BAD_I2C_SEG -106 // an I2C transaction segment failed
6372 #define PI_BAD_SMBUS_CMD -107 // SMBus command not supported by driver
6373 #define PI_NOT_I2C_GPIO -108 // no bit bang I2C in progress on GPIO
6374 #define PI_BAD_I2C_WLEN -109 // bad I2C write length
6375 #define PI_BAD_I2C_RLEN -110 // bad I2C read length
6376 #define PI_BAD_I2C_CMD -111 // bad I2C command
6377 #define PI_BAD_I2C_BAUD -112 // bad I2C baud rate, not 50-500k
6378 #define PI_CHAIN_LOOP_CNT -113 // bad chain loop count
6379 #define PI_BAD_CHAIN_LOOP -114 // empty chain loop
6380 #define PI_CHAIN_COUNTER -115 // too many chain counters
6381 #define PI_BAD_CHAIN_CMD -116 // bad chain command
6382 #define PI_BAD_CHAIN_DELAY -117 // bad chain delay micros
6383 #define PI_CHAIN_NESTING -118 // chain counters nested too deeply
6384 #define PI_CHAIN_TOO_BIG -119 // chain is too long
6385 #define PI_DEPRECATED -120 // deprecated function removed
6386 #define PI_BAD_SER_INVERT -121 // bit bang serial invert not 0 or 1
6387 #define PI_BAD_EDGE -122 // bad ISR edge value, not 0-2
6388 #define PI_BAD_ISR_INIT -123 // bad ISR initialisation
6389 #define PI_BAD_FOREVER -124 // loop forever must be last command
6390 #define PI_BAD_FILTER -125 // bad filter parameter
6391 #define PI_BAD_PAD -126 // bad pad number
6392 #define PI_BAD_STRENGTH -127 // bad pad drive strength
6393 #define PI_FIL_OPEN_FAILED -128 // file open failed
6394 #define PI_BAD_FILE_MODE -129 // bad file mode
6395 #define PI_BAD_FILE_FLAG -130 // bad file flag
6396 #define PI_BAD_FILE_READ -131 // bad file read
6397 #define PI_BAD_FILE_WRITE -132 // bad file write
6398 #define PI_FILE_NOT_ROPEN -133 // file not open for read
6399 #define PI_FILE_NOT_WOPEN -134 // file not open for write
6400 #define PI_BAD_FILE_SEEK -135 // bad file seek
6401 #define PI_NO_FILE_MATCH -136 // no files match pattern
6402 #define PI_NO_FILE_ACCESS -137 // no permission to access file
6403 #define PI_FILE_IS_A_DIR -138 // file is a directory
6404 #define PI_BAD_SHELL_STATUS -139 // bad shell return status
6405 #define PI_BAD_SCRIPT_NAME -140 // bad script name
6406 #define PI_BAD_SPI_BAUD -141 // bad SPI baud rate, not 50-500k
6407 #define PI_NOT_SPI_GPIO -142 // no bit bang SPI in progress on GPIO
6408 #define PI_BAD_EVENT_ID -143 // bad event id
6409 #define PI_CMD_INTERRUPTED -144 // Used by Python
6411 #define PI_PIGIF_ERR_0 -2000
6412 #define PI_PIGIF_ERR_99 -2099
6414 #define PI_CUSTOM_ERR_0 -3000
6415 #define PI_CUSTOM_ERR_999 -3999
6421 #define PI_DEFAULT_BUFFER_MILLIS 120
6422 #define PI_DEFAULT_CLK_MICROS 5
6423 #define PI_DEFAULT_CLK_PERIPHERAL PI_CLOCK_PCM
6424 #define PI_DEFAULT_IF_FLAGS 0
6425 #define PI_DEFAULT_FOREGROUND 0
6426 #define PI_DEFAULT_DMA_CHANNEL 14
6427 #define PI_DEFAULT_DMA_PRIMARY_CHANNEL 14
6428 #define PI_DEFAULT_DMA_SECONDARY_CHANNEL 6
6429 #define PI_DEFAULT_SOCKET_PORT 8888
6430 #define PI_DEFAULT_SOCKET_PORT_STR "8888"
6431 #define PI_DEFAULT_SOCKET_ADDR_STR "127.0.0.1"
6432 #define PI_DEFAULT_UPDATE_MASK_UNKNOWN 0x0000000FFFFFFCLL
6433 #define PI_DEFAULT_UPDATE_MASK_B1 0x03E7CF93
6434 #define PI_DEFAULT_UPDATE_MASK_A_B2 0xFBC7CF9C
6435 #define PI_DEFAULT_UPDATE_MASK_APLUS_BPLUS 0x0080480FFFFFFCLL
6436 #define PI_DEFAULT_UPDATE_MASK_ZERO 0x0080000FFFFFFCLL
6437 #define PI_DEFAULT_UPDATE_MASK_PI2B 0x0080480FFFFFFCLL
6438 #define PI_DEFAULT_UPDATE_MASK_PI3B 0x0000000FFFFFFCLL
6439 #define PI_DEFAULT_UPDATE_MASK_COMPUTE 0x00FFFFFFFFFFFFLL
6440 #define PI_DEFAULT_MEM_ALLOC_MODE PI_MEM_ALLOC_AUTO
6442 #define PI_DEFAULT_CFG_INTERNALS 0
int gpioHardwareClock(unsigned gpio, unsigned clkfreq)
uint32_t gpioRead_Bits_0_31(void)
int gpioCfgBufferSize(unsigned cfgMillis)
int spiWrite(unsigned handle, char *buf, unsigned count)
void(* gpioGetSamplesFuncEx_t)(const gpioSample_t *samples, int numSamples, void *userdata)
int gpioWaveGetMaxCbs(void)
int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency)
int spiRead(unsigned handle, char *buf, unsigned count)
int serWriteByte(unsigned handle, unsigned bVal)
int fileList(char *fpat, char *buf, unsigned count)
int gpioCustom1(unsigned arg1, unsigned arg2, char *argx, unsigned argc)
int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs)
int gpioGetPad(unsigned pad)
int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags)
int gpioGetMode(unsigned gpio)
int gpioCfgSetInternals(uint32_t cfgVal)
int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits)
int i2cReadByte(unsigned handle)
void *() gpioThreadFunc_t(void *)
int gpioWaveGetMaxPulses(void)
int gpioSetISRFuncEx(unsigned gpio, unsigned edge, int timeout, gpioISRFuncEx_t f, void *userdata)
int gpioSetTimerFuncEx(unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata)
int gpioSetMode(unsigned gpio, unsigned mode)
int gpioCfgPermissions(uint64_t updateMask)
int bbI2CZip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
int serRead(unsigned handle, char *buf, unsigned count)
int gpioNotifyPause(unsigned handle)
int i2cZip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
void gpioStopThread(pthread_t *pth)
int i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal)
int fileOpen(char *file, unsigned mode)
int gpioSetISRFunc(unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f)
static uint64_t updateMask
int fileClose(unsigned handle)
int gpioSerialRead(unsigned user_gpio, void *buf, size_t bufSize)
uint32_t gpioCfgGetInternals(void)
int i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf)
void(* gpioAlertFuncEx_t)(int gpio, int level, uint32_t tick, void *userdata)
int bbSPIXfer(unsigned CS, char *inBuf, char *outBuf, unsigned count)
int gpioCfgInternals(unsigned cfgWhat, unsigned cfgVal)
int bbSPIClose(unsigned CS)
unsigned gpioVersion(void)
static unsigned memAllocMode
rawWaveInfo_t rawWaveInfo(int wave_id)
int gpioWaveDelete(unsigned wave_id)
int gpioRead(unsigned gpio)
pthread_t * gpioStartThread(gpioThreadFunc_t f, void *userdata)
int gpioCfgNetAddr(int numSockAddr, uint32_t *sockAddr)
int gpioSetPWMrange(unsigned user_gpio, unsigned range)
int gpioSetGetSamplesFuncEx(gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata)
void(* gpioAlertFunc_t)(int gpio, int level, uint32_t tick)
void samples(const gpioSample_t *samples, int numSamples)
uint32_t rawWaveGetIn(int pos)
int serDataAvailable(unsigned handle)
int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses)
void i2cSwitchCombined(int setting)
int serReadByte(unsigned handle)
void(* gpioISRFuncEx_t)(int gpio, int level, uint32_t tick, void *userdata)
void rawWaveSetOOL(int pos, uint32_t lVal)
int shell(char *scriptName, char *scriptString)
int gpioGetPWMrange(unsigned user_gpio)
void time_sleep(double seconds)
int gpioSetPad(unsigned pad, unsigned padStrength)
int gpioWaveChain(char *buf, unsigned bufSize)
int gpioScriptStatus(unsigned script_id, uint32_t *param)
int getBitInBytes(int bitPos, char *buf, int numBits)
void putBitInBytes(int bitPos, char *buf, int bit)
int gpioCfgDMAchannel(unsigned DMAchannel)
int gpioStoreScript(char *script)
int gpioWaveAddSerial(unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)
void rawWaveSetIn(int pos, uint32_t lVal)
int i2cBlockProcessCall(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode)
unsigned gpioHardwareRevision(void)
void(* gpioTimerFuncEx_t)(void *userdata)
int gpioPWM(unsigned user_gpio, unsigned dutycycle)
int gpioSleep(unsigned timetype, int seconds, int micros)
int gpioNotifyOpenWithSize(int bufSize)
int gpioServo(unsigned user_gpio, unsigned pulsewidth)
int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param)
int gpioWaveGetPulses(void)
int gpioCfgDMAchannels(unsigned primaryChannel, unsigned secondaryChannel)
void(* gpioGetSamplesFunc_t)(const gpioSample_t *samples, int numSamples)
int serWrite(unsigned handle, char *buf, unsigned count)
int i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal)
int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud)
int eventTrigger(unsigned event)
int gpioDeleteScript(unsigned script_id)
int gpioCfgMemAlloc(unsigned memAllocMode)
int gpioWrite(unsigned gpio, unsigned level)
void(* gpioISRFunc_t)(int gpio, int level, uint32_t tick)
int gpioCustom2(unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)
int bbI2CClose(unsigned SDA)
int gpioNotifyClose(unsigned handle)
int eventSetFunc(unsigned event, eventFunc_t f)
int i2cReadDevice(unsigned handle, char *buf, unsigned count)
int i2cReadByteData(unsigned handle, unsigned i2cReg)
uint32_t gpioRead_Bits_32_53(void)
int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)
int gpioGetServoPulsewidth(unsigned user_gpio)
int i2cWriteByte(unsigned handle, unsigned bVal)
int gpioNotifyBegin(unsigned handle, uint32_t bits)
int gpioStopScript(unsigned script_id)
int eventMonitor(unsigned handle, uint32_t bits)
int bbSPIOpen(unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spiFlags)
void rawWaveSetOut(int pos, uint32_t lVal)
int i2cReadI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
int gpioWaveGetHighMicros(void)
rawCbs_t * rawWaveCBAdr(int cbNum)
int gpioSetAlertFuncEx(unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata)
int fileRead(unsigned handle, char *buf, unsigned count)
int serClose(unsigned handle)
int gpioSetSignalFuncEx(unsigned signum, gpioSignalFuncEx_t f, void *userdata)
int gpioGetPWMrealRange(unsigned user_gpio)
int bsc_xfer(int pi, bsc_xfer_t *bscxfer)
int i2cWriteDevice(unsigned handle, char *buf, unsigned count)
int spiClose(unsigned handle)
int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses)
int i2cWriteI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
int i2cClose(unsigned handle)
int i2cReadWordData(unsigned handle, unsigned i2cReg)
int gpioWaveGetMaxMicros(void)
int gpioCfgClock(unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource)
int gpioWrite_Bits_32_53_Clear(uint32_t bits)
int i2cWriteBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
int bscXfer(bsc_xfer_t *bsc_xfer)
int gpioSerialReadOpen(unsigned user_gpio, unsigned baud, unsigned data_bits)
void(* gpioSignalFuncEx_t)(int signum, void *userdata)
uint32_t gpioDelay(uint32_t micros)
int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f)
int gpioTime(unsigned timetype, int *seconds, int *micros)
int gpioCfgSocketPort(unsigned port)
int gpioWrite_Bits_32_53_Set(uint32_t bits)
int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom)
uint32_t rawWaveGetOut(int pos)
int fileWrite(unsigned handle, char *buf, unsigned count)
int gpioWrite_Bits_0_31_Set(uint32_t bits)
int gpioSetWatchdog(unsigned user_gpio, unsigned timeout)
int spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags)
void(* eventFunc_t)(int event, uint32_t tick)
int gpioWaveGetMicros(void)
int gpioGetPWMfrequency(unsigned user_gpio)
int i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal)
uint32_t rawWaveGetOOL(int pos)
void(* gpioTimerFunc_t)(void)
int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f)
int gpioSetPullUpDown(unsigned gpio, unsigned pud)
int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level)
int gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param)
int gpioWaveGetHighCbs(void)
int gpioWaveGetHighPulses(void)
int gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active)
int gpioSerialReadClose(unsigned user_gpio)
int gpioCfgInterfaces(unsigned ifFlags)
int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata)
void(* gpioSignalFunc_t)(int signum)
int i2cWriteQuick(unsigned handle, unsigned bit)
void(* eventFuncEx_t)(int event, uint32_t tick, void *userdata)
int rawWaveAddSPI(rawSPI_t *spi, unsigned offset, unsigned spiSS, char *buf, unsigned spiTxBits, unsigned spiBitFirst, unsigned spiBitLast, unsigned spiBits)
int serOpen(char *sertty, unsigned baud, unsigned serFlags)
int gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty)
int gpioWrite_Bits_0_31_Clear(uint32_t bits)
int gpioSerialReadInvert(unsigned user_gpio, unsigned invert)
int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f)
int gpioGetPWMdutycycle(unsigned user_gpio)
void rawDumpScript(unsigned script_id)
int gpioGlitchFilter(unsigned user_gpio, unsigned steady)
cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Fri Aug 2 2024 09:40:56