pigpio.h
Go to the documentation of this file.
1 /*
2 This is free and unencumbered software released into the public domain.
3 
4 Anyone is free to copy, modify, publish, use, compile, sell, or
5 distribute this software, either in source code form or as a compiled
6 binary, for any purpose, commercial or non-commercial, and by any
7 means.
8 
9 In jurisdictions that recognize copyright laws, the author or authors
10 of this software dedicate any and all copyright interest in the
11 software to the public domain. We make this dedication for the benefit
12 of the public at large and to the detriment of our heirs and
13 successors. We intend this dedication to be an overt act of
14 relinquishment in perpetuity of all present and future rights to this
15 software under copyright law.
16 
17 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
18 EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
19 MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
20 IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
21 OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
22 ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
23 OTHER DEALINGS IN THE SOFTWARE.
24 
25 For more information, please refer to <http://unlicense.org/>
26 */
27 
28 #ifndef PIGPIO_H
29 #define PIGPIO_H
30 
31 #include <stdint.h>
32 #include <pthread.h>
33 
34 #define PIGPIO_VERSION 67
35 
36 /*TEXT
37 
38 pigpio is a C library for the Raspberry which allows control of the GPIO.
39 
40 *Features*
41 
42 o hardware timed PWM on any of GPIO 0-31
43 
44 o hardware timed servo pulses on any of GPIO 0-31
45 
46 o callbacks when any of GPIO 0-31 change state
47 
48 o callbacks at timed intervals
49 
50 o reading/writing all of the GPIO in a bank as one operation
51 
52 o individually setting GPIO modes, reading and writing
53 
54 o notifications when any of GPIO 0-31 change state
55 
56 o the construction of output waveforms with microsecond timing
57 
58 o rudimentary permission control over GPIO
59 
60 o a simple interface to start and stop new threads
61 
62 o I2C, SPI, and serial link wrappers
63 
64 o creating and running scripts
65 
66 *GPIO*
67 
68 ALL GPIO are identified by their Broadcom number.
69 
70 *Credits*
71 
72 The PWM and servo pulses are timed using the DMA and PWM peripherals.
73 
74 This use was inspired by Richard Hirst's servoblaster kernel module.
75 
76 See [[https://github.com/richardghirst/PiBits/tree/master/ServoBlaster]]
77 
78 *Usage*
79 
80 Include <pigpio.h> in your source files.
81 
82 Assuming your source is in prog.c use the following command to build and
83 run the executable.
84 
85 . .
86 gcc -Wall -pthread -o prog prog.c -lpigpio -lrt
87 sudo ./prog
88 . .
89 
90 For examples of usage see the C programs within the pigpio archive file.
91 
92 *Notes*
93 
94 All the functions which return an int return < 0 on error.
95 
96 [*gpioInitialise*] must be called before all other library functions
97 with the following exceptions:
98 
99 . .
100 [*gpioCfg**]
101 [*gpioVersion*]
102 [*gpioHardwareRevision*]
103 . .
104 
105 If the library is not initialised all but the [*gpioCfg**],
106 [*gpioVersion*], and [*gpioHardwareRevision*] functions will
107 return error PI_NOT_INITIALISED.
108 
109 If the library is initialised the [*gpioCfg**] functions will return
110 error PI_INITIALISED.
111 
112 TEXT*/
113 
114 /*OVERVIEW
115 
116 ESSENTIAL
117 
118 gpioInitialise Initialise library
119 gpioTerminate Stop library
120 
121 BEGINNER
122 
123 gpioSetMode Set a GPIO mode
124 gpioGetMode Get a GPIO mode
125 
126 gpioSetPullUpDown Set/clear GPIO pull up/down resistor
127 
128 gpioRead Read a GPIO
129 gpioWrite Write a GPIO
130 
131 gpioPWM Start/stop PWM pulses on a GPIO
132 gpioGetPWMdutycycle Get dutycycle setting on a GPIO
133 
134 gpioServo Start/stop servo pulses on a GPIO
135 gpioGetServoPulsewidth Get pulsewidth setting on a GPIO
136 
137 gpioDelay Delay for a number of microseconds
138 
139 gpioSetAlertFunc Request a GPIO level change callback
140 
141 gpioSetTimerFunc Request a regular timed callback
142 
143 INTERMEDIATE
144 
145 gpioTrigger Send a trigger pulse to a GPIO.
146 
147 gpioSetWatchdog Set a watchdog on a GPIO.
148 
149 gpioSetPWMrange Configure PWM range for a GPIO
150 gpioGetPWMrange Get configured PWM range for a GPIO
151 
152 gpioSetPWMfrequency Configure PWM frequency for a GPIO
153 gpioGetPWMfrequency Get configured PWM frequency for a GPIO
154 
155 gpioRead_Bits_0_31 Read all GPIO in bank 1
156 gpioRead_Bits_32_53 Read all GPIO in bank 2
157 
158 gpioWrite_Bits_0_31_Clear Clear selected GPIO in bank 1
159 gpioWrite_Bits_32_53_Clear Clear selected GPIO in bank 2
160 
161 gpioWrite_Bits_0_31_Set Set selected GPIO in bank 1
162 gpioWrite_Bits_32_53_Set Set selected GPIO in bank 2
163 
164 gpioStartThread Start a new thread
165 gpioStopThread Stop a previously started thread
166 
167 ADVANCED
168 
169 gpioGetPWMrealRange Get underlying PWM range for a GPIO
170 
171 gpioSetAlertFuncEx Request a GPIO change callback, extended
172 
173 gpioSetISRFunc Request a GPIO interrupt callback
174 gpioSetISRFuncEx Request a GPIO interrupt callback, extended
175 
176 gpioSetSignalFunc Request a signal callback
177 gpioSetSignalFuncEx Request a signal callback, extended
178 
179 gpioSetGetSamplesFunc Requests a GPIO samples callback
180 gpioSetGetSamplesFuncEx Requests a GPIO samples callback, extended
181 
182 gpioSetTimerFuncEx Request a regular timed callback, extended
183 
184 gpioNotifyOpen Request a notification handle
185 gpioNotifyOpenWithSize Request a notification handle with sized pipe
186 gpioNotifyBegin Start notifications for selected GPIO
187 gpioNotifyPause Pause notifications
188 gpioNotifyClose Close a notification
189 
190 gpioSerialReadOpen Opens a GPIO for bit bang serial reads
191 gpioSerialReadInvert Configures normal/inverted for serial reads
192 gpioSerialRead Reads bit bang serial data from a GPIO
193 gpioSerialReadClose Closes a GPIO for bit bang serial reads
194 
195 gpioHardwareClock Start hardware clock on supported GPIO
196 gpioHardwarePWM Start hardware PWM on supported GPIO
197 
198 gpioGlitchFilter Set a glitch filter on a GPIO
199 gpioNoiseFilter Set a noise filter on a GPIO
200 
201 gpioGetPad Gets a pads drive strength
202 gpioSetPad Sets a pads drive strength
203 
204 shell Executes a shell command
205 
206 SCRIPTS
207 
208 gpioStoreScript Store a script
209 gpioRunScript Run a stored script
210 gpioUpdateScript Set a scripts parameters
211 gpioScriptStatus Get script status and parameters
212 gpioStopScript Stop a running script
213 gpioDeleteScript Delete a stored script
214 
215 WAVES
216 
217 gpioWaveClear Deletes all waveforms
218 
219 gpioWaveAddNew Starts a new waveform
220 gpioWaveAddGeneric Adds a series of pulses to the waveform
221 gpioWaveAddSerial Adds serial data to the waveform
222 
223 gpioWaveCreate Creates a waveform from added data
224 gpioWaveDelete Deletes a waveform
225 
226 gpioWaveTxSend Transmits a waveform
227 
228 gpioWaveChain Transmits a chain of waveforms
229 
230 gpioWaveTxAt Returns the current transmitting waveform
231 
232 gpioWaveTxBusy Checks to see if the waveform has ended
233 gpioWaveTxStop Aborts the current waveform
234 
235 gpioWaveGetMicros Length in microseconds of the current waveform
236 gpioWaveGetHighMicros Length of longest waveform so far
237 gpioWaveGetMaxMicros Absolute maximum allowed micros
238 
239 gpioWaveGetPulses Length in pulses of the current waveform
240 gpioWaveGetHighPulses Length of longest waveform so far
241 gpioWaveGetMaxPulses Absolute maximum allowed pulses
242 
243 gpioWaveGetCbs Length in control blocks of the current waveform
244 gpioWaveGetHighCbs Length of longest waveform so far
245 gpioWaveGetMaxCbs Absolute maximum allowed control blocks
246 
247 I2C
248 
249 i2cOpen Opens an I2C device
250 i2cClose Closes an I2C device
251 
252 i2cWriteQuick SMBus write quick
253 i2cWriteByte SMBus write byte
254 i2cReadByte SMBus read byte
255 i2cWriteByteData SMBus write byte data
256 i2cWriteWordData SMBus write word data
257 i2cReadByteData SMBus read byte data
258 i2cReadWordData SMBus read word data
259 i2cProcessCall SMBus process call
260 i2cWriteBlockData SMBus write block data
261 i2cReadBlockData SMBus read block data
262 i2cBlockProcessCall SMBus block process call
263 
264 i2cWriteI2CBlockData SMBus write I2C block data
265 i2cReadI2CBlockData SMBus read I2C block data
266 
267 i2cReadDevice Reads the raw I2C device
268 i2cWriteDevice Writes the raw I2C device
269 
270 i2cSwitchCombined Sets or clears the combined flag
271 
272 i2cSegments Performs multiple I2C transactions
273 
274 i2cZip Performs multiple I2C transactions
275 
276 bbI2COpen Opens GPIO for bit banging I2C
277 bbI2CClose Closes GPIO for bit banging I2C
278 bbI2CZip Performs multiple bit banged I2C transactions
279 
280 SPI
281 
282 spiOpen Opens a SPI device
283 spiClose Closes a SPI device
284 
285 spiRead Reads bytes from a SPI device
286 spiWrite Writes bytes to a SPI device
287 spiXfer Transfers bytes with a SPI device
288 
289 bbSPIOpen Opens GPIO for bit banging SPI
290 bbSPIClose Closes GPIO for bit banging SPI
291 bbSPIXfer Performs multiple bit banged SPI transactions
292 
293 I2C/SPI_SLAVE
294 
295 bscXfer I2C/SPI as slave transfer
296 
297 SERIAL
298 
299 serOpen Opens a serial device
300 serClose Closes a serial device
301 
302 serReadByte Reads a byte from a serial device
303 serWriteByte Writes a byte to a serial device
304 serRead Reads bytes from a serial device
305 serWrite Writes bytes to a serial device
306 
307 serDataAvailable Returns number of bytes ready to be read
308 
309 FILES
310 
311 fileOpen Opens a file
312 fileClose Closes a file
313 fileRead Reads bytes from a file
314 fileWrite Writes bytes to a file
315 fileSeek Seeks to a position within a file
316 fileList List files which match a pattern
317 
318 EVENTS
319 
320 eventMonitor Sets the events to monitor
321 eventSetFunc Request an event callback
322 eventSetFuncEx Request an event callback, extended
323 eventTrigger Trigger an event
324 
325 CONFIGURATION
326 
327 gpioCfgBufferSize Configure the GPIO sample buffer size
328 gpioCfgClock Configure the GPIO sample rate
329 gpioCfgDMAchannel Configure the DMA channel (DEPRECATED)
330 gpioCfgDMAchannels Configure the DMA channels
331 gpioCfgPermissions Configure the GPIO access permissions
332 gpioCfgInterfaces Configure user interfaces
333 gpioCfgSocketPort Configure socket port
334 gpioCfgMemAlloc Configure DMA memory allocation mode
335 gpioCfgNetAddr Configure allowed network addresses
336 
337 gpioCfgInternals Configure miscellaneous internals (DEPRECATED)
338 gpioCfgGetInternals Get internal configuration settings
339 gpioCfgSetInternals Set internal configuration settings
340 
341 CUSTOM
342 
343 gpioCustom1 User custom function 1
344 gpioCustom2 User custom function 2
345 
346 UTILITIES
347 
348 gpioTick Get current tick (microseconds)
349 
350 gpioHardwareRevision Get hardware revision
351 gpioVersion Get the pigpio version
352 
353 getBitInBytes Get the value of a bit
354 putBitInBytes Set the value of a bit
355 
356 gpioTime Get current time
357 gpioSleep Sleep for specified time
358 
359 time_sleep Sleeps for a float number of seconds
360 time_time Float number of seconds since the epoch
361 
362 EXPERT
363 
364 rawWaveAddSPI Not intended for general use
365 rawWaveAddGeneric Not intended for general use
366 rawWaveCB Not intended for general use
367 rawWaveCBAdr Not intended for general use
368 rawWaveGetOOL Not intended for general use
369 rawWaveSetOOL Not intended for general use
370 rawWaveGetOut Not intended for general use
371 rawWaveSetOut Not intended for general use
372 rawWaveGetIn Not intended for general use
373 rawWaveSetIn Not intended for general use
374 rawWaveInfo Not intended for general use
375 rawDumpWave Not intended for general use
376 rawDumpScript Not intended for general use
377 
378 OVERVIEW*/
379 
380 #define PI_INPFIFO "/dev/pigpio"
381 #define PI_OUTFIFO "/dev/pigout"
382 #define PI_ERRFIFO "/dev/pigerr"
383 
384 #define PI_ENVPORT "PIGPIO_PORT"
385 #define PI_ENVADDR "PIGPIO_ADDR"
386 
387 #define PI_LOCKFILE "/var/run/pigpio.pid"
388 
389 #define PI_I2C_COMBINED "/sys/module/i2c_bcm2708/parameters/combined"
390 
391 #ifdef __cplusplus
392 extern "C" {
393 #endif
394 
395 typedef struct
396 {
397  uint16_t func;
398  uint16_t size;
399 } gpioHeader_t;
400 
401 typedef struct
402 {
403  size_t size;
404  void *ptr;
405  uint32_t data;
406 } gpioExtent_t;
407 
408 typedef struct
409 {
410  uint32_t tick;
411  uint32_t level;
412 } gpioSample_t;
413 
414 typedef struct
415 {
416  uint16_t seqno;
417  uint16_t flags;
418  uint32_t tick;
419  uint32_t level;
420 } gpioReport_t;
421 
422 typedef struct
423 {
424  uint32_t gpioOn;
425  uint32_t gpioOff;
426  uint32_t usDelay;
427 } gpioPulse_t;
428 
429 #define WAVE_FLAG_READ 1
430 #define WAVE_FLAG_TICK 2
431 
432 typedef struct
433 {
434  uint32_t gpioOn;
435  uint32_t gpioOff;
436  uint32_t usDelay;
437  uint32_t flags;
438 } rawWave_t;
439 
440 /*
441 CBs are used in order from the lowest numbered CB up to
442 the maximum NUM_WAVE_CBS.
443 
444 OOLS are used from the bottom climbing up and from
445 the top climbing down.
446 
447 The GPIO on and off settings climb up from the bottom (botOOL/numBOOL).
448 
449 The level and tick read values are stored in descending locations
450 from the top (topOOL/numTOOL).
451 */
452 
453 typedef struct
454 {
455  uint16_t botCB; /* first CB used by wave */
456  uint16_t topCB; /* last CB used by wave */
457  uint16_t botOOL; /* first bottom OOL used by wave */
458  /* botOOL to botOOL + numBOOL - 1 are in use */
459  uint16_t topOOL; /* last top OOL used by wave */
460  /* topOOL - numTOOL to topOOL are in use.*/
461  uint16_t deleted;
462  uint16_t numCB;
463  uint16_t numBOOL;
464  uint16_t numTOOL;
465 } rawWaveInfo_t;
466 
467 typedef struct
468 {
469  int clk; /* GPIO for clock */
470  int mosi; /* GPIO for MOSI */
471  int miso; /* GPIO for MISO */
472  int ss_pol; /* slave select off state */
473  int ss_us; /* delay after slave select */
474  int clk_pol; /* clock off state */
475  int clk_pha; /* clock phase */
476  int clk_us; /* clock micros */
477 } rawSPI_t;
478 
479 typedef struct { /* linux/arch/arm/mach-bcm2708/include/mach/dma.h */
480  uint32_t info;
481  uint32_t src;
482  uint32_t dst;
483  uint32_t length;
484  uint32_t stride;
485  uint32_t next;
486  uint32_t pad[2];
487 } rawCbs_t;
488 
489 typedef struct
490 {
491  uint16_t addr; /* slave address */
492  uint16_t flags;
493  uint16_t len; /* msg length */
494  uint8_t *buf; /* pointer to msg data */
495 } pi_i2c_msg_t;
496 
497 /* BSC FIFO size */
498 
499 #define BSC_FIFO_SIZE 512
500 
501 typedef struct
502 {
503  uint32_t control; /* Write */
504  int rxCnt; /* Read only */
505  char rxBuf[BSC_FIFO_SIZE]; /* Read only */
506  int txCnt; /* Write */
507  char txBuf[BSC_FIFO_SIZE]; /* Write */
508 } bsc_xfer_t;
509 
510 
511 typedef void (*gpioAlertFunc_t) (int gpio,
512  int level,
513  uint32_t tick);
514 
515 typedef void (*gpioAlertFuncEx_t) (int gpio,
516  int level,
517  uint32_t tick,
518  void *userdata);
519 
520 typedef void (*eventFunc_t) (int event,
521  uint32_t tick);
522 
523 typedef void (*eventFuncEx_t) (int event,
524  uint32_t tick,
525  void *userdata);
526 
527 typedef void (*gpioISRFunc_t) (int gpio,
528  int level,
529  uint32_t tick);
530 
531 typedef void (*gpioISRFuncEx_t) (int gpio,
532  int level,
533  uint32_t tick,
534  void *userdata);
535 
536 typedef void (*gpioTimerFunc_t) (void);
537 
538 typedef void (*gpioTimerFuncEx_t) (void *userdata);
539 
540 typedef void (*gpioSignalFunc_t) (int signum);
541 
542 typedef void (*gpioSignalFuncEx_t) (int signum,
543  void *userdata);
544 
545 typedef void (*gpioGetSamplesFunc_t) (const gpioSample_t *samples,
546  int numSamples);
547 
549  int numSamples,
550  void *userdata);
551 
552 typedef void *(gpioThreadFunc_t) (void *);
553 
554 
555 /* gpio: 0-53 */
556 
557 #define PI_MIN_GPIO 0
558 #define PI_MAX_GPIO 53
559 
560 /* user_gpio: 0-31 */
561 
562 #define PI_MAX_USER_GPIO 31
563 
564 /* level: 0-1 */
565 
566 #define PI_OFF 0
567 #define PI_ON 1
568 
569 #define PI_CLEAR 0
570 #define PI_SET 1
571 
572 #define PI_LOW 0
573 #define PI_HIGH 1
574 
575 /* level: only reported for GPIO time-out, see gpioSetWatchdog */
576 
577 #define PI_TIMEOUT 2
578 
579 /* mode: 0-7 */
580 
581 #define PI_INPUT 0
582 #define PI_OUTPUT 1
583 #define PI_ALT0 4
584 #define PI_ALT1 5
585 #define PI_ALT2 6
586 #define PI_ALT3 7
587 #define PI_ALT4 3
588 #define PI_ALT5 2
589 
590 /* pud: 0-2 */
591 
592 #define PI_PUD_OFF 0
593 #define PI_PUD_DOWN 1
594 #define PI_PUD_UP 2
595 
596 /* dutycycle: 0-range */
597 
598 #define PI_DEFAULT_DUTYCYCLE_RANGE 255
599 
600 /* range: 25-40000 */
601 
602 #define PI_MIN_DUTYCYCLE_RANGE 25
603 #define PI_MAX_DUTYCYCLE_RANGE 40000
604 
605 /* pulsewidth: 0, 500-2500 */
606 
607 #define PI_SERVO_OFF 0
608 #define PI_MIN_SERVO_PULSEWIDTH 500
609 #define PI_MAX_SERVO_PULSEWIDTH 2500
610 
611 /* hardware PWM */
612 
613 #define PI_HW_PWM_MIN_FREQ 1
614 #define PI_HW_PWM_MAX_FREQ 125000000
615 #define PI_HW_PWM_RANGE 1000000
616 
617 /* hardware clock */
618 
619 #define PI_HW_CLK_MIN_FREQ 4689
620 #define PI_HW_CLK_MAX_FREQ 250000000
621 
622 #define PI_NOTIFY_SLOTS 32
623 
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)
628 
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)
632 
633 #define PI_BB_I2C_MIN_BAUD 50
634 #define PI_BB_I2C_MAX_BAUD 500000
635 
636 #define PI_BB_SPI_MIN_BAUD 50
637 #define PI_BB_SPI_MAX_BAUD 250000
638 
639 #define PI_BB_SER_MIN_BAUD 50
640 #define PI_BB_SER_MAX_BAUD 250000
641 
642 #define PI_BB_SER_NORMAL 0
643 #define PI_BB_SER_INVERT 1
644 
645 #define PI_WAVE_MIN_BAUD 50
646 #define PI_WAVE_MAX_BAUD 1000000
647 
648 #define PI_SPI_MIN_BAUD 32000
649 #define PI_SPI_MAX_BAUD 125000000
650 
651 #define PI_MIN_WAVE_DATABITS 1
652 #define PI_MAX_WAVE_DATABITS 32
653 
654 #define PI_MIN_WAVE_HALFSTOPBITS 2
655 #define PI_MAX_WAVE_HALFSTOPBITS 8
656 
657 #define PI_WAVE_MAX_MICROS (30 * 60 * 1000000) /* half an hour */
658 
659 #define PI_MAX_WAVES 250
660 
661 #define PI_MAX_WAVE_CYCLES 65535
662 #define PI_MAX_WAVE_DELAY 65535
663 
664 #define PI_WAVE_COUNT_PAGES 10
665 
666 /* wave tx mode */
667 
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
672 
673 /* special wave at return values */
674 
675 #define PI_WAVE_NOT_FOUND 9998 /* Transmitted wave not found. */
676 #define PI_NO_TX_WAVE 9999 /* No wave being transmitted. */
677 
678 /* Files, I2C, SPI, SER */
679 
680 #define PI_FILE_SLOTS 16
681 #define PI_I2C_SLOTS 64
682 #define PI_SPI_SLOTS 32
683 #define PI_SER_SLOTS 16
684 
685 #define PI_MAX_I2C_ADDR 0x7F
686 
687 #define PI_NUM_AUX_SPI_CHANNEL 3
688 #define PI_NUM_STD_SPI_CHANNEL 2
689 
690 #define PI_MAX_I2C_DEVICE_COUNT (1<<16)
691 #define PI_MAX_SPI_DEVICE_COUNT (1<<16)
692 
693 /* max pi_i2c_msg_t per transaction */
694 
695 #define PI_I2C_RDRW_IOCTL_MAX_MSGS 42
696 
697 /* flags for i2cTransaction, pi_i2c_msg_t */
698 
699 #define PI_I2C_M_WR 0x0000 /* write data */
700 #define PI_I2C_M_RD 0x0001 /* read data */
701 #define PI_I2C_M_TEN 0x0010 /* ten bit chip address */
702 #define PI_I2C_M_RECV_LEN 0x0400 /* length will be first received byte */
703 #define PI_I2C_M_NO_RD_ACK 0x0800 /* if I2C_FUNC_PROTOCOL_MANGLING */
704 #define PI_I2C_M_IGNORE_NAK 0x1000 /* if I2C_FUNC_PROTOCOL_MANGLING */
705 #define PI_I2C_M_REV_DIR_ADDR 0x2000 /* if I2C_FUNC_PROTOCOL_MANGLING */
706 #define PI_I2C_M_NOSTART 0x4000 /* if I2C_FUNC_PROTOCOL_MANGLING */
707 
708 /* bbI2CZip and i2cZip commands */
709 
710 #define PI_I2C_END 0
711 #define PI_I2C_ESC 1
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
720 
721 /* SPI */
722 
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))
732 
733 /* BSC registers */
734 
735 #define BSC_DR 0
736 #define BSC_RSR 1
737 #define BSC_SLV 2
738 #define BSC_CR 3
739 #define BSC_FR 4
740 #define BSC_IFLS 5
741 #define BSC_IMSC 6
742 #define BSC_RIS 7
743 #define BSC_MIS 8
744 #define BSC_ICR 9
745 #define BSC_DMACR 10
746 #define BSC_TDR 11
747 #define BSC_GPUSTAT 12
748 #define BSC_HCTRL 13
749 #define BSC_DEBUG_I2C 14
750 #define BSC_DEBUG_SPI 15
751 
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
758 #define BSC_CR_I2C 4
759 #define BSC_CR_SPI 2
760 #define BSC_CR_EN 1
761 
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
768 
769 /* BSC GPIO */
770 
771 #define BSC_SDA_MOSI 18
772 #define BSC_SCL_SCLK 19
773 #define BSC_MISO 20
774 #define BSC_CE_N 21
775 
776 /* Longest busy delay */
777 
778 #define PI_MAX_BUSY_DELAY 100
779 
780 /* timeout: 0-60000 */
781 
782 #define PI_MIN_WDOG_TIMEOUT 0
783 #define PI_MAX_WDOG_TIMEOUT 60000
784 
785 /* timer: 0-9 */
786 
787 #define PI_MIN_TIMER 0
788 #define PI_MAX_TIMER 9
789 
790 /* millis: 10-60000 */
791 
792 #define PI_MIN_MS 10
793 #define PI_MAX_MS 60000
794 
795 #define PI_MAX_SCRIPTS 32
796 
797 #define PI_MAX_SCRIPT_TAGS 50
798 #define PI_MAX_SCRIPT_VARS 150
799 #define PI_MAX_SCRIPT_PARAMS 10
800 
801 /* script status */
802 
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
808 
809 /* signum: 0-63 */
810 
811 #define PI_MIN_SIGNUM 0
812 #define PI_MAX_SIGNUM 63
813 
814 /* timetype: 0-1 */
815 
816 #define PI_TIME_RELATIVE 0
817 #define PI_TIME_ABSOLUTE 1
818 
819 #define PI_MAX_MICS_DELAY 1000000 /* 1 second */
820 #define PI_MAX_MILS_DELAY 60000 /* 60 seconds */
821 
822 /* cfgMillis */
823 
824 #define PI_BUF_MILLIS_MIN 100
825 #define PI_BUF_MILLIS_MAX 10000
826 
827 /* cfgMicros: 1, 2, 4, 5, 8, or 10 */
828 
829 /* cfgPeripheral: 0-1 */
830 
831 #define PI_CLOCK_PWM 0
832 #define PI_CLOCK_PCM 1
833 
834 /* DMA channel: 0-14 */
835 
836 #define PI_MIN_DMA_CHANNEL 0
837 #define PI_MAX_DMA_CHANNEL 14
838 
839 /* port */
840 
841 #define PI_MIN_SOCKET_PORT 1024
842 #define PI_MAX_SOCKET_PORT 32000
843 
844 
845 /* ifFlags: */
846 
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
851 
852 /* memAllocMode */
853 
854 #define PI_MEM_ALLOC_AUTO 0
855 #define PI_MEM_ALLOC_PAGEMAP 1
856 #define PI_MEM_ALLOC_MAILBOX 2
857 
858 /* filters */
859 
860 #define PI_MAX_STEADY 300000
861 #define PI_MAX_ACTIVE 1000000
862 
863 /* gpioCfgInternals */
864 
865 #define PI_CFG_DBG_LEVEL 0 /* bits 0-3 */
866 #define PI_CFG_ALERT_FREQ 4 /* bits 4-7 */
867 #define PI_CFG_RT_PRIORITY (1<<8)
868 #define PI_CFG_STATS (1<<9)
869 #define PI_CFG_NOSIGHANDLER (1<<10)
870 
871 #define PI_CFG_ILLEGAL_VAL (1<<11)
872 
873 
874 /* gpioISR */
875 
876 #define RISING_EDGE 0
877 #define FALLING_EDGE 1
878 #define EITHER_EDGE 2
879 
880 
881 /* pads */
882 
883 #define PI_MAX_PAD 2
884 
885 #define PI_MIN_PAD_STRENGTH 1
886 #define PI_MAX_PAD_STRENGTH 16
887 
888 /* files */
889 
890 #define PI_FILE_NONE 0
891 #define PI_FILE_MIN 1
892 #define PI_FILE_READ 1
893 #define PI_FILE_WRITE 2
894 #define PI_FILE_RW 3
895 #define PI_FILE_APPEND 4
896 #define PI_FILE_CREATE 8
897 #define PI_FILE_TRUNC 16
898 #define PI_FILE_MAX 31
899 
900 #define PI_FROM_START 0
901 #define PI_FROM_CURRENT 1
902 #define PI_FROM_END 2
903 
904 /* Allowed socket connect addresses */
905 
906 #define MAX_CONNECT_ADDRESSES 256
907 
908 /* events */
909 
910 #define PI_MAX_EVENT 31
911 
912 /* Event auto generated on BSC slave activity */
913 
914 #define PI_EVENT_BSC 31
915 
916 /*F*/
917 int gpioInitialise(void);
918 /*D
919 Initialises the library.
920 
921 Returns the pigpio version number if OK, otherwise PI_INIT_FAILED.
922 
923 gpioInitialise must be called before using the other library functions
924 with the following exceptions:
925 
926 . .
927 [*gpioCfg**]
928 [*gpioVersion*]
929 [*gpioHardwareRevision*]
930 . .
931 
932 ...
933 if (gpioInitialise() < 0)
934 {
935  // pigpio initialisation failed.
936 }
937 else
938 {
939  // pigpio initialised okay.
940 }
941 ...
942 D*/
943 
944 
945 /*F*/
946 void gpioTerminate(void);
947 /*D
948 Terminates the library.
949 
950 Returns nothing.
951 
952 Call before program exit.
953 
954 This function resets the used DMA channels, releases memory, and
955 terminates any running threads.
956 
957 ...
958 gpioTerminate();
959 ...
960 D*/
961 
962 
963 /*F*/
964 int gpioSetMode(unsigned gpio, unsigned mode);
965 /*D
966 Sets the GPIO mode, typically input or output.
967 
968 . .
969 gpio: 0-53
970 mode: 0-7
971 . .
972 
973 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE.
974 
975 Arduino style: pinMode.
976 
977 ...
978 gpioSetMode(17, PI_INPUT); // Set GPIO17 as input.
979 
980 gpioSetMode(18, PI_OUTPUT); // Set GPIO18 as output.
981 
982 gpioSetMode(22,PI_ALT0); // Set GPIO22 to alternative mode 0.
983 ...
984 
985 See [[http://www.raspberrypi.org/documentation/hardware/raspberrypi/bcm2835/BCM2835-ARM-Peripherals.pdf]] page 102 for an overview of the modes.
986 D*/
987 
988 
989 /*F*/
990 int gpioGetMode(unsigned gpio);
991 /*D
992 Gets the GPIO mode.
993 
994 . .
995 gpio: 0-53
996 . .
997 
998 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
999 
1000 ...
1001 if (gpioGetMode(17) != PI_ALT0)
1002 {
1003  gpioSetMode(17, PI_ALT0); // set GPIO17 to ALT0
1004 }
1005 ...
1006 D*/
1007 
1008 
1009 /*F*/
1010 int gpioSetPullUpDown(unsigned gpio, unsigned pud);
1011 /*D
1012 Sets or clears resistor pull ups or downs on the GPIO.
1013 
1014 . .
1015 gpio: 0-53
1016  pud: 0-2
1017 . .
1018 
1019 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD.
1020 
1021 ...
1022 gpioSetPullUpDown(17, PI_PUD_UP); // Sets a pull-up.
1023 
1024 gpioSetPullUpDown(18, PI_PUD_DOWN); // Sets a pull-down.
1025 
1026 gpioSetPullUpDown(23, PI_PUD_OFF); // Clear any pull-ups/downs.
1027 ...
1028 D*/
1029 
1030 
1031 /*F*/
1032 int gpioRead (unsigned gpio);
1033 /*D
1034 Reads the GPIO level, on or off.
1035 
1036 . .
1037 gpio: 0-53
1038 . .
1039 
1040 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
1041 
1042 Arduino style: digitalRead.
1043 
1044 ...
1045 printf("GPIO24 is level %d", gpioRead(24));
1046 ...
1047 D*/
1048 
1049 
1050 /*F*/
1051 int gpioWrite(unsigned gpio, unsigned level);
1052 /*D
1053 Sets the GPIO level, on or off.
1054 
1055 . .
1056  gpio: 0-53
1057 level: 0-1
1058 . .
1059 
1060 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL.
1061 
1062 If PWM or servo pulses are active on the GPIO they are switched off.
1063 
1064 Arduino style: digitalWrite
1065 
1066 ...
1067 gpioWrite(24, 1); // Set GPIO24 high.
1068 ...
1069 D*/
1070 
1071 
1072 /*F*/
1073 int gpioPWM(unsigned user_gpio, unsigned dutycycle);
1074 /*D
1075 Starts PWM on the GPIO, dutycycle between 0 (off) and range (fully on).
1076 Range defaults to 255.
1077 
1078 . .
1079 user_gpio: 0-31
1080 dutycycle: 0-range
1081 . .
1082 
1083 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE.
1084 
1085 Arduino style: analogWrite
1086 
1087 This and the servo functionality use the DMA and PWM or PCM peripherals
1088 to control and schedule the pulse lengths and dutycycles.
1089 
1090 The [*gpioSetPWMrange*] function may be used to change the default
1091 range of 255.
1092 
1093 ...
1094 gpioPWM(17, 255); // Sets GPIO17 full on.
1095 
1096 gpioPWM(18, 128); // Sets GPIO18 half on.
1097 
1098 gpioPWM(23, 0); // Sets GPIO23 full off.
1099 ...
1100 D*/
1101 
1102 
1103 /*F*/
1104 int gpioGetPWMdutycycle(unsigned user_gpio);
1105 /*D
1106 Returns the PWM dutycycle setting for the GPIO.
1107 
1108 . .
1109 user_gpio: 0-31
1110 . .
1111 
1112 Returns between 0 (off) and range (fully on) if OK, otherwise
1113 PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
1114 
1115 For normal PWM the dutycycle will be out of the defined range
1116 for the GPIO (see [*gpioGetPWMrange*]).
1117 
1118 If a hardware clock is active on the GPIO the reported dutycycle
1119 will be 500000 (500k) out of 1000000 (1M).
1120 
1121 If hardware PWM is active on the GPIO the reported dutycycle
1122 will be out of a 1000000 (1M).
1123 
1124 Normal PWM range defaults to 255.
1125 D*/
1126 
1127 
1128 /*F*/
1129 int gpioSetPWMrange(unsigned user_gpio, unsigned range);
1130 /*D
1131 Selects the dutycycle range to be used for the GPIO. Subsequent calls
1132 to gpioPWM will use a dutycycle between 0 (off) and range (fully on).
1133 
1134 . .
1135 user_gpio: 0-31
1136  range: 25-40000
1137 . .
1138 
1139 Returns the real range for the given GPIO's frequency if OK,
1140 otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE.
1141 
1142 If PWM is currently active on the GPIO its dutycycle will be scaled
1143 to reflect the new range.
1144 
1145 The real range, the number of steps between fully off and fully
1146 on for each frequency, is given in the following table.
1147 
1148 . .
1149  25, 50, 100, 125, 200, 250, 400, 500, 625,
1150  800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000
1151 . .
1152 
1153 The real value set by [*gpioPWM*] is (dutycycle * real range) / range.
1154 
1155 ...
1156 gpioSetPWMrange(24, 2000); // Now 2000 is fully on
1157  // 1000 is half on
1158  // 500 is quarter on, etc.
1159 ...
1160 D*/
1161 
1162 
1163 /*F*/
1164 int gpioGetPWMrange(unsigned user_gpio);
1165 /*D
1166 Returns the dutycycle range used for the GPIO if OK, otherwise
1167 PI_BAD_USER_GPIO.
1168 
1169 . .
1170 user_gpio: 0-31
1171 . .
1172 
1173 If a hardware clock or hardware PWM is active on the GPIO
1174 the reported range will be 1000000 (1M).
1175 
1176 ...
1177 r = gpioGetPWMrange(23);
1178 ...
1179 D*/
1180 
1181 
1182 /*F*/
1183 int gpioGetPWMrealRange(unsigned user_gpio);
1184 /*D
1185 Returns the real range used for the GPIO if OK, otherwise
1186 PI_BAD_USER_GPIO.
1187 
1188 . .
1189 user_gpio: 0-31
1190 . .
1191 
1192 If a hardware clock is active on the GPIO the reported real
1193 range will be 1000000 (1M).
1194 
1195 If hardware PWM is active on the GPIO the reported real range
1196 will be approximately 250M divided by the set PWM frequency.
1197 
1198 ...
1199 rr = gpioGetPWMrealRange(17);
1200 ...
1201 D*/
1202 
1203 
1204 /*F*/
1205 int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency);
1206 /*D
1207 Sets the frequency in hertz to be used for the GPIO.
1208 
1209 . .
1210 user_gpio: 0-31
1211 frequency: >=0
1212 . .
1213 
1214 Returns the numerically closest frequency if OK, otherwise
1215 PI_BAD_USER_GPIO.
1216 
1217 If PWM is currently active on the GPIO it will be
1218 switched off and then back on at the new frequency.
1219 
1220 Each GPIO can be independently set to one of 18 different PWM
1221 frequencies.
1222 
1223 The selectable frequencies depend upon the sample rate which
1224 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5).
1225 
1226 The frequencies for each sample rate are:
1227 
1228 . .
1229  Hertz
1230 
1231  1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
1232  1250 1000 800 500 400 250 200 100 50
1233 
1234  2: 20000 10000 5000 4000 2500 2000 1250 1000 800
1235  625 500 400 250 200 125 100 50 25
1236 
1237  4: 10000 5000 2500 2000 1250 1000 625 500 400
1238  313 250 200 125 100 63 50 25 13
1239 sample
1240  rate
1241  (us) 5: 8000 4000 2000 1600 1000 800 500 400 320
1242  250 200 160 100 80 50 40 20 10
1243 
1244  8: 5000 2500 1250 1000 625 500 313 250 200
1245  156 125 100 63 50 31 25 13 6
1246 
1247  10: 4000 2000 1000 800 500 400 250 200 160
1248  125 100 80 50 40 25 20 10 5
1249 . .
1250 
1251 ...
1252 gpioSetPWMfrequency(23, 0); // Set GPIO23 to lowest frequency.
1253 
1254 gpioSetPWMfrequency(24, 500); // Set GPIO24 to 500Hz.
1255 
1256 gpioSetPWMfrequency(25, 100000); // Set GPIO25 to highest frequency.
1257 ...
1258 D*/
1259 
1260 
1261 /*F*/
1262 int gpioGetPWMfrequency(unsigned user_gpio);
1263 /*D
1264 Returns the frequency (in hertz) used for the GPIO if OK, otherwise
1265 PI_BAD_USER_GPIO.
1266 
1267 . .
1268 user_gpio: 0-31
1269 . .
1270 
1271 For normal PWM the frequency will be that defined for the GPIO by
1272 [*gpioSetPWMfrequency*].
1273 
1274 If a hardware clock is active on the GPIO the reported frequency
1275 will be that set by [*gpioHardwareClock*].
1276 
1277 If hardware PWM is active on the GPIO the reported frequency
1278 will be that set by [*gpioHardwarePWM*].
1279 
1280 ...
1281 f = gpioGetPWMfrequency(23); // Get frequency used for GPIO23.
1282 ...
1283 D*/
1284 
1285 
1286 /*F*/
1287 int gpioServo(unsigned user_gpio, unsigned pulsewidth);
1288 /*D
1289 Starts servo pulses on the GPIO, 0 (off), 500 (most anti-clockwise) to
1290 2500 (most clockwise).
1291 
1292 . .
1293  user_gpio: 0-31
1294 pulsewidth: 0, 500-2500
1295 . .
1296 
1297 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH.
1298 
1299 The range supported by servos varies and should probably be determined
1300 by experiment. A value of 1500 should always be safe and represents
1301 the mid-point of rotation. You can DAMAGE a servo if you command it
1302 to move beyond its limits.
1303 
1304 The following causes an on pulse of 1500 microseconds duration to be
1305 transmitted on GPIO 17 at a rate of 50 times per second. This will
1306 command a servo connected to GPIO 17 to rotate to its mid-point.
1307 
1308 ...
1309 gpioServo(17, 1000); // Move servo to safe position anti-clockwise.
1310 
1311 gpioServo(23, 1500); // Move servo to centre position.
1312 
1313 gpioServo(25, 2000); // Move servo to safe position clockwise.
1314 ...
1315 
1316 OTHER UPDATE RATES:
1317 
1318 This function updates servos at 50Hz. If you wish to use a different
1319 update frequency you will have to use the PWM functions.
1320 
1321 . .
1322 PWM Hz 50 100 200 400 500
1323 1E6/Hz 20000 10000 5000 2500 2000
1324 . .
1325 
1326 Firstly set the desired PWM frequency using [*gpioSetPWMfrequency*].
1327 
1328 Then set the PWM range using [*gpioSetPWMrange*] to 1E6/frequency.
1329 Doing this allows you to use units of microseconds when setting
1330 the servo pulsewidth.
1331 
1332 E.g. If you want to update a servo connected to GPIO25 at 400Hz
1333 
1334 . .
1335 gpioSetPWMfrequency(25, 400);
1336 
1337 gpioSetPWMrange(25, 2500);
1338 . .
1339 
1340 Thereafter use the PWM command to move the servo,
1341 e.g. gpioPWM(25, 1500) will set a 1500 us pulse.
1342 D*/
1343 
1344 
1345 /*F*/
1346 int gpioGetServoPulsewidth(unsigned user_gpio);
1347 /*D
1348 Returns the servo pulsewidth setting for the GPIO.
1349 
1350 . .
1351 user_gpio: 0-31
1352 . .
1353 
1354 Returns 0 (off), 500 (most anti-clockwise) to 2500 (most clockwise)
1355 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
1356 D*/
1357 
1358 
1359 /*F*/
1360 int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f);
1361 /*D
1362 Registers a function to be called (a callback) when the specified
1363 GPIO changes state.
1364 
1365 . .
1366 user_gpio: 0-31
1367  f: the callback function
1368 . .
1369 
1370 Returns 0 if OK, otherwise PI_BAD_USER_GPIO.
1371 
1372 One callback may be registered per GPIO.
1373 
1374 The callback is passed the GPIO, the new level, and the tick.
1375 
1376 . .
1377 Parameter Value Meaning
1378 
1379 GPIO 0-31 The GPIO which has changed state
1380 
1381 level 0-2 0 = change to low (a falling edge)
1382  1 = change to high (a rising edge)
1383  2 = no level change (a watchdog timeout)
1384 
1385 tick 32 bit The number of microseconds since boot
1386  WARNING: this wraps around from
1387  4294967295 to 0 roughly every 72 minutes
1388 . .
1389 
1390 The alert may be cancelled by passing NULL as the function.
1391 
1392 The GPIO are sampled at a rate set when the library is started.
1393 
1394 If a value isn't specifically set the default of 5 us is used.
1395 
1396 The number of samples per second is given in the following table.
1397 
1398 . .
1399  samples
1400  per sec
1401 
1402  1 1,000,000
1403  2 500,000
1404 sample 4 250,000
1405 rate 5 200,000
1406 (us) 8 125,000
1407  10 100,000
1408 . .
1409 
1410 Level changes shorter than the sample rate may be missed.
1411 
1412 The thread which calls the alert functions is triggered nominally
1413 1000 times per second. The active alert functions will be called
1414 once per level change since the last time the thread was activated.
1415 i.e. The active alert functions will get all level changes but there
1416 will be a latency.
1417 
1418 The tick value is the time stamp of the sample in microseconds, see
1419 [*gpioTick*] for more details.
1420 
1421 ...
1422 void aFunction(int gpio, int level, uint32_t tick)
1423 {
1424  printf("GPIO %d became %d at %d", gpio, level, tick);
1425 }
1426 
1427 // call aFunction whenever GPIO 4 changes state
1428 
1429 gpioSetAlertFunc(4, aFunction);
1430 ...
1431 D*/
1432 
1433 
1434 /*F*/
1435 int gpioSetAlertFuncEx(
1436  unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata);
1437 /*D
1438 Registers a function to be called (a callback) when the specified
1439 GPIO changes state.
1440 
1441 . .
1442 user_gpio: 0-31
1443  f: the callback function
1444  userdata: pointer to arbitrary user data
1445 . .
1446 
1447 Returns 0 if OK, otherwise PI_BAD_USER_GPIO.
1448 
1449 One callback may be registered per GPIO.
1450 
1451 The callback is passed the GPIO, the new level, the tick, and
1452 the userdata pointer.
1453 
1454 . .
1455 Parameter Value Meaning
1456 
1457 GPIO 0-31 The GPIO which has changed state
1458 
1459 level 0-2 0 = change to low (a falling edge)
1460  1 = change to high (a rising edge)
1461  2 = no level change (a watchdog timeout)
1462 
1463 tick 32 bit The number of microseconds since boot
1464  WARNING: this wraps around from
1465  4294967295 to 0 roughly every 72 minutes
1466 
1467 userdata pointer Pointer to an arbitrary object
1468 . .
1469 
1470 See [*gpioSetAlertFunc*] for further details.
1471 
1472 Only one of [*gpioSetAlertFunc*] or [*gpioSetAlertFuncEx*] can be
1473 registered per GPIO.
1474 D*/
1475 
1476 
1477 /*F*/
1478 int gpioSetISRFunc(
1479  unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f);
1480 /*D
1481 Registers a function to be called (a callback) whenever the specified
1482 GPIO interrupt occurs.
1483 
1484 . .
1485  gpio: 0-53
1486  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE
1487 timeout: interrupt timeout in milliseconds (<=0 to cancel)
1488  f: the callback function
1489 . .
1490 
1491 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE,
1492 or PI_BAD_ISR_INIT.
1493 
1494 One function may be registered per GPIO.
1495 
1496 The function is passed the GPIO, the current level, and the
1497 current tick. The level will be PI_TIMEOUT if the optional
1498 interrupt timeout expires.
1499 
1500 . .
1501 Parameter Value Meaning
1502 
1503 GPIO 0-53 The GPIO which has changed state
1504 
1505 level 0-2 0 = change to low (a falling edge)
1506  1 = change to high (a rising edge)
1507  2 = no level change (interrupt timeout)
1508 
1509 tick 32 bit The number of microseconds since boot
1510  WARNING: this wraps around from
1511  4294967295 to 0 roughly every 72 minutes
1512 . .
1513 
1514 The underlying Linux sysfs GPIO interface is used to provide
1515 the interrupt services.
1516 
1517 The first time the function is called, with a non-NULL f, the
1518 GPIO is exported, set to be an input, and set to interrupt
1519 on the given edge and timeout.
1520 
1521 Subsequent calls, with a non-NULL f, can vary one or more of the
1522 edge, timeout, or function.
1523 
1524 The ISR may be cancelled by passing a NULL f, in which case the
1525 GPIO is unexported.
1526 
1527 The tick is that read at the time the process was informed of
1528 the interrupt. This will be a variable number of microseconds
1529 after the interrupt occurred. Typically the latency will be of
1530 the order of 50 microseconds. The latency is not guaranteed
1531 and will vary with system load.
1532 
1533 The level is that read at the time the process was informed of
1534 the interrupt, or PI_TIMEOUT if the optional interrupt timeout
1535 expired. It may not be the same as the expected edge as
1536 interrupts happening in rapid succession may be missed by the
1537 kernel (i.e. this mechanism can not be used to capture several
1538 interrupts only a few microseconds apart).
1539 D*/
1540 
1541 
1542 /*F*/
1543 int gpioSetISRFuncEx(
1544  unsigned gpio,
1545  unsigned edge,
1546  int timeout,
1547  gpioISRFuncEx_t f,
1548  void *userdata);
1549 /*D
1550 Registers a function to be called (a callback) whenever the specified
1551 GPIO interrupt occurs.
1552 
1553 . .
1554  gpio: 0-53
1555  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE
1556  timeout: interrupt timeout in milliseconds (<=0 to cancel)
1557  f: the callback function
1558 userdata: pointer to arbitrary user data
1559 . .
1560 
1561 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE,
1562 or PI_BAD_ISR_INIT.
1563 
1564 The function is passed the GPIO, the current level, the
1565 current tick, and the userdata pointer.
1566 
1567 . .
1568 Parameter Value Meaning
1569 
1570 GPIO 0-53 The GPIO which has changed state
1571 
1572 level 0-2 0 = change to low (a falling edge)
1573  1 = change to high (a rising edge)
1574  2 = no level change (interrupt timeout)
1575 
1576 tick 32 bit The number of microseconds since boot
1577  WARNING: this wraps around from
1578  4294967295 to 0 roughly every 72 minutes
1579 
1580 userdata pointer Pointer to an arbitrary object
1581 . .
1582 
1583 Only one of [*gpioSetISRFunc*] or [*gpioSetISRFuncEx*] can be
1584 registered per GPIO.
1585 
1586 See [*gpioSetISRFunc*] for further details.
1587 D*/
1588 
1589 
1590 /*F*/
1591 int gpioNotifyOpen(void);
1592 /*D
1593 This function requests a free notification handle.
1594 
1595 Returns a handle greater than or equal to zero if OK,
1596 otherwise PI_NO_HANDLE.
1597 
1598 A notification is a method for being notified of GPIO state changes
1599 via a pipe or socket.
1600 
1601 Pipe notifications for handle x will be available at the pipe
1602 named /dev/pigpiox (where x is the handle number). E.g. if the
1603 function returns 15 then the notifications must be read
1604 from /dev/pigpio15.
1605 
1606 Socket notifications are returned to the socket which requested the
1607 handle.
1608 
1609 ...
1610 h = gpioNotifyOpen();
1611 
1612 if (h >= 0)
1613 {
1614  sprintf(str, "/dev/pigpio%d", h);
1615 
1616  fd = open(str, O_RDONLY);
1617 
1618  if (fd >= 0)
1619  {
1620  // Okay.
1621  }
1622  else
1623  {
1624  // Error.
1625  }
1626 }
1627 else
1628 {
1629  // Error.
1630 }
1631 ...
1632 D*/
1633 
1634 
1635 /*F*/
1636 int gpioNotifyOpenWithSize(int bufSize);
1637 /*D
1638 This function requests a free notification handle.
1639 
1640 It differs from [*gpioNotifyOpen*] in that the pipe size may be
1641 specified, whereas [*gpioNotifyOpen*] uses the default pipe size.
1642 
1643 See [*gpioNotifyOpen*] for further details.
1644 D*/
1645 
1646 
1647 /*F*/
1648 int gpioNotifyBegin(unsigned handle, uint32_t bits);
1649 /*D
1650 This function starts notifications on a previously opened handle.
1651 
1652 . .
1653 handle: >=0, as returned by [*gpioNotifyOpen*]
1654  bits: a bit mask indicating the GPIO of interest
1655 . .
1656 
1657 Returns 0 if OK, otherwise PI_BAD_HANDLE.
1658 
1659 The notification sends state changes for each GPIO whose corresponding
1660 bit in bits is set.
1661 
1662 Each notification occupies 12 bytes in the fifo and has the
1663 following structure.
1664 
1665 . .
1666 typedef struct
1667 {
1668  uint16_t seqno;
1669  uint16_t flags;
1670  uint32_t tick;
1671  uint32_t level;
1672 } gpioReport_t;
1673 . .
1674 
1675 seqno: starts at 0 each time the handle is opened and then increments
1676 by one for each report.
1677 
1678 flags: three flags are defined, PI_NTFY_FLAGS_WDOG,
1679 PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT.
1680 
1681 If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags
1682 indicate a GPIO which has had a watchdog timeout.
1683 
1684 If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive
1685 signal on the pipe/socket and is sent once a minute in the absence
1686 of other notification activity.
1687 
1688 If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags
1689 indicate an event which has been triggered.
1690 
1691 tick: the number of microseconds since system boot. It wraps around
1692 after 1h12m.
1693 
1694 level: indicates the level of each GPIO. If bit 1<<x is set then
1695 GPIO x is high.
1696 
1697 ...
1698 // Start notifications for GPIO 1, 4, 6, 7, 10.
1699 
1700 // 1
1701 // 0 76 4 1
1702 // (1234 = 0x04D2 = 0b0000010011010010)
1703 
1704 gpioNotifyBegin(h, 1234);
1705 ...
1706 D*/
1707 
1708 
1709 /*F*/
1710 int gpioNotifyPause(unsigned handle);
1711 /*D
1712 This function pauses notifications on a previously opened handle.
1713 
1714 . .
1715 handle: >=0, as returned by [*gpioNotifyOpen*]
1716 . .
1717 
1718 Returns 0 if OK, otherwise PI_BAD_HANDLE.
1719 
1720 Notifications for the handle are suspended until [*gpioNotifyBegin*]
1721 is called again.
1722 
1723 ...
1724 gpioNotifyPause(h);
1725 ...
1726 D*/
1727 
1728 
1729 /*F*/
1730 int gpioNotifyClose(unsigned handle);
1731 /*D
1732 This function stops notifications on a previously opened handle
1733 and releases the handle for reuse.
1734 
1735 . .
1736 handle: >=0, as returned by [*gpioNotifyOpen*]
1737 . .
1738 
1739 Returns 0 if OK, otherwise PI_BAD_HANDLE.
1740 
1741 ...
1742 gpioNotifyClose(h);
1743 ...
1744 D*/
1745 
1746 
1747 /*F*/
1748 int gpioWaveClear(void);
1749 /*D
1750 This function clears all waveforms and any data added by calls to the
1751 [*gpioWaveAdd**] functions.
1752 
1753 Returns 0 if OK.
1754 
1755 ...
1756 gpioWaveClear();
1757 ...
1758 D*/
1759 
1760 
1761 /*F*/
1762 int gpioWaveAddNew(void);
1763 /*D
1764 This function starts a new empty waveform.
1765 
1766 You wouldn't normally need to call this function as it is automatically
1767 called after a waveform is created with the [*gpioWaveCreate*] function.
1768 
1769 Returns 0 if OK.
1770 
1771 ...
1772 gpioWaveAddNew();
1773 ...
1774 D*/
1775 
1776 
1777 /*F*/
1778 int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses);
1779 /*D
1780 This function adds a number of pulses to the current waveform.
1781 
1782 . .
1783 numPulses: the number of pulses
1784  pulses: an array of pulses
1785 . .
1786 
1787 Returns the new total number of pulses in the current waveform if OK,
1788 otherwise PI_TOO_MANY_PULSES.
1789 
1790 The pulses are interleaved in time order within the existing waveform
1791 (if any).
1792 
1793 Merging allows the waveform to be built in parts, that is the settings
1794 for GPIO#1 can be added, and then GPIO#2 etc.
1795 
1796 If the added waveform is intended to start after or within the existing
1797 waveform then the first pulse should consist of a delay.
1798 
1799 ...
1800 // Construct and send a 30 microsecond square wave.
1801 
1802 gpioSetMode(gpio, PI_OUTPUT);
1803 
1804 pulse[0].gpioOn = (1<<gpio);
1805 pulse[0].gpioOff = 0;
1806 pulse[0].usDelay = 15;
1807 
1808 pulse[1].gpioOn = 0;
1809 pulse[1].gpioOff = (1<<gpio);
1810 pulse[1].usDelay = 15;
1811 
1812 gpioWaveAddNew();
1813 
1814 gpioWaveAddGeneric(2, pulse);
1815 
1816 wave_id = gpioWaveCreate();
1817 
1818 if (wave_id >= 0)
1819 {
1820  gpioWaveTxSend(wave_id, PI_WAVE_MODE_REPEAT);
1821 
1822  // Transmit for 30 seconds.
1823 
1824  sleep(30);
1825 
1826  gpioWaveTxStop();
1827 }
1828 else
1829 {
1830  // Wave create failed.
1831 }
1832 ...
1833 D*/
1834 
1835 
1836 /*F*/
1838  (unsigned user_gpio,
1839  unsigned baud,
1840  unsigned data_bits,
1841  unsigned stop_bits,
1842  unsigned offset,
1843  unsigned numBytes,
1844  char *str);
1845 /*D
1846 This function adds a waveform representing serial data to the
1847 existing waveform (if any). The serial data starts offset
1848 microseconds from the start of the waveform.
1849 
1850 . .
1851 user_gpio: 0-31
1852  baud: 50-1000000
1853 data_bits: 1-32
1854 stop_bits: 2-8
1855  offset: >=0
1856  numBytes: >=1
1857  str: an array of chars (which may contain nulls)
1858 . .
1859 
1860 Returns the new total number of pulses in the current waveform if OK,
1861 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
1862 PI_BAD_STOPBITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
1863 or PI_TOO_MANY_PULSES.
1864 
1865 NOTES:
1866 
1867 The serial data is formatted as one start bit, data_bits data bits, and
1868 stop_bits/2 stop bits.
1869 
1870 It is legal to add serial data streams with different baud rates to
1871 the same waveform.
1872 
1873 numBytes is the number of bytes of data in str.
1874 
1875 The bytes required for each character depend upon data_bits.
1876 
1877 For data_bits 1-8 there will be one byte per character.
1878 For data_bits 9-16 there will be two bytes per character.
1879 For data_bits 17-32 there will be four bytes per character.
1880 
1881 ...
1882 #define MSG_LEN 8
1883 
1884 int i;
1885 char *str;
1886 char data[MSG_LEN];
1887 
1888 str = "Hello world!";
1889 
1890 gpioWaveAddSerial(4, 9600, 8, 2, 0, strlen(str), str);
1891 
1892 for (i=0; i<MSG_LEN; i++) data[i] = i;
1893 
1894 // Data added is offset 1 second from the waveform start.
1895 gpioWaveAddSerial(4, 9600, 8, 2, 1000000, MSG_LEN, data);
1896 ...
1897 D*/
1898 
1899 
1900 /*F*/
1901 int gpioWaveCreate(void);
1902 /*D
1903 This function creates a waveform from the data provided by the prior
1904 calls to the [*gpioWaveAdd**] functions. Upon success a wave id
1905 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
1906 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
1907 
1908 The data provided by the [*gpioWaveAdd**] functions is consumed by this
1909 function.
1910 
1911 As many waveforms may be created as there is space available. The
1912 wave id is passed to [*gpioWaveTxSend*] to specify the waveform to transmit.
1913 
1914 Normal usage would be
1915 
1916 Step 1. [*gpioWaveClear*] to clear all waveforms and added data.
1917 
1918 Step 2. [*gpioWaveAdd**] calls to supply the waveform data.
1919 
1920 Step 3. [*gpioWaveCreate*] to create the waveform and get a unique id
1921 
1922 Repeat steps 2 and 3 as needed.
1923 
1924 Step 4. [*gpioWaveTxSend*] with the id of the waveform to transmit.
1925 
1926 A waveform comprises one of more pulses. Each pulse consists of a
1927 [*gpioPulse_t*] structure.
1928 
1929 . .
1930 typedef struct
1931 {
1932  uint32_t gpioOn;
1933  uint32_t gpioOff;
1934  uint32_t usDelay;
1935 } gpioPulse_t;
1936 . .
1937 
1938 The fields specify
1939 
1940 1) the GPIO to be switched on at the start of the pulse.
1941 2) the GPIO to be switched off at the start of the pulse.
1942 3) the delay in microseconds before the next pulse.
1943 
1944 Any or all the fields can be zero. It doesn't make any sense to
1945 set all the fields to zero (the pulse will be ignored).
1946 
1947 When a waveform is started each pulse is executed in order with the
1948 specified delay between the pulse and the next.
1949 
1950 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
1951 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
1952 D*/
1953 
1954 
1955 /*F*/
1956 int gpioWaveDelete(unsigned wave_id);
1957 /*D
1958 This function deletes the waveform with id wave_id.
1959 
1960 The wave is flagged for deletion. The resources used by the wave
1961 will only be reused when either of the following apply.
1962 
1963 - all waves with higher numbered wave ids have been deleted or have
1964 been flagged for deletion.
1965 
1966 - a new wave is created which uses exactly the same resources as
1967 the current wave (see the C source for gpioWaveCreate for details).
1968 
1969 . .
1970 wave_id: >=0, as returned by [*gpioWaveCreate*]
1971 . .
1972 
1973 Wave ids are allocated in order, 0, 1, 2, etc.
1974 
1975 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
1976 D*/
1977 
1978 
1979 /*F*/
1980 int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode);
1981 /*D
1982 This function transmits the waveform with id wave_id. The mode
1983 determines whether the waveform is sent once or cycles endlessly.
1984 The SYNC variants wait for the current waveform to reach the
1985 end of a cycle or finish before starting the new waveform.
1986 
1987 WARNING: bad things may happen if you delete the previous
1988 waveform before it has been synced to the new waveform.
1989 
1990 NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled.
1991 
1992 . .
1993  wave_id: >=0, as returned by [*gpioWaveCreate*]
1994 wave_mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT,
1995  PI_WAVE_MODE_ONE_SHOT_SYNC, PI_WAVE_MODE_REPEAT_SYNC
1996 . .
1997 
1998 Returns the number of DMA control blocks in the waveform if OK,
1999 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
2000 D*/
2001 
2002 
2003 /*F*/
2004 int gpioWaveChain(char *buf, unsigned bufSize);
2005 /*D
2006 This function transmits a chain of waveforms.
2007 
2008 NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled.
2009 
2010 The waves to be transmitted are specified by the contents of buf
2011 which contains an ordered list of [*wave_id*]s and optional command
2012 codes and related data.
2013 
2014 . .
2015  buf: pointer to the wave_ids and optional command codes
2016 bufSize: the number of bytes in buf
2017 . .
2018 
2019 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
2020 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
2021 
2022 Each wave is transmitted in the order specified. A wave may
2023 occur multiple times per chain.
2024 
2025 A blocks of waves may be transmitted multiple times by using
2026 the loop commands. The block is bracketed by loop start and
2027 end commands. Loops may be nested.
2028 
2029 Delays between waves may be added with the delay command.
2030 
2031 The following command codes are supported:
2032 
2033 Name @ Cmd & Data @ Meaning
2034 Loop Start @ 255 0 @ Identify start of a wave block
2035 Loop Repeat @ 255 1 x y @ loop x + y*256 times
2036 Delay @ 255 2 x y @ delay x + y*256 microseconds
2037 Loop Forever @ 255 3 @ loop forever
2038 
2039 If present Loop Forever must be the last entry in the chain.
2040 
2041 The code is currently dimensioned to support a chain with roughly
2042 600 entries and 20 loop counters.
2043 
2044 ...
2045 #include <stdio.h>
2046 #include <pigpio.h>
2047 
2048 #define WAVES 5
2049 #define GPIO 4
2050 
2051 int main(int argc, char *argv[])
2052 {
2053  int i, wid[WAVES];
2054 
2055  if (gpioInitialise()<0) return -1;
2056 
2057  gpioSetMode(GPIO, PI_OUTPUT);
2058 
2059  printf("start piscope, press return"); getchar();
2060 
2061  for (i=0; i<WAVES; i++)
2062  {
2063  gpioWaveAddGeneric(2, (gpioPulse_t[])
2064  {{1<<GPIO, 0, 20},
2065  {0, 1<<GPIO, (i+1)*200}});
2066 
2067  wid[i] = gpioWaveCreate();
2068  }
2069 
2070  gpioWaveChain((char []) {
2071  wid[4], wid[3], wid[2], // transmit waves 4+3+2
2072  255, 0, // loop start
2073  wid[0], wid[0], wid[0], // transmit waves 0+0+0
2074  255, 0, // loop start
2075  wid[0], wid[1], // transmit waves 0+1
2076  255, 2, 0x88, 0x13, // delay 5000us
2077  255, 1, 30, 0, // loop end (repeat 30 times)
2078  255, 0, // loop start
2079  wid[2], wid[3], wid[0], // transmit waves 2+3+0
2080  wid[3], wid[1], wid[2], // transmit waves 3+1+2
2081  255, 1, 10, 0, // loop end (repeat 10 times)
2082  255, 1, 5, 0, // loop end (repeat 5 times)
2083  wid[4], wid[4], wid[4], // transmit waves 4+4+4
2084  255, 2, 0x20, 0x4E, // delay 20000us
2085  wid[0], wid[0], wid[0], // transmit waves 0+0+0
2086 
2087  }, 46);
2088 
2089  while (gpioWaveTxBusy()) time_sleep(0.1);
2090 
2091  for (i=0; i<WAVES; i++) gpioWaveDelete(wid[i]);
2092 
2093  printf("stop piscope, press return"); getchar();
2094 
2095  gpioTerminate();
2096 }
2097 ...
2098 D*/
2099 
2100 
2101 /*F*/
2102 int gpioWaveTxAt(void);
2103 /*D
2104 This function returns the id of the waveform currently being
2105 transmitted.
2106 
2107 Returns the waveform id or one of the following special values:
2108 
2109 PI_WAVE_NOT_FOUND (9998) - transmitted wave not found.
2110 PI_NO_TX_WAVE (9999) - no wave being transmitted.
2111 D*/
2112 
2113 
2114 /*F*/
2115 int gpioWaveTxBusy(void);
2116 /*D
2117 This function checks to see if a waveform is currently being
2118 transmitted.
2119 
2120 Returns 1 if a waveform is currently being transmitted, otherwise 0.
2121 D*/
2122 
2123 
2124 /*F*/
2125 int gpioWaveTxStop(void);
2126 /*D
2127 This function aborts the transmission of the current waveform.
2128 
2129 Returns 0 if OK.
2130 
2131 This function is intended to stop a waveform started in repeat mode.
2132 D*/
2133 
2134 
2135 /*F*/
2136 int gpioWaveGetMicros(void);
2137 /*D
2138 This function returns the length in microseconds of the current
2139 waveform.
2140 D*/
2141 
2142 
2143 /*F*/
2144 int gpioWaveGetHighMicros(void);
2145 /*D
2146 This function returns the length in microseconds of the longest waveform
2147 created since [*gpioInitialise*] was called.
2148 D*/
2149 
2150 
2151 /*F*/
2152 int gpioWaveGetMaxMicros(void);
2153 /*D
2154 This function returns the maximum possible size of a waveform in
2155 microseconds.
2156 D*/
2157 
2158 
2159 /*F*/
2160 int gpioWaveGetPulses(void);
2161 /*D
2162 This function returns the length in pulses of the current waveform.
2163 D*/
2164 
2165 
2166 /*F*/
2167 int gpioWaveGetHighPulses(void);
2168 /*D
2169 This function returns the length in pulses of the longest waveform
2170 created since [*gpioInitialise*] was called.
2171 D*/
2172 
2173 
2174 /*F*/
2175 int gpioWaveGetMaxPulses(void);
2176 /*D
2177 This function returns the maximum possible size of a waveform in pulses.
2178 D*/
2179 
2180 
2181 /*F*/
2182 int gpioWaveGetCbs(void);
2183 /*D
2184 This function returns the length in DMA control blocks of the current
2185 waveform.
2186 D*/
2187 
2188 
2189 /*F*/
2190 int gpioWaveGetHighCbs(void);
2191 /*D
2192 This function returns the length in DMA control blocks of the longest
2193 waveform created since [*gpioInitialise*] was called.
2194 D*/
2195 
2196 
2197 /*F*/
2198 int gpioWaveGetMaxCbs(void);
2199 /*D
2200 This function returns the maximum possible size of a waveform in DMA
2201 control blocks.
2202 D*/
2203 
2204 
2205 /*F*/
2206 int gpioSerialReadOpen(unsigned user_gpio, unsigned baud, unsigned data_bits);
2207 /*D
2208 This function opens a GPIO for bit bang reading of serial data.
2209 
2210 . .
2211 user_gpio: 0-31
2212  baud: 50-250000
2213 data_bits: 1-32
2214 . .
2215 
2216 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
2217 PI_BAD_DATABITS, or PI_GPIO_IN_USE.
2218 
2219 The serial data is returned in a cyclic buffer and is read using
2220 [*gpioSerialRead*].
2221 
2222 It is the caller's responsibility to read data from the cyclic buffer
2223 in a timely fashion.
2224 D*/
2225 
2226 /*F*/
2227 int gpioSerialReadInvert(unsigned user_gpio, unsigned invert);
2228 /*D
2229 This function configures the level logic for bit bang serial reads.
2230 
2231 Use PI_BB_SER_INVERT to invert the serial logic and PI_BB_SER_NORMAL for
2232 normal logic. Default is PI_BB_SER_NORMAL.
2233 
2234 . .
2235 user_gpio: 0-31
2236  invert: 0-1
2237 . .
2238 
2239 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_GPIO_IN_USE,
2240 PI_NOT_SERIAL_GPIO, or PI_BAD_SER_INVERT.
2241 
2242 The GPIO must be opened for bit bang reading of serial data using
2243 [*gpioSerialReadOpen*] prior to calling this function.
2244 D*/
2245 
2246 
2247 /*F*/
2248 int gpioSerialRead(unsigned user_gpio, void *buf, size_t bufSize);
2249 /*D
2250 This function copies up to bufSize bytes of data read from the
2251 bit bang serial cyclic buffer to the buffer starting at buf.
2252 
2253 . .
2254 user_gpio: 0-31, previously opened with [*gpioSerialReadOpen*]
2255  buf: an array to receive the read bytes
2256  bufSize: >=0
2257 . .
2258 
2259 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
2260 or PI_NOT_SERIAL_GPIO.
2261 
2262 The bytes returned for each character depend upon the number of
2263 data bits [*data_bits*] specified in the [*gpioSerialReadOpen*] command.
2264 
2265 For [*data_bits*] 1-8 there will be one byte per character.
2266 For [*data_bits*] 9-16 there will be two bytes per character.
2267 For [*data_bits*] 17-32 there will be four bytes per character.
2268 D*/
2269 
2270 
2271 /*F*/
2272 int gpioSerialReadClose(unsigned user_gpio);
2273 /*D
2274 This function closes a GPIO for bit bang reading of serial data.
2275 
2276 . .
2277 user_gpio: 0-31, previously opened with [*gpioSerialReadOpen*]
2278 . .
2279 
2280 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
2281 D*/
2282 
2283 /*F*/
2284 int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags);
2285 /*D
2286 This returns a handle for the device at the address on the I2C bus.
2287 
2288 . .
2289  i2cBus: >=0
2290  i2cAddr: 0-0x7F
2291 i2cFlags: 0
2292 . .
2293 
2294 No flags are currently defined. This parameter should be set to zero.
2295 
2296 Physically buses 0 and 1 are available on the Pi. Higher numbered buses
2297 will be available if a kernel supported bus multiplexor is being used.
2298 
2299 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
2300 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
2301 
2302 For the SMBus commands the low level transactions are shown at the end
2303 of the function description. The following abbreviations are used.
2304 
2305 . .
2306 S (1 bit) : Start bit
2307 P (1 bit) : Stop bit
2308 Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
2309 A, NA (1 bit) : Accept and not accept bit.
2310 Addr (7 bits): I2C 7 bit address.
2311 i2cReg (8 bits): Command byte, a byte which often selects a register.
2312 Data (8 bits): A data byte.
2313 Count (8 bits): A byte defining the length of a block operation.
2314 
2315 [..]: Data sent by the device.
2316 . .
2317 D*/
2318 
2319 
2320 /*F*/
2321 int i2cClose(unsigned handle);
2322 /*D
2323 This closes the I2C device associated with the handle.
2324 
2325 . .
2326 handle: >=0, as returned by a call to [*i2cOpen*]
2327 . .
2328 
2329 Returns 0 if OK, otherwise PI_BAD_HANDLE.
2330 D*/
2331 
2332 
2333 /*F*/
2334 int i2cWriteQuick(unsigned handle, unsigned bit);
2335 /*D
2336 This sends a single bit (in the Rd/Wr bit) to the device associated
2337 with handle.
2338 
2339 . .
2340 handle: >=0, as returned by a call to [*i2cOpen*]
2341  bit: 0-1, the value to write
2342 . .
2343 
2344 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2345 PI_I2C_WRITE_FAILED.
2346 
2347 Quick command. SMBus 2.0 5.5.1
2348 . .
2349 S Addr bit [A] P
2350 . .
2351 D*/
2352 
2353 
2354 /*F*/
2355 int i2cWriteByte(unsigned handle, unsigned bVal);
2356 /*D
2357 This sends a single byte to the device associated with handle.
2358 
2359 . .
2360 handle: >=0, as returned by a call to [*i2cOpen*]
2361  bVal: 0-0xFF, the value to write
2362 . .
2363 
2364 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2365 PI_I2C_WRITE_FAILED.
2366 
2367 Send byte. SMBus 2.0 5.5.2
2368 . .
2369 S Addr Wr [A] bVal [A] P
2370 . .
2371 D*/
2372 
2373 
2374 /*F*/
2375 int i2cReadByte(unsigned handle);
2376 /*D
2377 This reads a single byte from the device associated with handle.
2378 
2379 . .
2380 handle: >=0, as returned by a call to [*i2cOpen*]
2381 . .
2382 
2383 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
2384 or PI_I2C_READ_FAILED.
2385 
2386 Receive byte. SMBus 2.0 5.5.3
2387 . .
2388 S Addr Rd [A] [Data] NA P
2389 . .
2390 D*/
2391 
2392 
2393 /*F*/
2394 int i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal);
2395 /*D
2396 This writes a single byte to the specified register of the device
2397 associated with handle.
2398 
2399 . .
2400 handle: >=0, as returned by a call to [*i2cOpen*]
2401 i2cReg: 0-255, the register to write
2402  bVal: 0-0xFF, the value to write
2403 . .
2404 
2405 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2406 PI_I2C_WRITE_FAILED.
2407 
2408 Write byte. SMBus 2.0 5.5.4
2409 . .
2410 S Addr Wr [A] i2cReg [A] bVal [A] P
2411 . .
2412 D*/
2413 
2414 
2415 /*F*/
2416 int i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal);
2417 /*D
2418 This writes a single 16 bit word to the specified register of the device
2419 associated with handle.
2420 
2421 . .
2422 handle: >=0, as returned by a call to [*i2cOpen*]
2423 i2cReg: 0-255, the register to write
2424  wVal: 0-0xFFFF, the value to write
2425 . .
2426 
2427 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2428 PI_I2C_WRITE_FAILED.
2429 
2430 Write word. SMBus 2.0 5.5.4
2431 . .
2432 S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] P
2433 . .
2434 D*/
2435 
2436 
2437 /*F*/
2438 int i2cReadByteData(unsigned handle, unsigned i2cReg);
2439 /*D
2440 This reads a single byte from the specified register of the device
2441 associated with handle.
2442 
2443 . .
2444 handle: >=0, as returned by a call to [*i2cOpen*]
2445 i2cReg: 0-255, the register to read
2446 . .
2447 
2448 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
2449 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2450 
2451 Read byte. SMBus 2.0 5.5.5
2452 . .
2453 S Addr Wr [A] i2cReg [A] S Addr Rd [A] [Data] NA P
2454 . .
2455 D*/
2456 
2457 
2458 /*F*/
2459 int i2cReadWordData(unsigned handle, unsigned i2cReg);
2460 /*D
2461 This reads a single 16 bit word from the specified register of the device
2462 associated with handle.
2463 
2464 . .
2465 handle: >=0, as returned by a call to [*i2cOpen*]
2466 i2cReg: 0-255, the register to read
2467 . .
2468 
2469 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
2470 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2471 
2472 Read word. SMBus 2.0 5.5.5
2473 . .
2474 S Addr Wr [A] i2cReg [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P
2475 . .
2476 D*/
2477 
2478 
2479 /*F*/
2480 int i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal);
2481 /*D
2482 This writes 16 bits of data to the specified register of the device
2483 associated with handle and reads 16 bits of data in return.
2484 
2485 . .
2486 handle: >=0, as returned by a call to [*i2cOpen*]
2487 i2cReg: 0-255, the register to write/read
2488  wVal: 0-0xFFFF, the value to write
2489 . .
2490 
2491 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
2492 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2493 
2494 Process call. SMBus 2.0 5.5.6
2495 . .
2496 S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A]
2497  S Addr Rd [A] [DataLow] A [DataHigh] NA P
2498 . .
2499 D*/
2500 
2501 
2502 /*F*/
2503 int i2cWriteBlockData(
2504 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
2505 /*D
2506 This writes up to 32 bytes to the specified register of the device
2507 associated with handle.
2508 
2509 . .
2510 handle: >=0, as returned by a call to [*i2cOpen*]
2511 i2cReg: 0-255, the register to write
2512  buf: an array with the data to send
2513  count: 1-32, the number of bytes to write
2514 . .
2515 
2516 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2517 PI_I2C_WRITE_FAILED.
2518 
2519 Block write. SMBus 2.0 5.5.7
2520 . .
2521 S Addr Wr [A] i2cReg [A] count [A]
2522  buf0 [A] buf1 [A] ... [A] bufn [A] P
2523 . .
2524 D*/
2525 
2526 
2527 /*F*/
2528 int i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf);
2529 /*D
2530 This reads a block of up to 32 bytes from the specified register of
2531 the device associated with handle.
2532 
2533 . .
2534 handle: >=0, as returned by a call to [*i2cOpen*]
2535 i2cReg: 0-255, the register to read
2536  buf: an array to receive the read data
2537 . .
2538 
2539 The amount of returned data is set by the device.
2540 
2541 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
2542 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2543 
2544 Block read. SMBus 2.0 5.5.7
2545 . .
2546 S Addr Wr [A] i2cReg [A]
2547  S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P
2548 . .
2549 D*/
2550 
2551 
2552 /*F*/
2554 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
2555 /*D
2556 This writes data bytes to the specified register of the device
2557 associated with handle and reads a device specified number
2558 of bytes of data in return.
2559 
2560 . .
2561 handle: >=0, as returned by a call to [*i2cOpen*]
2562 i2cReg: 0-255, the register to write/read
2563  buf: an array with the data to send and to receive the read data
2564  count: 1-32, the number of bytes to write
2565 . .
2566 
2567 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
2568 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2569 
2570 The SMBus 2.0 documentation states that a minimum of 1 byte may be
2571 sent and a minimum of 1 byte may be received. The total number of
2572 bytes sent/received must be 32 or less.
2573 
2574 Block write-block read. SMBus 2.0 5.5.8
2575 . .
2576 S Addr Wr [A] i2cReg [A] count [A] buf0 [A] ... bufn [A]
2577  S Addr Rd [A] [Count] A [buf0] A ... [bufn] A P
2578 . .
2579 D*/
2580 
2581 
2582 /*F*/
2584 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
2585 /*D
2586 This reads count bytes from the specified register of the device
2587 associated with handle . The count may be 1-32.
2588 
2589 . .
2590 handle: >=0, as returned by a call to [*i2cOpen*]
2591 i2cReg: 0-255, the register to read
2592  buf: an array to receive the read data
2593  count: 1-32, the number of bytes to read
2594 . .
2595 
2596 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
2597 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2598 
2599 . .
2600 S Addr Wr [A] i2cReg [A]
2601  S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
2602 . .
2603 D*/
2604 
2605 
2606 /*F*/
2608 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
2609 /*D
2610 This writes 1 to 32 bytes to the specified register of the device
2611 associated with handle.
2612 
2613 . .
2614 handle: >=0, as returned by a call to [*i2cOpen*]
2615 i2cReg: 0-255, the register to write
2616  buf: the data to write
2617  count: 1-32, the number of bytes to write
2618 . .
2619 
2620 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2621 PI_I2C_WRITE_FAILED.
2622 
2623 . .
2624 S Addr Wr [A] i2cReg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
2625 . .
2626 D*/
2627 
2628 /*F*/
2629 int i2cReadDevice(unsigned handle, char *buf, unsigned count);
2630 /*D
2631 This reads count bytes from the raw device into buf.
2632 
2633 . .
2634 handle: >=0, as returned by a call to [*i2cOpen*]
2635  buf: an array to receive the read data bytes
2636  count: >0, the number of bytes to read
2637 . .
2638 
2639 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2640 PI_I2C_READ_FAILED.
2641 
2642 . .
2643 S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
2644 . .
2645 D*/
2646 
2647 
2648 /*F*/
2649 int i2cWriteDevice(unsigned handle, char *buf, unsigned count);
2650 /*D
2651 This writes count bytes from buf to the raw device.
2652 
2653 . .
2654 handle: >=0, as returned by a call to [*i2cOpen*]
2655  buf: an array containing the data bytes to write
2656  count: >0, the number of bytes to write
2657 . .
2658 
2659 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2660 PI_I2C_WRITE_FAILED.
2661 
2662 . .
2663 S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
2664 . .
2665 D*/
2666 
2667 /*F*/
2668 void i2cSwitchCombined(int setting);
2669 /*D
2670 This sets the I2C (i2c-bcm2708) module "use combined transactions"
2671 parameter on or off.
2672 
2673 . .
2674 setting: 0 to set the parameter off, non-zero to set it on
2675 . .
2676 
2677 
2678 NOTE: when the flag is on a write followed by a read to the same
2679 slave address will use a repeated start (rather than a stop/start).
2680 D*/
2681 
2682 /*F*/
2683 int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs);
2684 /*D
2685 This function executes multiple I2C segments in one transaction by
2686 calling the I2C_RDWR ioctl.
2687 
2688 . .
2689  handle: >=0, as returned by a call to [*i2cOpen*]
2690  segs: an array of I2C segments
2691 numSegs: >0, the number of I2C segments
2692 . .
2693 
2694 Returns the number of segments if OK, otherwise PI_BAD_I2C_SEG.
2695 D*/
2696 
2697 /*F*/
2698 int i2cZip(
2699  unsigned handle,
2700  char *inBuf,
2701  unsigned inLen,
2702  char *outBuf,
2703  unsigned outLen);
2704 /*D
2705 This function executes a sequence of I2C operations. The
2706 operations to be performed are specified by the contents of inBuf
2707 which contains the concatenated command codes and associated data.
2708 
2709 . .
2710 handle: >=0, as returned by a call to [*i2cOpen*]
2711  inBuf: pointer to the concatenated I2C commands, see below
2712  inLen: size of command buffer
2713 outBuf: pointer to buffer to hold returned data
2714 outLen: size of output buffer
2715 . .
2716 
2717 Returns >= 0 if OK (the number of bytes read), otherwise
2718 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
2719 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
2720 
2721 The following command codes are supported:
2722 
2723 Name @ Cmd & Data @ Meaning
2724 End @ 0 @ No more commands
2725 Escape @ 1 @ Next P is two bytes
2726 On @ 2 @ Switch combined flag on
2727 Off @ 3 @ Switch combined flag off
2728 Address @ 4 P @ Set I2C address to P
2729 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2730 Read @ 6 P @ Read P bytes of data
2731 Write @ 7 P ... @ Write P bytes of data
2732 
2733 The address, read, and write commands take a parameter P.
2734 Normally P is one byte (0-255). If the command is preceded by
2735 the Escape command then P is two bytes (0-65535, least significant
2736 byte first).
2737 
2738 The address defaults to that associated with the handle.
2739 The flags default to 0. The address and flags maintain their
2740 previous value until updated.
2741 
2742 The returned I2C data is stored in consecutive locations of outBuf.
2743 
2744 ...
2745 Set address 0x53, write 0x32, read 6 bytes
2746 Set address 0x1E, write 0x03, read 6 bytes
2747 Set address 0x68, write 0x1B, read 8 bytes
2748 End
2749 
2750 0x04 0x53 0x07 0x01 0x32 0x06 0x06
2751 0x04 0x1E 0x07 0x01 0x03 0x06 0x06
2752 0x04 0x68 0x07 0x01 0x1B 0x06 0x08
2753 0x00
2754 ...
2755 D*/
2756 
2757 /*F*/
2758 int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud);
2759 /*D
2760 This function selects a pair of GPIO for bit banging I2C at a
2761 specified baud rate.
2762 
2763 Bit banging I2C allows for certain operations which are not possible
2764 with the standard I2C driver.
2765 
2766 o baud rates as low as 50
2767 o repeated starts
2768 o clock stretching
2769 o I2C on any pair of spare GPIO
2770 
2771 . .
2772  SDA: 0-31
2773  SCL: 0-31
2774 baud: 50-500000
2775 . .
2776 
2777 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
2778 PI_GPIO_IN_USE.
2779 
2780 NOTE:
2781 
2782 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As
2783 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
2784 D*/
2785 
2786 /*F*/
2787 int bbI2CClose(unsigned SDA);
2788 /*D
2789 This function stops bit banging I2C on a pair of GPIO previously
2790 opened with [*bbI2COpen*].
2791 
2792 . .
2793 SDA: 0-31, the SDA GPIO used in a prior call to [*bbI2COpen*]
2794 . .
2795 
2796 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
2797 D*/
2798 
2799 /*F*/
2800 int bbI2CZip(
2801  unsigned SDA,
2802  char *inBuf,
2803  unsigned inLen,
2804  char *outBuf,
2805  unsigned outLen);
2806 /*D
2807 This function executes a sequence of bit banged I2C operations. The
2808 operations to be performed are specified by the contents of inBuf
2809 which contains the concatenated command codes and associated data.
2810 
2811 . .
2812  SDA: 0-31 (as used in a prior call to [*bbI2COpen*])
2813  inBuf: pointer to the concatenated I2C commands, see below
2814  inLen: size of command buffer
2815 outBuf: pointer to buffer to hold returned data
2816 outLen: size of output buffer
2817 . .
2818 
2819 Returns >= 0 if OK (the number of bytes read), otherwise
2820 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
2821 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
2822 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
2823 
2824 The following command codes are supported:
2825 
2826 Name @ Cmd & Data @ Meaning
2827 End @ 0 @ No more commands
2828 Escape @ 1 @ Next P is two bytes
2829 Start @ 2 @ Start condition
2830 Stop @ 3 @ Stop condition
2831 Address @ 4 P @ Set I2C address to P
2832 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2833 Read @ 6 P @ Read P bytes of data
2834 Write @ 7 P ... @ Write P bytes of data
2835 
2836 The address, read, and write commands take a parameter P.
2837 Normally P is one byte (0-255). If the command is preceded by
2838 the Escape command then P is two bytes (0-65535, least significant
2839 byte first).
2840 
2841 The address and flags default to 0. The address and flags maintain
2842 their previous value until updated.
2843 
2844 No flags are currently defined.
2845 
2846 The returned I2C data is stored in consecutive locations of outBuf.
2847 
2848 ...
2849 Set address 0x53
2850 start, write 0x32, (re)start, read 6 bytes, stop
2851 Set address 0x1E
2852 start, write 0x03, (re)start, read 6 bytes, stop
2853 Set address 0x68
2854 start, write 0x1B, (re)start, read 8 bytes, stop
2855 End
2856 
2857 0x04 0x53
2858 0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03
2859 
2860 0x04 0x1E
2861 0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03
2862 
2863 0x04 0x68
2864 0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03
2865 
2866 0x00
2867 ...
2868 D*/
2869 
2870 /*F*/
2872 /*D
2873 This function provides a low-level interface to the
2874 SPI/I2C Slave peripheral. This peripheral allows the
2875 Pi to act as a slave device on an I2C or SPI bus.
2876 
2877 I can't get SPI to work properly. I tried with a
2878 control word of 0x303 and swapped MISO and MOSI.
2879 
2880 The function sets the BSC mode, writes any data in
2881 the transmit buffer to the BSC transmit FIFO, and
2882 copies any data in the BSC receive FIFO to the
2883 receive buffer.
2884 
2885 . .
2886 bsc_xfer:= a structure defining the transfer
2887 
2888 typedef struct
2889 {
2890  uint32_t control; // Write
2891  int rxCnt; // Read only
2892  char rxBuf[BSC_FIFO_SIZE]; // Read only
2893  int txCnt; // Write
2894  char txBuf[BSC_FIFO_SIZE]; // Write
2895 } bsc_xfer_t;
2896 . .
2897 
2898 To start a transfer set control (see below) and copy the bytes to
2899 be sent (if any) to txBuf and set the byte count in txCnt.
2900 
2901 Upon return rxCnt will be set to the number of received bytes placed
2902 in rxBuf.
2903 
2904 Note that the control word sets the BSC mode. The BSC will stay in
2905 that mode until a different control word is sent.
2906 
2907 The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode
2908 and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You
2909 need to swap MISO/MOSI between master and slave.
2910 
2911 When a zero control word is received GPIO 18-21 will be reset
2912 to INPUT mode.
2913 
2914 The returned function value is the status of the transfer (see below).
2915 
2916 If there was an error the status will be less than zero
2917 (and will contain the error code).
2918 
2919 The most significant word of the returned status contains the number
2920 of bytes actually copied from txBuf to the BSC transmit FIFO (may be
2921 less than requested if the FIFO already contained untransmitted data).
2922 
2923 control consists of the following bits.
2924 
2925 . .
2926 22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
2927  a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN
2928 . .
2929 
2930 Bits 0-13 are copied unchanged to the BSC CR register. See
2931 pages 163-165 of the Broadcom peripherals document for full
2932 details.
2933 
2934 aaaaaaa @ defines the I2C slave address (only relevant in I2C mode)
2935 IT @ invert transmit status flags
2936 HC @ enable host control
2937 TF @ enable test FIFO
2938 IR @ invert receive status flags
2939 RE @ enable receive
2940 TE @ enable transmit
2941 BK @ abort operation and clear FIFOs
2942 EC @ send control register as first I2C byte
2943 ES @ send status register as first I2C byte
2944 PL @ set SPI polarity high
2945 PH @ set SPI phase high
2946 I2 @ enable I2C mode
2947 SP @ enable SPI mode
2948 EN @ enable BSC peripheral
2949 
2950 The returned status has the following format
2951 
2952 . .
2953 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
2954  S S S S S R R R R R T T T T T RB TE RF TF RE TB
2955 . .
2956 
2957 Bits 0-15 are copied unchanged from the BSC FR register. See
2958 pages 165-166 of the Broadcom peripherals document for full
2959 details.
2960 
2961 SSSSS @ number of bytes successfully copied to transmit FIFO
2962 RRRRR @ number of bytes in receieve FIFO
2963 TTTTT @ number of bytes in transmit FIFO
2964 RB @ receive busy
2965 TE @ transmit FIFO empty
2966 RF @ receive FIFO full
2967 TF @ transmit FIFO full
2968 RE @ receive FIFO empty
2969 TB @ transmit busy
2970 
2971 The following example shows how to configure the BSC peripheral as
2972 an I2C slave with address 0x13 and send four bytes.
2973 
2974 ...
2975 bsc_xfer_t xfer;
2976 
2977 xfer.control = (0x13<<16) | 0x305;
2978 
2979 memcpy(xfer.txBuf, "ABCD", 4);
2980 xfer.txCnt = 4;
2981 
2982 status = bscXfer(&xfer);
2983 
2984 if (status >= 0)
2985 {
2986  // process transfer
2987 }
2988 ...
2989 D*/
2990 
2991 /*F*/
2992 int bbSPIOpen(
2993  unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK,
2994  unsigned baud, unsigned spiFlags);
2995 /*D
2996 This function selects a set of GPIO for bit banging SPI with
2997 a specified baud rate and mode.
2998 
2999 . .
3000  CS: 0-31
3001  MISO: 0-31
3002  MOSI: 0-31
3003  SCLK: 0-31
3004  baud: 50-250000
3005 spiFlags: see below
3006 . .
3007 
3008 spiFlags consists of the least significant 22 bits.
3009 
3010 . .
3011 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
3012  0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m
3013 . .
3014 
3015 mm defines the SPI mode, defaults to 0
3016 
3017 . .
3018 Mode CPOL CPHA
3019  0 0 0
3020  1 0 1
3021  2 1 0
3022  3 1 1
3023 . .
3024 
3025 p is 0 if CS is active low (default) and 1 for active high.
3026 
3027 T is 1 if the least significant bit is transmitted on MOSI first, the
3028 default (0) shifts the most significant bit out first.
3029 
3030 R is 1 if the least significant bit is received on MISO first, the
3031 default (0) receives the most significant bit first.
3032 
3033 The other bits in flags should be set to zero.
3034 
3035 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or
3036 PI_GPIO_IN_USE.
3037 
3038 If more than one device is connected to the SPI bus (defined by
3039 SCLK, MOSI, and MISO) each must have its own CS.
3040 
3041 ...
3042 bbSPIOpen(10, MISO, MOSI, SCLK, 10000, 0); // device 1
3043 bbSPIOpen(11, MISO, MOSI, SCLK, 20000, 3); // device 2
3044 ...
3045 D*/
3046 
3047 /*F*/
3048 int bbSPIClose(unsigned CS);
3049 /*D
3050 This function stops bit banging SPI on a set of GPIO
3051 opened with [*bbSPIOpen*].
3052 
3053 . .
3054 CS: 0-31, the CS GPIO used in a prior call to [*bbSPIOpen*]
3055 . .
3056 
3057 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO.
3058 D*/
3059 
3060 /*F*/
3061 int bbSPIXfer(
3062  unsigned CS,
3063  char *inBuf,
3064  char *outBuf,
3065  unsigned count);
3066 /*D
3067 This function executes a bit banged SPI transfer.
3068 
3069 . .
3070  CS: 0-31 (as used in a prior call to [*bbSPIOpen*])
3071  inBuf: pointer to buffer to hold data to be sent
3072 outBuf: pointer to buffer to hold returned data
3073  count: size of data transfer
3074 . .
3075 
3076 Returns >= 0 if OK (the number of bytes read), otherwise
3077 PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER.
3078 
3079 ...
3080 // gcc -Wall -pthread -o bbSPIx_test bbSPIx_test.c -lpigpio
3081 // sudo ./bbSPIx_test
3082 
3083 
3084 #include <stdio.h>
3085 
3086 #include "pigpio.h"
3087 
3088 #define CE0 5
3089 #define CE1 6
3090 #define MISO 13
3091 #define MOSI 19
3092 #define SCLK 12
3093 
3094 int main(int argc, char *argv[])
3095 {
3096  int i, count, set_val, read_val;
3097  unsigned char inBuf[3];
3098  char cmd1[] = {0, 0};
3099  char cmd2[] = {12, 0};
3100  char cmd3[] = {1, 128, 0};
3101 
3102  if (gpioInitialise() < 0)
3103  {
3104  fprintf(stderr, "pigpio initialisation failed.\n");
3105  return 1;
3106  }
3107 
3108  bbSPIOpen(CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC
3109  bbSPIOpen(CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC
3110 
3111  for (i=0; i<256; i++)
3112  {
3113  cmd1[1] = i;
3114 
3115  count = bbSPIXfer(CE0, cmd1, (char *)inBuf, 2); // > DAC
3116 
3117  if (count == 2)
3118  {
3119  count = bbSPIXfer(CE0, cmd2, (char *)inBuf, 2); // < DAC
3120 
3121  if (count == 2)
3122  {
3123  set_val = inBuf[1];
3124 
3125  count = bbSPIXfer(CE1, cmd3, (char *)inBuf, 3); // < ADC
3126 
3127  if (count == 3)
3128  {
3129  read_val = ((inBuf[1]&3)<<8) | inBuf[2];
3130  printf("%d %d\n", set_val, read_val);
3131  }
3132  }
3133  }
3134  }
3135 
3136  bbSPIClose(CE0);
3137  bbSPIClose(CE1);
3138 
3139  gpioTerminate();
3140 
3141  return 0;
3142 }
3143 ...
3144 D*/
3145 
3146 /*F*/
3147 int spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags);
3148 /*D
3149 This function returns a handle for the SPI device on the channel.
3150 Data will be transferred at baud bits per second. The flags may
3151 be used to modify the default behaviour of 4-wire operation, mode 0,
3152 active low chip select.
3153 
3154 An auxiliary SPI device is available on all models but the
3155 A and B and may be selected by setting the A bit in the flags.
3156 The auxiliary device has 3 chip selects and a selectable word
3157 size in bits.
3158 
3159 . .
3160  spiChan: 0-1 (0-2 for the auxiliary SPI device)
3161  baud: 32K-125M (values above 30M are unlikely to work)
3162 spiFlags: see below
3163 . .
3164 
3165 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
3166 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
3167 
3168 spiFlags consists of the least significant 22 bits.
3169 
3170 . .
3171 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
3172  b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m
3173 . .
3174 
3175 mm defines the SPI mode.
3176 
3177 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
3178 
3179 . .
3180 Mode POL PHA
3181  0 0 0
3182  1 0 1
3183  2 1 0
3184  3 1 1
3185 . .
3186 
3187 px is 0 if CEx is active low (default) and 1 for active high.
3188 
3189 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
3190 
3191 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
3192 
3193 W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Standard
3194 SPI device only.
3195 
3196 nnnn defines the number of bytes (0-15) to write before switching
3197 the MOSI line to MISO to read data. This field is ignored
3198 if W is not set. Standard SPI device only.
3199 
3200 T is 1 if the least significant bit is transmitted on MOSI first, the
3201 default (0) shifts the most significant bit out first. Auxiliary SPI
3202 device only.
3203 
3204 R is 1 if the least significant bit is received on MISO first, the
3205 default (0) receives the most significant bit first. Auxiliary SPI
3206 device only.
3207 
3208 bbbbbb defines the word size in bits (0-32). The default (0)
3209 sets 8 bits per word. Auxiliary SPI device only.
3210 
3211 The [*spiRead*], [*spiWrite*], and [*spiXfer*] functions
3212 transfer data packed into 1, 2, or 4 bytes according to
3213 the word size in bits.
3214 
3215 For bits 1-8 there will be one byte per word.
3216 For bits 9-16 there will be two bytes per word.
3217 For bits 17-32 there will be four bytes per word.
3218 
3219 Multi-byte transfers are made in least significant byte first order.
3220 
3221 E.g. to transfer 32 11-bit words buf should contain 64 bytes
3222 and count should be 64.
3223 
3224 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
3225 by 0x1A.
3226 
3227 The other bits in flags should be set to zero.
3228 D*/
3229 
3230 /*F*/
3231 int spiClose(unsigned handle);
3232 /*D
3233 This functions closes the SPI device identified by the handle.
3234 
3235 . .
3236 handle: >=0, as returned by a call to [*spiOpen*]
3237 . .
3238 
3239 Returns 0 if OK, otherwise PI_BAD_HANDLE.
3240 D*/
3241 
3242 
3243 /*F*/
3244 int spiRead(unsigned handle, char *buf, unsigned count);
3245 /*D
3246 This function reads count bytes of data from the SPI
3247 device associated with the handle.
3248 
3249 . .
3250 handle: >=0, as returned by a call to [*spiOpen*]
3251  buf: an array to receive the read data bytes
3252  count: the number of bytes to read
3253 . .
3254 
3255 Returns the number of bytes transferred if OK, otherwise
3256 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
3257 D*/
3258 
3259 
3260 /*F*/
3261 int spiWrite(unsigned handle, char *buf, unsigned count);
3262 /*D
3263 This function writes count bytes of data from buf to the SPI
3264 device associated with the handle.
3265 
3266 . .
3267 handle: >=0, as returned by a call to [*spiOpen*]
3268  buf: the data bytes to write
3269  count: the number of bytes to write
3270 . .
3271 
3272 Returns the number of bytes transferred if OK, otherwise
3273 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
3274 D*/
3275 
3276 /*F*/
3277 int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count);
3278 /*D
3279 This function transfers count bytes of data from txBuf to the SPI
3280 device associated with the handle. Simultaneously count bytes of
3281 data are read from the device and placed in rxBuf.
3282 
3283 . .
3284 handle: >=0, as returned by a call to [*spiOpen*]
3285  txBuf: the data bytes to write
3286  rxBuf: the received data bytes
3287  count: the number of bytes to transfer
3288 . .
3289 
3290 Returns the number of bytes transferred if OK, otherwise
3291 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
3292 D*/
3293 
3294 
3295 /*F*/
3296 int serOpen(char *sertty, unsigned baud, unsigned serFlags);
3297 /*D
3298 This function opens a serial device at a specified baud rate
3299 and with specified flags. The device name must start with
3300 /dev/tty or /dev/serial.
3301 
3302 . .
3303  sertty: the serial device to open
3304  baud: the baud rate in bits per second, see below
3305 serFlags: 0
3306 . .
3307 
3308 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
3309 PI_SER_OPEN_FAILED.
3310 
3311 The baud rate must be one of 50, 75, 110, 134, 150,
3312 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
3313 38400, 57600, 115200, or 230400.
3314 
3315 No flags are currently defined. This parameter should be set to zero.
3316 D*/
3317 
3318 
3319 /*F*/
3320 int serClose(unsigned handle);
3321 /*D
3322 This function closes the serial device associated with handle.
3323 
3324 . .
3325 handle: >=0, as returned by a call to [*serOpen*]
3326 . .
3327 
3328 Returns 0 if OK, otherwise PI_BAD_HANDLE.
3329 D*/
3330 
3331 /*F*/
3332 int serWriteByte(unsigned handle, unsigned bVal);
3333 /*D
3334 This function writes bVal to the serial port associated with handle.
3335 
3336 . .
3337 handle: >=0, as returned by a call to [*serOpen*]
3338 . .
3339 
3340 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
3341 PI_SER_WRITE_FAILED.
3342 D*/
3343 
3344 /*F*/
3345 int serReadByte(unsigned handle);
3346 /*D
3347 This function reads a byte from the serial port associated with handle.
3348 
3349 . .
3350 handle: >=0, as returned by a call to [*serOpen*]
3351 . .
3352 
3353 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
3354 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
3355 
3356 If no data is ready PI_SER_READ_NO_DATA is returned.
3357 D*/
3358 
3359 /*F*/
3360 int serWrite(unsigned handle, char *buf, unsigned count);
3361 /*D
3362 This function writes count bytes from buf to the the serial port
3363 associated with handle.
3364 
3365 . .
3366 handle: >=0, as returned by a call to [*serOpen*]
3367  buf: the array of bytes to write
3368  count: the number of bytes to write
3369 . .
3370 
3371 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
3372 PI_SER_WRITE_FAILED.
3373 D*/
3374 
3375 
3376 /*F*/
3377 int serRead(unsigned handle, char *buf, unsigned count);
3378 /*D
3379 This function reads up count bytes from the the serial port
3380 associated with handle and writes them to buf.
3381 
3382 . .
3383 handle: >=0, as returned by a call to [*serOpen*]
3384  buf: an array to receive the read data
3385  count: the maximum number of bytes to read
3386 . .
3387 
3388 Returns the number of bytes read (>0=) if OK, otherwise PI_BAD_HANDLE,
3389 PI_BAD_PARAM, or PI_SER_READ_NO_DATA.
3390 
3391 If no data is ready zero is returned.
3392 D*/
3393 
3394 
3395 /*F*/
3396 int serDataAvailable(unsigned handle);
3397 /*D
3398 This function returns the number of bytes available
3399 to be read from the device associated with handle.
3400 
3401 . .
3402 handle: >=0, as returned by a call to [*serOpen*]
3403 . .
3404 
3405 Returns the number of bytes of data available (>=0) if OK,
3406 otherwise PI_BAD_HANDLE.
3407 D*/
3408 
3409 
3410 /*F*/
3411 int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level);
3412 /*D
3413 This function sends a trigger pulse to a GPIO. The GPIO is set to
3414 level for pulseLen microseconds and then reset to not level.
3415 
3416 . .
3417 user_gpio: 0-31
3418  pulseLen: 1-100
3419  level: 0,1
3420 . .
3421 
3422 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
3423 or PI_BAD_PULSELEN.
3424 D*/
3425 
3426 
3427 /*F*/
3428 int gpioSetWatchdog(unsigned user_gpio, unsigned timeout);
3429 /*D
3430 Sets a watchdog for a GPIO.
3431 
3432 . .
3433 user_gpio: 0-31
3434  timeout: 0-60000
3435 . .
3436 
3437 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT.
3438 
3439 The watchdog is nominally in milliseconds.
3440 
3441 One watchdog may be registered per GPIO.
3442 
3443 The watchdog may be cancelled by setting timeout to 0.
3444 
3445 Until cancelled a timeout will be reported every timeout milliseconds
3446 after the last GPIO activity.
3447 
3448 In particular:
3449 
3450 1) any registered alert function for the GPIO will be called with
3451  the level set to PI_TIMEOUT.
3452 
3453 2) any notification for the GPIO will have a report written to the
3454  fifo with the flags set to indicate a watchdog timeout.
3455 
3456 ...
3457 void aFunction(int gpio, int level, uint32_t tick)
3458 {
3459  printf("GPIO %d became %d at %d", gpio, level, tick);
3460 }
3461 
3462 // call aFunction whenever GPIO 4 changes state
3463 gpioSetAlertFunc(4, aFunction);
3464 
3465 // or approximately every 5 millis
3466 gpioSetWatchdog(4, 5);
3467 ...
3468 D*/
3469 
3470 
3471 /*F*/
3472 int gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active);
3473 /*D
3474 Sets a noise filter on a GPIO.
3475 
3476 Level changes on the GPIO are ignored until a level which has
3477 been stable for [*steady*] microseconds is detected. Level changes
3478 on the GPIO are then reported for [*active*] microseconds after
3479 which the process repeats.
3480 
3481 . .
3482 user_gpio: 0-31
3483  steady: 0-300000
3484  active: 0-1000000
3485 . .
3486 
3487 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
3488 
3489 This filter affects the GPIO samples returned to callbacks set up
3490 with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*],
3491 and [*gpioSetGetSamplesFuncEx*].
3492 
3493 It does not affect interrupts set up with [*gpioSetISRFunc*],
3494 [*gpioSetISRFuncEx*], or levels read by [*gpioRead*],
3495 [*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*].
3496 
3497 Level changes before and after the active period may
3498 be reported. Your software must be designed to cope with
3499 such reports.
3500 D*/
3501 
3502 
3503 /*F*/
3504 int gpioGlitchFilter(unsigned user_gpio, unsigned steady);
3505 /*D
3506 Sets a glitch filter on a GPIO.
3507 
3508 Level changes on the GPIO are not reported unless the level
3509 has been stable for at least [*steady*] microseconds. The
3510 level is then reported. Level changes of less than [*steady*]
3511 microseconds are ignored.
3512 
3513 . .
3514 user_gpio: 0-31
3515  steady: 0-300000
3516 . .
3517 
3518 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
3519 
3520 This filter affects the GPIO samples returned to callbacks set up
3521 with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*],
3522 and [*gpioSetGetSamplesFuncEx*].
3523 
3524 It does not affect interrupts set up with [*gpioSetISRFunc*],
3525 [*gpioSetISRFuncEx*], or levels read by [*gpioRead*],
3526 [*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*].
3527 
3528 Each (stable) edge will be timestamped [*steady*] microseconds
3529 after it was first detected.
3530 D*/
3531 
3532 
3533 /*F*/
3534 int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits);
3535 /*D
3536 Registers a function to be called (a callback) every millisecond
3537 with the latest GPIO samples.
3538 
3539 . .
3540  f: the function to call
3541 bits: the GPIO of interest
3542 . .
3543 
3544 Returns 0 if OK.
3545 
3546 The function is passed a pointer to the samples (an array of
3547 [*gpioSample_t*]), and the number of samples.
3548 
3549 Only one function can be registered.
3550 
3551 The callback may be cancelled by passing NULL as the function.
3552 
3553 The samples returned will be the union of bits, plus any active alerts,
3554 plus any active notifications.
3555 
3556 e.g. if there are alerts for GPIO 7, 8, and 9, notifications for GPIO
3557 8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for GPIO
3558 7, 8, 9, 10, 17, 23, and 24 will be reported.
3559 D*/
3560 
3561 
3562 /*F*/
3564  gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata);
3565 /*D
3566 Registers a function to be called (a callback) every millisecond
3567 with the latest GPIO samples.
3568 
3569 . .
3570  f: the function to call
3571  bits: the GPIO of interest
3572 userdata: a pointer to arbitrary user data
3573 . .
3574 
3575 Returns 0 if OK.
3576 
3577 The function is passed a pointer to the samples (an array of
3578 [*gpioSample_t*]), the number of samples, and the userdata pointer.
3579 
3580 Only one of [*gpioGetSamplesFunc*] or [*gpioGetSamplesFuncEx*] can be
3581 registered.
3582 
3583 See [*gpioSetGetSamplesFunc*] for further details.
3584 D*/
3585 
3586 
3587 /*F*/
3588 int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f);
3589 /*D
3590 Registers a function to be called (a callback) every millis milliseconds.
3591 
3592 . .
3593  timer: 0-9
3594 millis: 10-60000
3595  f: the function to call
3596 . .
3597 
3598 Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED.
3599 
3600 10 timers are supported numbered 0 to 9.
3601 
3602 One function may be registered per timer.
3603 
3604 The timer may be cancelled by passing NULL as the function.
3605 
3606 ...
3607 void bFunction(void)
3608 {
3609  printf("two seconds have elapsed");
3610 }
3611 
3612 // call bFunction every 2000 milliseconds
3613 gpioSetTimerFunc(0, 2000, bFunction);
3614 ...
3615 D*/
3616 
3617 
3618 /*F*/
3619 int gpioSetTimerFuncEx(
3620  unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata);
3621 /*D
3622 Registers a function to be called (a callback) every millis milliseconds.
3623 
3624 . .
3625  timer: 0-9.
3626  millis: 10-60000
3627  f: the function to call
3628 userdata: a pointer to arbitrary user data
3629 . .
3630 
3631 Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED.
3632 
3633 The function is passed the userdata pointer.
3634 
3635 Only one of [*gpioSetTimerFunc*] or [*gpioSetTimerFuncEx*] can be
3636 registered per timer.
3637 
3638 See [*gpioSetTimerFunc*] for further details.
3639 D*/
3640 
3641 
3642 /*F*/
3643 pthread_t *gpioStartThread(gpioThreadFunc_t f, void *userdata);
3644 /*D
3645 Starts a new thread of execution with f as the main routine.
3646 
3647 . .
3648  f: the main function for the new thread
3649 userdata: a pointer to arbitrary user data
3650 . .
3651 
3652 Returns a pointer to pthread_t if OK, otherwise NULL.
3653 
3654 The function is passed the single argument arg.
3655 
3656 The thread can be cancelled by passing the pointer to pthread_t to
3657 [*gpioStopThread*].
3658 
3659 ...
3660 #include <stdio.h>
3661 #include <pigpio.h>
3662 
3663 void *myfunc(void *arg)
3664 {
3665  while (1)
3666  {
3667  printf("%s", arg);
3668  sleep(1);
3669  }
3670 }
3671 
3672 int main(int argc, char *argv[])
3673 {
3674  pthread_t *p1, *p2, *p3;
3675 
3676  if (gpioInitialise() < 0) return 1;
3677 
3678  p1 = gpioStartThread(myfunc, "thread 1"); sleep(3);
3679 
3680  p2 = gpioStartThread(myfunc, "thread 2"); sleep(3);
3681 
3682  p3 = gpioStartThread(myfunc, "thread 3"); sleep(3);
3683 
3684  gpioStopThread(p3); sleep(3);
3685 
3686  gpioStopThread(p2); sleep(3);
3687 
3688  gpioStopThread(p1); sleep(3);
3689 
3690  gpioTerminate();
3691 }
3692 ...
3693 D*/
3694 
3695 
3696 /*F*/
3697 void gpioStopThread(pthread_t *pth);
3698 /*D
3699 Cancels the thread pointed at by pth.
3700 
3701 . .
3702 pth: a thread pointer returned by [*gpioStartThread*]
3703 . .
3704 
3705 No value is returned.
3706 
3707 The thread to be stopped should have been started with [*gpioStartThread*].
3708 D*/
3709 
3710 
3711 /*F*/
3712 int gpioStoreScript(char *script);
3713 /*D
3714 This function stores a null terminated script for later execution.
3715 
3716 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
3717 
3718 . .
3719 script: the text of the script
3720 . .
3721 
3722 The function returns a script id if the script is valid,
3723 otherwise PI_BAD_SCRIPT.
3724 D*/
3725 
3726 
3727 /*F*/
3728 int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param);
3729 /*D
3730 This function runs a stored script.
3731 
3732 . .
3733 script_id: >=0, as returned by [*gpioStoreScript*]
3734  numPar: 0-10, the number of parameters
3735  param: an array of parameters
3736 . .
3737 
3738 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
3739 PI_TOO_MANY_PARAM.
3740 
3741 param is an array of up to 10 parameters which may be referenced in
3742 the script as p0 to p9.
3743 D*/
3744 
3745 /*F*/
3746 int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param);
3747 /*D
3748 This function runs a stored script.
3749 
3750 . .
3751 script_id: >=0, as returned by [*gpioStoreScript*]
3752  numPar: 0-10, the number of parameters
3753  param: an array of parameters
3754 . .
3755 
3756 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
3757 PI_TOO_MANY_PARAM.
3758 
3759 param is an array of up to 10 parameters which may be referenced in
3760 the script as p0 to p9.
3761 D*/
3762 
3763 
3764 
3765 /*F*/
3766 int gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param);
3767 /*D
3768 This function sets the parameters of a script. The script may or
3769 may not be running. The first numPar parameters of the script are
3770 overwritten with the new values.
3771 
3772 . .
3773 script_id: >=0, as returned by [*gpioStoreScript*]
3774  numPar: 0-10, the number of parameters
3775  param: an array of parameters
3776 . .
3777 
3778 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
3779 PI_TOO_MANY_PARAM.
3780 
3781 param is an array of up to 10 parameters which may be referenced in
3782 the script as p0 to p9.
3783 D*/
3784 
3785 
3786 /*F*/
3787 int gpioScriptStatus(unsigned script_id, uint32_t *param);
3788 /*D
3789 This function returns the run status of a stored script as well as
3790 the current values of parameters 0 to 9.
3791 
3792 . .
3793 script_id: >=0, as returned by [*gpioStoreScript*]
3794  param: an array to hold the returned 10 parameters
3795 . .
3796 
3797 The function returns greater than or equal to 0 if OK,
3798 otherwise PI_BAD_SCRIPT_ID.
3799 
3800 The run status may be
3801 
3802 . .
3803 PI_SCRIPT_INITING
3804 PI_SCRIPT_HALTED
3805 PI_SCRIPT_RUNNING
3806 PI_SCRIPT_WAITING
3807 PI_SCRIPT_FAILED
3808 . .
3809 
3810 The current value of script parameters 0 to 9 are returned in param.
3811 D*/
3812 
3813 
3814 /*F*/
3815 int gpioStopScript(unsigned script_id);
3816 /*D
3817 This function stops a running script.
3818 
3819 . .
3820 script_id: >=0, as returned by [*gpioStoreScript*]
3821 . .
3822 
3823 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
3824 D*/
3825 
3826 
3827 /*F*/
3828 int gpioDeleteScript(unsigned script_id);
3829 /*D
3830 This function deletes a stored script.
3831 
3832 . .
3833 script_id: >=0, as returned by [*gpioStoreScript*]
3834 . .
3835 
3836 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
3837 D*/
3838 
3839 
3840 /*F*/
3841 int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f);
3842 /*D
3843 Registers a function to be called (a callback) when a signal occurs.
3844 
3845 . .
3846 signum: 0-63
3847  f: the callback function
3848 . .
3849 
3850 Returns 0 if OK, otherwise PI_BAD_SIGNUM.
3851 
3852 The function is passed the signal number.
3853 
3854 One function may be registered per signal.
3855 
3856 The callback may be cancelled by passing NULL.
3857 
3858 By default all signals are treated as fatal and cause the library
3859 to call gpioTerminate and then exit.
3860 D*/
3861 
3862 
3863 /*F*/
3865  unsigned signum, gpioSignalFuncEx_t f, void *userdata);
3866 /*D
3867 Registers a function to be called (a callback) when a signal occurs.
3868 
3869 . .
3870  signum: 0-63
3871  f: the callback function
3872 userdata: a pointer to arbitrary user data
3873 . .
3874 
3875 Returns 0 if OK, otherwise PI_BAD_SIGNUM.
3876 
3877 The function is passed the signal number and the userdata pointer.
3878 
3879 Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be
3880 registered per signal.
3881 
3882 See gpioSetSignalFunc for further details.
3883 D*/
3884 
3885 
3886 /*F*/
3887 uint32_t gpioRead_Bits_0_31(void);
3888 /*D
3889 Returns the current level of GPIO 0-31.
3890 D*/
3891 
3892 
3893 /*F*/
3894 uint32_t gpioRead_Bits_32_53(void);
3895 /*D
3896 Returns the current level of GPIO 32-53.
3897 D*/
3898 
3899 
3900 /*F*/
3901 int gpioWrite_Bits_0_31_Clear(uint32_t bits);
3902 /*D
3903 Clears GPIO 0-31 if the corresponding bit in bits is set.
3904 
3905 . .
3906 bits: a bit mask of GPIO to clear
3907 . .
3908 
3909 Returns 0 if OK.
3910 
3911 ...
3912 // To clear (set to 0) GPIO 4, 7, and 15
3913 gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) );
3914 ...
3915 D*/
3916 
3917 
3918 /*F*/
3919 int gpioWrite_Bits_32_53_Clear(uint32_t bits);
3920 /*D
3921 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
3922 
3923 . .
3924 bits: a bit mask of GPIO to clear
3925 . .
3926 
3927 Returns 0 if OK.
3928 D*/
3929 
3930 
3931 /*F*/
3932 int gpioWrite_Bits_0_31_Set(uint32_t bits);
3933 /*D
3934 Sets GPIO 0-31 if the corresponding bit in bits is set.
3935 
3936 . .
3937 bits: a bit mask of GPIO to set
3938 . .
3939 
3940 Returns 0 if OK.
3941 D*/
3942 
3943 
3944 /*F*/
3945 int gpioWrite_Bits_32_53_Set(uint32_t bits);
3946 /*D
3947 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
3948 
3949 . .
3950 bits: a bit mask of GPIO to set
3951 . .
3952 
3953 Returns 0 if OK.
3954 
3955 ...
3956 // To set (set to 1) GPIO 32, 40, and 53
3957 gpioWrite_Bits_32_53_Set((1<<(32-32)) | (1<<(40-32)) | (1<<(53-32)));
3958 ...
3959 D*/
3960 
3961 /*F*/
3962 int gpioHardwareClock(unsigned gpio, unsigned clkfreq);
3963 /*D
3964 Starts a hardware clock on a GPIO at the specified frequency.
3965 Frequencies above 30MHz are unlikely to work.
3966 
3967 . .
3968  gpio: see description
3969 clkfreq: 0 (off) or 4689-250000000 (250M)
3970 . .
3971 
3972 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HCLK_GPIO,
3973 PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
3974 
3975 The same clock is available on multiple GPIO. The latest
3976 frequency setting will be used by all GPIO which share a clock.
3977 
3978 The GPIO must be one of the following.
3979 
3980 . .
3981 4 clock 0 All models
3982 5 clock 1 All models but A and B (reserved for system use)
3983 6 clock 2 All models but A and B
3984 20 clock 0 All models but A and B
3985 21 clock 1 All models but A and Rev.2 B (reserved for system use)
3986 
3987 32 clock 0 Compute module only
3988 34 clock 0 Compute module only
3989 42 clock 1 Compute module only (reserved for system use)
3990 43 clock 2 Compute module only
3991 44 clock 1 Compute module only (reserved for system use)
3992 . .
3993 
3994 Access to clock 1 is protected by a password as its use will likely
3995 crash the Pi. The password is given by or'ing 0x5A000000 with the
3996 GPIO number.
3997 D*/
3998 
3999 /*F*/
4000 int gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty);
4001 /*D
4002 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
4003 Frequencies above 30MHz are unlikely to work.
4004 
4005 NOTE: Any waveform started by [*gpioWaveTxSend*], or
4006 [*gpioWaveChain*] will be cancelled.
4007 
4008 This function is only valid if the pigpio main clock is PCM. The
4009 main clock defaults to PCM but may be overridden by a call to
4010 [*gpioCfgClock*].
4011 
4012 . .
4013  gpio: see description
4014 PWMfreq: 0 (off) or 1-125000000 (125M)
4015 PWMduty: 0 (off) to 1000000 (1M)(fully on)
4016 . .
4017 
4018 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HPWM_GPIO,
4019 PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, or PI_HPWM_ILLEGAL.
4020 
4021 The same PWM channel is available on multiple GPIO. The latest
4022 frequency and dutycycle setting will be used by all GPIO which
4023 share a PWM channel.
4024 
4025 The GPIO must be one of the following.
4026 
4027 . .
4028 12 PWM channel 0 All models but A and B
4029 13 PWM channel 1 All models but A and B
4030 18 PWM channel 0 All models
4031 19 PWM channel 1 All models but A and B
4032 
4033 40 PWM channel 0 Compute module only
4034 41 PWM channel 1 Compute module only
4035 45 PWM channel 1 Compute module only
4036 52 PWM channel 0 Compute module only
4037 53 PWM channel 1 Compute module only
4038 . .
4039 
4040 The actual number of steps beween off and fully on is the
4041 integral part of 250 million divided by PWMfreq.
4042 
4043 The actual frequency set is 250 million / steps.
4044 
4045 There will only be a million steps for a PWMfreq of 250.
4046 Lower frequencies will have more steps and higher
4047 frequencies will have fewer steps. PWMduty is
4048 automatically scaled to take this into account.
4049 D*/
4050 
4051 /*F*/
4052 int gpioTime(unsigned timetype, int *seconds, int *micros);
4053 /*D
4054 Updates the seconds and micros variables with the current time.
4055 
4056 . .
4057 timetype: 0 (relative), 1 (absolute)
4058  seconds: a pointer to an int to hold seconds
4059  micros: a pointer to an int to hold microseconds
4060 . .
4061 
4062 Returns 0 if OK, otherwise PI_BAD_TIMETYPE.
4063 
4064 If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the
4065 number of seconds and microseconds since the epoch (1st January 1970).
4066 
4067 If timetype is PI_TIME_RELATIVE updates seconds and micros with the
4068 number of seconds and microseconds since the library was initialised.
4069 
4070 ...
4071 int secs, mics;
4072 
4073 // print the number of seconds since the library was started
4074 gpioTime(PI_TIME_RELATIVE, &secs, &mics);
4075 printf("library started %d.%03d seconds ago", secs, mics/1000);
4076 ...
4077 D*/
4078 
4079 
4080 /*F*/
4081 int gpioSleep(unsigned timetype, int seconds, int micros);
4082 /*D
4083 Sleeps for the number of seconds and microseconds specified by seconds
4084 and micros.
4085 
4086 . .
4087 timetype: 0 (relative), 1 (absolute)
4088  seconds: seconds to sleep
4089  micros: microseconds to sleep
4090 . .
4091 
4092 Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS,
4093 or PI_BAD_MICROS.
4094 
4095 If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds
4096 and microseconds since the epoch (1st January 1970) has elapsed. System
4097 clock changes are taken into account.
4098 
4099 If timetype is PI_TIME_RELATIVE the sleep is for the specified number
4100 of seconds and microseconds. System clock changes do not effect the
4101 sleep length.
4102 
4103 For short delays (say, 50 microseonds or less) use [*gpioDelay*].
4104 
4105 ...
4106 gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds
4107 
4108 gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 0.1 seconds
4109 
4110 gpioSleep(PI_TIME_RELATIVE, 60, 0); // sleep for one minute
4111 ...
4112 D*/
4113 
4114 
4115 /*F*/
4116 uint32_t gpioDelay(uint32_t micros);
4117 /*D
4118 Delays for at least the number of microseconds specified by micros.
4119 
4120 . .
4121 micros: the number of microseconds to sleep
4122 . .
4123 
4124 Returns the actual length of the delay in microseconds.
4125 
4126 Delays of 100 microseconds or less use busy waits.
4127 D*/
4128 
4129 
4130 /*F*/
4131 uint32_t gpioTick(void);
4132 /*D
4133 Returns the current system tick.
4134 
4135 Tick is the number of microseconds since system boot.
4136 
4137 As tick is an unsigned 32 bit quantity it wraps around after
4138 2^32 microseconds, which is approximately 1 hour 12 minutes.
4139 
4140 You don't need to worry about the wrap around as long as you
4141 take a tick (uint32_t) from another tick, i.e. the following
4142 code will always provide the correct difference.
4143 
4144 ...
4145 uint32_t startTick, endTick;
4146 int diffTick;
4147 
4148 startTick = gpioTick();
4149 
4150 // do some processing
4151 
4152 endTick = gpioTick();
4153 
4154 diffTick = endTick - startTick;
4155 
4156 printf("some processing took %d microseconds", diffTick);
4157 ...
4158 D*/
4159 
4160 
4161 /*F*/
4162 unsigned gpioHardwareRevision(void);
4163 /*D
4164 Returns the hardware revision.
4165 
4166 If the hardware revision can not be found or is not a valid hexadecimal
4167 number the function returns 0.
4168 
4169 The hardware revision is the last few characters on the Revision line of
4170 /proc/cpuinfo.
4171 
4172 The revision number can be used to determine the assignment of GPIO
4173 to pins (see [*gpio*]).
4174 
4175 There are at least three types of board.
4176 
4177 Type 1 boards have hardware revision numbers of 2 and 3.
4178 
4179 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
4180 
4181 Type 3 boards have hardware revision numbers of 16 or greater.
4182 
4183 for "Revision : 0002" the function returns 2.
4184 for "Revision : 000f" the function returns 15.
4185 for "Revision : 000g" the function returns 0.
4186 D*/
4187 
4188 
4189 /*F*/
4190 unsigned gpioVersion(void);
4191 /*D
4192 Returns the pigpio version.
4193 D*/
4194 
4195 
4196 /*F*/
4197 int gpioGetPad(unsigned pad);
4198 /*D
4199 This function returns the pad drive strength in mA.
4200 
4201 . .
4202 pad: 0-2, the pad to get
4203 . .
4204 
4205 Returns the pad drive strength if OK, otherwise PI_BAD_PAD.
4206 
4207 Pad @ GPIO
4208 0 @ 0-27
4209 1 @ 28-45
4210 2 @ 46-53
4211 
4212 ...
4213 strength = gpioGetPad(1); // get pad 1 strength
4214 ...
4215 D*/
4216 
4217 
4218 /*F*/
4219 int gpioSetPad(unsigned pad, unsigned padStrength);
4220 /*D
4221 This function sets the pad drive strength in mA.
4222 
4223 . .
4224  pad: 0-2, the pad to set
4225 padStrength: 1-16 mA
4226 . .
4227 
4228 Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH.
4229 
4230 Pad @ GPIO
4231 0 @ 0-27
4232 1 @ 28-45
4233 2 @ 46-53
4234 
4235 ...
4236 gpioSetPad(0, 16); // set pad 0 strength to 16 mA
4237 ...
4238 D*/
4239 
4240 /*F*/
4241 int eventMonitor(unsigned handle, uint32_t bits);
4242 /*D
4243 This function selects the events to be reported on a previously
4244 opened handle.
4245 
4246 . .
4247 handle: >=0, as returned by [*gpioNotifyOpen*]
4248  bits: a bit mask indicating the events of interest
4249 . .
4250 
4251 Returns 0 if OK, otherwise PI_BAD_HANDLE.
4252 
4253 A report is sent each time an event is triggered providing the
4254 corresponding bit in bits is set.
4255 
4256 See [*gpioNotifyBegin*] for the notification format.
4257 
4258 ...
4259 // Start reporting events 3, 6, and 7.
4260 
4261 // bit 76543210
4262 // (0xC8 = 0b11001000)
4263 
4264 eventMonitor(h, 0xC8);
4265 ...
4266 
4267 D*/
4268 
4269 /*F*/
4270 int eventSetFunc(unsigned event, eventFunc_t f);
4271 /*D
4272 Registers a function to be called (a callback) when the specified
4273 event occurs.
4274 
4275 . .
4276 event: 0-31
4277  f: the callback function
4278 . .
4279 
4280 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
4281 
4282 One function may be registered per event.
4283 
4284 The function is passed the event, and the tick.
4285 
4286 The callback may be cancelled by passing NULL as the function.
4287 D*/
4288 
4289 /*F*/
4290 int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata);
4291 /*D
4292 Registers a function to be called (a callback) when the specified
4293 event occurs.
4294 
4295 . .
4296  event: 0-31
4297  f: the callback function
4298 userdata: pointer to arbitrary user data
4299 . .
4300 
4301 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
4302 
4303 One function may be registered per event.
4304 
4305 The function is passed the event, the tick, and the ueserdata pointer.
4306 
4307 The callback may be cancelled by passing NULL as the function.
4308 
4309 Only one of [*eventSetFunc*] or [*eventSetFuncEx*] can be
4310 registered per event.
4311 D*/
4312 
4313 /*F*/
4314 int eventTrigger(unsigned event);
4315 /*D
4316 This function signals the occurrence of an event.
4317 
4318 . .
4319 event: 0-31, the event
4320 . .
4321 
4322 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
4323 
4324 An event is a signal used to inform one or more consumers
4325 to start an action. Each consumer which has registered an interest
4326 in the event (e.g. by calling [*eventSetFunc*]) will be informed by
4327 a callback.
4328 
4329 One event, PI_EVENT_BSC (31) is predefined. This event is
4330 auto generated on BSC slave activity.
4331 
4332 The meaning of other events is arbitrary.
4333 
4334 Note that other than its id and its tick there is no data associated
4335 with an event.
4336 D*/
4337 
4338 
4339 /*F*/
4340 int shell(char *scriptName, char *scriptString);
4341 /*D
4342 This function uses the system call to execute a shell script
4343 with the given string as its parameter.
4344 
4345 . .
4346  scriptName: the name of the script, only alphanumeric characters,
4347  '-' and '_' are allowed in the name
4348 scriptString: the string to pass to the script
4349 . .
4350 
4351 The exit status of the system call is returned if OK, otherwise
4352 PI_BAD_SHELL_STATUS.
4353 
4354 scriptName must exist in /opt/pigpio/cgi and must be executable.
4355 
4356 The returned exit status is normally 256 times that set by the
4357 shell script exit function. If the script can't be found 32512 will
4358 be returned.
4359 
4360 The following table gives some example returned statuses.
4361 
4362 Script exit status @ Returned system call status
4363 1 @ 256
4364 5 @ 1280
4365 10 @ 2560
4366 200 @ 51200
4367 script not found @ 32512
4368 
4369 ...
4370 // pass two parameters, hello and world
4371 status = shell("scr1", "hello world");
4372 
4373 // pass three parameters, hello, string with spaces, and world
4374 status = shell("scr1", "hello 'string with spaces' world");
4375 
4376 // pass one parameter, hello string with spaces world
4377 status = shell("scr1", "\"hello string with spaces world\"");
4378 ...
4379 D*/
4380 
4381 #pragma GCC diagnostic push
4382 
4383 #pragma GCC diagnostic ignored "-Wcomment"
4384 
4385 /*F*/
4386 int fileOpen(char *file, unsigned mode);
4387 /*D
4388 This function returns a handle to a file opened in a specified mode.
4389 
4390 . .
4391 file: the file to open
4392 mode: the file open mode
4393 . .
4394 
4395 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS,
4396 PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR.
4397 
4398 File
4399 
4400 A file may only be opened if permission is granted by an entry in
4401 /opt/pigpio/access. This is intended to allow remote access to files
4402 in a more or less controlled manner.
4403 
4404 Each entry in /opt/pigpio/access takes the form of a file path
4405 which may contain wildcards followed by a single letter permission.
4406 The permission may be R for read, W for write, U for read/write,
4407 and N for no access.
4408 
4409 Where more than one entry matches a file the most specific rule
4410 applies. If no entry matches a file then access is denied.
4411 
4412 Suppose /opt/pigpio/access contains the following entries
4413 
4414 . .
4415 /home/* n
4416 /home/pi/shared/dir_1/* w
4417 /home/pi/shared/dir_2/* r
4418 /home/pi/shared/dir_3/* u
4419 /home/pi/shared/dir_1/file.txt n
4420 . .
4421 
4422 Files may be written in directory dir_1 with the exception
4423 of file.txt.
4424 
4425 Files may be read in directory dir_2.
4426 
4427 Files may be read and written in directory dir_3.
4428 
4429 If a directory allows read, write, or read/write access then files may
4430 be created in that directory.
4431 
4432 In an attempt to prevent risky permissions the following paths are
4433 ignored in /opt/pigpio/access.
4434 
4435 . .
4436 a path containing ..
4437 a path containing only wildcards (*?)
4438 a path containing less than two non-wildcard parts
4439 . .
4440 
4441 Mode
4442 
4443 The mode may have the following values.
4444 
4445 Macro @ Value @ Meaning
4446 PI_FILE_READ @ 1 @ open file for reading
4447 PI_FILE_WRITE @ 2 @ open file for writing
4448 PI_FILE_RW @ 3 @ open file for reading and writing
4449 
4450 The following values may be or'd into the mode.
4451 
4452 Macro @ Value @ Meaning
4453 PI_FILE_APPEND @ 4 @ Writes append data to the end of the file
4454 PI_FILE_CREATE @ 8 @ The file is created if it doesn't exist
4455 PI_FILE_TRUNC @ 16 @ The file is truncated
4456 
4457 Newly created files are owned by root with permissions owner read and write.
4458 
4459 ...
4460 #include <stdio.h>
4461 #include <pigpio.h>
4462 
4463 int main(int argc, char *argv[])
4464 {
4465  int handle, c;
4466  char buf[60000];
4467 
4468  if (gpioInitialise() < 0) return 1;
4469 
4470  // assumes /opt/pigpio/access contains the following line
4471  // /ram/*.c r
4472 
4473  handle = fileOpen("/ram/pigpio.c", PI_FILE_READ);
4474 
4475  if (handle >= 0)
4476  {
4477  while ((c=fileRead(handle, buf, sizeof(buf)-1)))
4478  {
4479  buf[c] = 0;
4480  printf("%s", buf);
4481  }
4482 
4483  fileClose(handle);
4484  }
4485 
4486  gpioTerminate();
4487 }
4488 ...
4489 D*/
4490 
4491 #pragma GCC diagnostic pop
4492 
4493 /*F*/
4494 int fileClose(unsigned handle);
4495 /*D
4496 This function closes the file associated with handle.
4497 
4498 . .
4499 handle: >=0, as returned by a call to [*fileOpen*]
4500 . .
4501 
4502 Returns 0 if OK, otherwise PI_BAD_HANDLE.
4503 
4504 ...
4505 fileClose(h);
4506 ...
4507 D*/
4508 
4509 
4510 /*F*/
4511 int fileWrite(unsigned handle, char *buf, unsigned count);
4512 /*D
4513 This function writes count bytes from buf to the the file
4514 associated with handle.
4515 
4516 . .
4517 handle: >=0, as returned by a call to [*fileOpen*]
4518  buf: the array of bytes to write
4519  count: the number of bytes to write
4520 . .
4521 
4522 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM,
4523 PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE.
4524 
4525 ...
4526 status = fileWrite(h, buf, count);
4527 if (status == 0)
4528 {
4529  // okay
4530 }
4531 else
4532 {
4533  // error
4534 }
4535 ...
4536 D*/
4537 
4538 
4539 /*F*/
4540 int fileRead(unsigned handle, char *buf, unsigned count);
4541 /*D
4542 This function reads up to count bytes from the the file
4543 associated with handle and writes them to buf.
4544 
4545 . .
4546 handle: >=0, as returned by a call to [*fileOpen*]
4547  buf: an array to receive the read data
4548  count: the maximum number of bytes to read
4549 . .
4550 
4551 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE.
4552 
4553 ...
4554 if (fileRead(h, buf, sizeof(buf)) > 0)
4555 {
4556  // process read data
4557 }
4558 ...
4559 D*/
4560 
4561 
4562 /*F*/
4563 int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom);
4564 /*D
4565 This function seeks to a position within the file associated
4566 with handle.
4567 
4568 . .
4569  handle: >=0, as returned by a call to [*fileOpen*]
4570 seekOffset: the number of bytes to move. Positive offsets
4571  move forward, negative offsets backwards.
4572  seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1),
4573  or PI_FROM_END (2)
4574 . .
4575 
4576 Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK.
4577 
4578 ...
4579 fileSeek(0, 20, PI_FROM_START); // Seek to start plus 20
4580 
4581 size = fileSeek(0, 0, PI_FROM_END); // Seek to end, return size
4582 
4583 pos = fileSeek(0, 0, PI_FROM_CURRENT); // Return current position
4584 ...
4585 D*/
4586 
4587 #pragma GCC diagnostic push
4588 
4589 #pragma GCC diagnostic ignored "-Wcomment"
4590 
4591 /*F*/
4592 int fileList(char *fpat, char *buf, unsigned count);
4593 /*D
4594 This function returns a list of files which match a pattern. The
4595 pattern may contain wildcards.
4596 
4597 . .
4598  fpat: file pattern to match
4599  buf: an array to receive the matching file names
4600 count: the maximum number of bytes to read
4601 . .
4602 
4603 Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS,
4604 or PI_NO_FILE_MATCH.
4605 
4606 The pattern must match an entry in /opt/pigpio/access. The pattern
4607 may contain wildcards. See [*fileOpen*].
4608 
4609 NOTE
4610 
4611 The returned value is not the number of files, it is the number
4612 of bytes in the buffer. The file names are separated by newline
4613 characters.
4614 
4615 ...
4616 #include <stdio.h>
4617 #include <pigpio.h>
4618 
4619 int main(int argc, char *argv[])
4620 {
4621  int c;
4622  char buf[1000];
4623 
4624  if (gpioInitialise() < 0) return 1;
4625 
4626  // assumes /opt/pigpio/access contains the following line
4627  // /ram/*.c r
4628 
4629  c = fileList("/ram/p*.c", buf, sizeof(buf));
4630 
4631  if (c >= 0)
4632  {
4633  // terminate string
4634  buf[c] = 0;
4635  printf("%s", buf);
4636  }
4637 
4638  gpioTerminate();
4639 }
4640 ...
4641 D*/
4642 
4643 #pragma GCC diagnostic pop
4644 
4645 
4646 /*F*/
4647 int gpioCfgBufferSize(unsigned cfgMillis);
4648 /*D
4649 Configures pigpio to buffer cfgMillis milliseconds of GPIO samples.
4650 
4651 This function is only effective if called before [*gpioInitialise*].
4652 
4653 . .
4654 cfgMillis: 100-10000
4655 . .
4656 
4657 The default setting is 120 milliseconds.
4658 
4659 The intention is to allow for bursts of data and protection against
4660 other processes hogging cpu time.
4661 
4662 I haven't seen a process locked out for more than 100 milliseconds.
4663 
4664 Making the buffer bigger uses a LOT of memory at the more frequent
4665 sampling rates as shown in the following table in MBs.
4666 
4667 . .
4668  buffer milliseconds
4669  120 250 500 1sec 2sec 4sec 8sec
4670 
4671  1 16 31 55 107 --- --- ---
4672  2 10 18 31 55 107 --- ---
4673 sample 4 8 12 18 31 55 107 ---
4674  rate 5 8 10 14 24 45 87 ---
4675  (us) 8 6 8 12 18 31 55 107
4676  10 6 8 10 14 24 45 87
4677 . .
4678 D*/
4679 
4680 
4681 /*F*/
4682 int gpioCfgClock(
4683  unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource);
4684 /*D
4685 Configures pigpio to use a particular sample rate timed by a specified
4686 peripheral.
4687 
4688 This function is only effective if called before [*gpioInitialise*].
4689 
4690 . .
4691  cfgMicros: 1, 2, 4, 5, 8, 10
4692 cfgPeripheral: 0 (PWM), 1 (PCM)
4693  cfgSource: deprecated, value is ignored
4694 . .
4695 
4696 The timings are provided by the specified peripheral (PWM or PCM).
4697 
4698 The default setting is 5 microseconds using the PCM peripheral.
4699 
4700 The approximate CPU percentage used for each sample rate is:
4701 
4702 . .
4703 sample cpu
4704  rate %
4705 
4706  1 25
4707  2 16
4708  4 11
4709  5 10
4710  8 15
4711  10 14
4712 . .
4713 
4714 A sample rate of 5 microseconds seeems to be the sweet spot.
4715 D*/
4716 
4717 
4718 /*F*/
4719 int gpioCfgDMAchannel(unsigned DMAchannel); /* DEPRECATED */
4720 /*D
4721 Configures pigpio to use the specified DMA channel.
4722 
4723 This function is only effective if called before [*gpioInitialise*].
4724 
4725 . .
4726 DMAchannel: 0-14
4727 . .
4728 
4729 The default setting is to use channel 14.
4730 D*/
4731 
4732 
4733 /*F*/
4734 int gpioCfgDMAchannels(
4735  unsigned primaryChannel, unsigned secondaryChannel);
4736 /*D
4737 Configures pigpio to use the specified DMA channels.
4738 
4739 This function is only effective if called before [*gpioInitialise*].
4740 
4741 . .
4742  primaryChannel: 0-14
4743 secondaryChannel: 0-14
4744 . .
4745 
4746 The default setting is to use channel 14 for the primary channel and
4747 channel 6 for the secondary channel.
4748 
4749 The secondary channel is only used for the transmission of waves.
4750 
4751 If possible use one of channels 0 to 6 for the secondary channel
4752 (a full channel).
4753 
4754 A full channel only requires one DMA control block regardless of the
4755 length of a pulse delay. Channels 7 to 14 (lite channels) require
4756 one DMA control block for each 16383 microseconds of delay. I.e.
4757 a 10 second pulse delay requires one control block on a full channel
4758 and 611 control blocks on a lite channel.
4759 D*/
4760 
4761 
4762 /*F*/
4763 int gpioCfgPermissions(uint64_t updateMask);
4764 /*D
4765 Configures pigpio to restrict GPIO updates via the socket or pipe
4766 interfaces to the GPIO specified by the mask. Programs directly
4767 calling the pigpio library (i.e. linked with -lpigpio are not
4768 affected). A GPIO update is a write to a GPIO or a GPIO mode
4769 change or any function which would force such an action.
4770 
4771 This function is only effective if called before [*gpioInitialise*].
4772 
4773 . .
4774 updateMask: bit (1<<n) is set for each GPIO n which may be updated
4775 . .
4776 
4777 The default setting depends upon the Pi model. The user GPIO are
4778 added to the mask.
4779 
4780 If the board revision is not recognised then GPIO 2-27 are allowed.
4781 
4782 Unknown board @ PI_DEFAULT_UPDATE_MASK_UNKNOWN @ 0x0FFFFFFC
4783 Type 1 board @ PI_DEFAULT_UPDATE_MASK_B1 @ 0x03E6CF93
4784 Type 2 board @ PI_DEFAULT_UPDATE_MASK_A_B2 @ 0xFBC6CF9C
4785 Type 3 board @ PI_DEFAULT_UPDATE_MASK_R3 @ 0x0FFFFFFC
4786 D*/
4787 
4788 
4789 /*F*/
4790 int gpioCfgSocketPort(unsigned port);
4791 /*D
4792 Configures pigpio to use the specified socket port.
4793 
4794 This function is only effective if called before [*gpioInitialise*].
4795 
4796 . .
4797 port: 1024-32000
4798 . .
4799 
4800 The default setting is to use port 8888.
4801 D*/
4802 
4803 
4804 /*F*/
4805 int gpioCfgInterfaces(unsigned ifFlags);
4806 /*D
4807 Configures pigpio support of the fifo and socket interfaces.
4808 
4809 This function is only effective if called before [*gpioInitialise*].
4810 
4811 . .
4812 ifFlags: 0-7
4813 . .
4814 
4815 The default setting (0) is that both interfaces are enabled.
4816 
4817 Or in PI_DISABLE_FIFO_IF to disable the pipe interface.
4818 
4819 Or in PI_DISABLE_SOCK_IF to disable the socket interface.
4820 
4821 Or in PI_LOCALHOST_SOCK_IF to disable remote socket
4822 access (this means that the socket interface is only
4823 usable from the local Pi).
4824 D*/
4825 
4826 
4827 /*F*/
4828 int gpioCfgMemAlloc(unsigned memAllocMode);
4829 /*D
4830 Selects the method of DMA memory allocation.
4831 
4832 This function is only effective if called before [*gpioInitialise*].
4833 
4834 . .
4835 memAllocMode: 0-2
4836 . .
4837 
4838 There are two methods of DMA memory allocation. The original method
4839 uses the /proc/self/pagemap file to allocate bus memory. The new
4840 method uses the mailbox property interface to allocate bus memory.
4841 
4842 Auto will use the mailbox method unless a larger than default buffer
4843 size is requested with [*gpioCfgBufferSize*].
4844 D*/
4845 
4846 
4847 /*F*/
4848 int gpioCfgNetAddr(int numSockAddr, uint32_t *sockAddr);
4849 /*D
4850 Sets the network addresses which are allowed to talk over the
4851 socket interface.
4852 
4853 This function is only effective if called before [*gpioInitialise*].
4854 
4855 . .
4856 numSockAddr: 0-256 (0 means all addresses allowed)
4857  sockAddr: an array of permitted network addresses.
4858 . .
4859 D*/
4860 
4861 
4862 /*F*/
4863 int gpioCfgInternals(unsigned cfgWhat, unsigned cfgVal);
4864 /*D
4865 Used to tune internal settings.
4866 
4867 . .
4868 cfgWhat: see source code
4869  cfgVal: see source code
4870 . .
4871 D*/
4872 
4873 
4874 /*F*/
4875 uint32_t gpioCfgGetInternals(void);
4876 /*D
4877 This function returns the current library internal configuration
4878 settings.
4879 D*/
4880 
4881 /*F*/
4882 int gpioCfgSetInternals(uint32_t cfgVal);
4883 /*D
4884 This function sets the current library internal configuration
4885 settings.
4886 
4887 . .
4888 cfgVal: see source code
4889 . .
4890 D*/
4891 
4892 
4893 /*F*/
4894 int gpioCustom1(unsigned arg1, unsigned arg2, char *argx, unsigned argc);
4895 /*D
4896 This function is available for user customisation.
4897 
4898 It returns a single integer value.
4899 
4900 . .
4901 arg1: >=0
4902 arg2: >=0
4903 argx: extra (byte) arguments
4904 argc: number of extra arguments
4905 . .
4906 
4907 Returns >= 0 if OK, less than 0 indicates a user defined error.
4908 D*/
4909 
4910 
4911 /*F*/
4912 int gpioCustom2(unsigned arg1, char *argx, unsigned argc,
4913  char *retBuf, unsigned retMax);
4914 /*D
4915 This function is available for user customisation.
4916 
4917 It differs from gpioCustom1 in that it returns an array of bytes
4918 rather than just an integer.
4919 
4920 The returned value is an integer indicating the number of returned bytes.
4921 . .
4922  arg1: >=0
4923  argx: extra (byte) arguments
4924  argc: number of extra arguments
4925 retBuf: buffer for returned bytes
4926 retMax: maximum number of bytes to return
4927 . .
4928 
4929 Returns >= 0 if OK, less than 0 indicates a user defined error.
4930 
4931 The number of returned bytes must be retMax or less.
4932 D*/
4933 
4934 
4935 /*F*/
4936 int rawWaveAddSPI(
4937  rawSPI_t *spi,
4938  unsigned offset,
4939  unsigned spiSS,
4940  char *buf,
4941  unsigned spiTxBits,
4942  unsigned spiBitFirst,
4943  unsigned spiBitLast,
4944  unsigned spiBits);
4945 /*D
4946 This function adds a waveform representing SPI data to the
4947 existing waveform (if any).
4948 
4949 . .
4950  spi: a pointer to a spi object
4951  offset: microseconds from the start of the waveform
4952  spiSS: the slave select GPIO
4953  buf: the bits to transmit, most significant bit first
4954  spiTxBits: the number of bits to write
4955 spiBitFirst: the first bit to read
4956  spiBitLast: the last bit to read
4957  spiBits: the number of bits to transfer
4958 . .
4959 
4960 Returns the new total number of pulses in the current waveform if OK,
4961 otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES.
4962 
4963 Not intended for general use.
4964 D*/
4965 
4966 /*F*/
4967 int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses);
4968 /*D
4969 This function adds a number of pulses to the current waveform.
4970 
4971 . .
4972 numPulses: the number of pulses
4973  pulses: the array containing the pulses
4974 . .
4975 
4976 Returns the new total number of pulses in the current waveform if OK,
4977 otherwise PI_TOO_MANY_PULSES.
4978 
4979 The advantage of this function over gpioWaveAddGeneric is that it
4980 allows the setting of the flags field.
4981 
4982 The pulses are interleaved in time order within the existing waveform
4983 (if any).
4984 
4985 Merging allows the waveform to be built in parts, that is the settings
4986 for GPIO#1 can be added, and then GPIO#2 etc.
4987 
4988 If the added waveform is intended to start after or within the existing
4989 waveform then the first pulse should consist of a delay.
4990 
4991 Not intended for general use.
4992 D*/
4993 
4994 /*F*/
4995 unsigned rawWaveCB(void);
4996 /*D
4997 Returns the number of the cb being currently output.
4998 
4999 Not intended for general use.
5000 D*/
5001 
5002 /*F*/
5003 rawCbs_t *rawWaveCBAdr(int cbNum);
5004 /*D
5005 Return the (Linux) address of contol block cbNum.
5006 
5007 . .
5008 cbNum: the cb of interest
5009 . .
5010 
5011 Not intended for general use.
5012 D*/
5013 
5014 /*F*/
5015 uint32_t rawWaveGetOOL(int pos);
5016 /*D
5017 Gets the OOL parameter stored at pos.
5018 
5019 . .
5020 pos: the position of interest.
5021 . .
5022 
5023 Not intended for general use.
5024 D*/
5025 
5026 
5027 /*F*/
5028 void rawWaveSetOOL(int pos, uint32_t lVal);
5029 /*D
5030 Sets the OOL parameter stored at pos to value.
5031 
5032 . .
5033  pos: the position of interest
5034 lVal: the value to write
5035 . .
5036 
5037 Not intended for general use.
5038 D*/
5039 
5040 /*F*/
5041 uint32_t rawWaveGetOut(int pos);
5042 /*D
5043 Gets the wave output parameter stored at pos.
5044 
5045 DEPRECATED: use rawWaveGetOOL instead.
5046 
5047 . .
5048 pos: the position of interest.
5049 . .
5050 
5051 Not intended for general use.
5052 D*/
5053 
5054 
5055 /*F*/
5056 void rawWaveSetOut(int pos, uint32_t lVal);
5057 /*D
5058 Sets the wave output parameter stored at pos to value.
5059 
5060 DEPRECATED: use rawWaveSetOOL instead.
5061 
5062 . .
5063  pos: the position of interest
5064 lVal: the value to write
5065 . .
5066 
5067 Not intended for general use.
5068 D*/
5069 
5070 /*F*/
5071 uint32_t rawWaveGetIn(int pos);
5072 /*D
5073 Gets the wave input value parameter stored at pos.
5074 
5075 DEPRECATED: use rawWaveGetOOL instead.
5076 
5077 . .
5078 pos: the position of interest
5079 . .
5080 
5081 Not intended for general use.
5082 D*/
5083 
5084 
5085 /*F*/
5086 void rawWaveSetIn(int pos, uint32_t lVal);
5087 /*D
5088 Sets the wave input value stored at pos to value.
5089 
5090 DEPRECATED: use rawWaveSetOOL instead.
5091 
5092 . .
5093  pos: the position of interest
5094 lVal: the value to write
5095 . .
5096 
5097 Not intended for general use.
5098 D*/
5099 
5100 /*F*/
5101 rawWaveInfo_t rawWaveInfo(int wave_id);
5102 /*D
5103 Gets details about the wave with id wave_id.
5104 
5105 . .
5106 wave_id: the wave of interest
5107 . .
5108 
5109 Not intended for general use.
5110 D*/
5111 
5112 /*F*/
5113 int getBitInBytes(int bitPos, char *buf, int numBits);
5114 /*D
5115 Returns the value of the bit bitPos bits from the start of buf. Returns
5116 0 if bitPos is greater than or equal to numBits.
5117 
5118 . .
5119  bitPos: bit index from the start of buf
5120  buf: array of bits
5121 numBits: number of valid bits in buf
5122 . .
5123 
5124 D*/
5125 
5126 /*F*/
5127 void putBitInBytes(int bitPos, char *buf, int bit);
5128 /*D
5129 Sets the bit bitPos bits from the start of buf to bit.
5130 
5131 . .
5132 bitPos: bit index from the start of buf
5133  buf: array of bits
5134  bit: 0-1, value to set
5135 . .
5136 
5137 D*/
5138 
5139 /*F*/
5140 double time_time(void);
5141 /*D
5142 Return the current time in seconds since the Epoch.
5143 D*/
5144 
5145 
5146 /*F*/
5147 void time_sleep(double seconds);
5148 /*D
5149 Delay execution for a given number of seconds
5150 
5151 . .
5152 seconds: the number of seconds to sleep
5153 . .
5154 D*/
5155 
5156 
5157 /*F*/
5158 void rawDumpWave(void);
5159 /*D
5160 Used to print a readable version of the current waveform to stderr.
5161 
5162 Not intended for general use.
5163 D*/
5164 
5165 
5166 /*F*/
5167 void rawDumpScript(unsigned script_id);
5168 /*D
5169 Used to print a readable version of a script to stderr.
5170 
5171 . .
5172 script_id: >=0, a script_id returned by [*gpioStoreScript*]
5173 . .
5174 
5175 Not intended for general use.
5176 D*/
5177 
5178 
5179 #ifdef __cplusplus
5180 }
5181 #endif
5182 
5183 /*PARAMS
5184 
5185 active :: 0-1000000
5186 
5187 The number of microseconds level changes are reported for once
5188 a noise filter has been triggered (by [*steady*] microseconds of
5189 a stable level).
5190 
5191 arg1::
5192 
5193 An unsigned argument passed to a user customised function. Its
5194 meaning is defined by the customiser.
5195 
5196 arg2::
5197 
5198 An unsigned argument passed to a user customised function. Its
5199 meaning is defined by the customiser.
5200 
5201 argc::
5202 The count of bytes passed to a user customised function.
5203 
5204 *argx::
5205 A pointer to an array of bytes passed to a user customised function.
5206 Its meaning and content is defined by the customiser.
5207 
5208 baud::
5209 The speed of serial communication (I2C, SPI, serial link, waves) in
5210 bits per second.
5211 
5212 bit::
5213 A value of 0 or 1.
5214 
5215 bitPos::
5216 A bit position within a byte or word. The least significant bit is
5217 position 0.
5218 
5219 bits::
5220 A value used to select GPIO. If bit n of bits is set then GPIO n is
5221 selected.
5222 
5223 A convenient way to set bit n is to or in (1<<n).
5224 
5225 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
5226 
5227 *bsc_xfer::
5228 A pointer to a [*bsc_xfer_t*] object used to control a BSC transfer.
5229 
5230 bsc_xfer_t::
5231 
5232 . .
5233 typedef struct
5234 {
5235  uint32_t control; // Write
5236  int rxCnt; // Read only
5237  char rxBuf[BSC_FIFO_SIZE]; // Read only
5238  int txCnt; // Write
5239  char txBuf[BSC_FIFO_SIZE]; // Write
5240 } bsc_xfer_t;
5241 . .
5242 
5243 *buf::
5244 
5245 A buffer to hold data being sent or being received.
5246 
5247 bufSize::
5248 
5249 The size in bytes of a buffer.
5250 
5251 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
5252 
5253 An 8-bit byte value.
5254 
5255 cbNum::
5256 
5257 A number identifying a DMA contol block.
5258 
5259 cfgMicros::
5260 
5261 The GPIO sample rate in microseconds. The default is 5us, or 200 thousand
5262 samples per second.
5263 
5264 cfgMillis:: 100-10000
5265 
5266 The size of the sample buffer in milliseconds. Generally this should be
5267 left at the default of 120ms. If you expect intense bursts of signals it
5268 might be necessary to increase the buffer size.
5269 
5270 cfgPeripheral::
5271 
5272 One of the PWM or PCM peripherals used to pace DMA transfers for timing
5273 purposes.
5274 
5275 cfgSource::
5276 
5277 Deprecated.
5278 
5279 cfgVal::
5280 
5281 A number specifying the value of a configuration item. See [*cfgWhat*].
5282 
5283 cfgWhat::
5284 
5285 A number specifying a configuration item.
5286 
5287 562484977: print enhanced statistics at termination.
5288 984762879: set the initial debug level.
5289 
5290 char::
5291 
5292 A single character, an 8 bit quantity able to store 0-255.
5293 
5294 clkfreq::4689-250M
5295 
5296 The hardware clock frequency.
5297 
5298 . .
5299 PI_HW_CLK_MIN_FREQ 4689
5300 PI_HW_CLK_MAX_FREQ 250000000
5301 . .
5302 
5303 count::
5304 The number of bytes to be transferred in an I2C, SPI, or Serial
5305 command.
5306 
5307 CS::
5308 The GPIO used for the slave select signal when bit banging SPI.
5309 
5310 data_bits::1-32
5311 
5312 The number of data bits to be used when adding serial data to a
5313 waveform.
5314 
5315 . .
5316 PI_MIN_WAVE_DATABITS 1
5317 PI_MAX_WAVE_DATABITS 32
5318 . .
5319 
5320 DMAchannel::0-14
5321 . .
5322 PI_MIN_DMA_CHANNEL 0
5323 PI_MAX_DMA_CHANNEL 14
5324 . .
5325 
5326 double::
5327 
5328 A floating point number.
5329 
5330 dutycycle::0-range
5331 
5332 A number representing the ratio of on time to off time for PWM.
5333 
5334 The number may vary between 0 and range (default 255) where
5335 0 is off and range is fully on.
5336 
5337 edge::0-2
5338 The type of GPIO edge to generate an interrupt. See [*gpioSetISRFunc*]
5339 and [*gpioSetISRFuncEx*].
5340 
5341 . .
5342 RISING_EDGE 0
5343 FALLING_EDGE 1
5344 EITHER_EDGE 2
5345 . .
5346 
5347 event::0-31
5348 An event is a signal used to inform one or more consumers
5349 to start an action.
5350 
5351 eventFunc_t::
5352 . .
5353 typedef void (*eventFunc_t) (int event, uint32_t tick);
5354 . .
5355 
5356 eventFuncEx_t::
5357 . .
5358 typedef void (*eventFuncEx_t)
5359  (int event, uint32_t tick, void *userdata);
5360 . .
5361 
5362 f::
5363 
5364 A function.
5365 
5366 *file::
5367 A full file path. To be accessible the path must match an entry in
5368 /opt/pigpio/access.
5369 
5370 *fpat::
5371 A file path which may contain wildcards. To be accessible the path
5372 must match an entry in /opt/pigpio/access.
5373 
5374 frequency::>=0
5375 
5376 The number of times a GPIO is swiched on and off per second. This
5377 can be set per GPIO and may be as little as 5Hz or as much as
5378 40KHz. The GPIO will be on for a proportion of the time as defined
5379 by its dutycycle.
5380 
5381 gpio::
5382 
5383 A Broadcom numbered GPIO, in the range 0-53.
5384 
5385 There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through
5386 GPIO53.
5387 
5388 They are split into two banks. Bank 1 consists of GPIO0 through
5389 GPIO31. Bank 2 consists of GPIO32 through GPIO53.
5390 
5391 All the GPIO which are safe for the user to read and write are in
5392 bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards
5393 have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26.
5394 
5395 See [*gpioHardwareRevision*].
5396 
5397 The user GPIO are marked with an X in the following table.
5398 
5399 . .
5400  0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
5401 Type 1 X X - - X - - X X X X X - - X X
5402 Type 2 - - X X X - - X X X X X - - X X
5403 Type 3 X X X X X X X X X X X X X X
5404 
5405  16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
5406 Type 1 - X X - - X X X X X - - - - - -
5407 Type 2 - X X - - - X X X X - X X X X X
5408 Type 3 X X X X X X X X X X X X - - - -
5409 . .
5410 
5411 gpioAlertFunc_t::
5412 . .
5413 typedef void (*gpioAlertFunc_t) (int gpio, int level, uint32_t tick);
5414 . .
5415 
5416 gpioAlertFuncEx_t::
5417 . .
5418 typedef void (*eventFuncEx_t)
5419  (int event, int level, uint32_t tick, void *userdata);
5420 . .
5421 
5422 gpioCfg*::
5423 
5424 These functions are only effective if called before [*gpioInitialise*].
5425 
5426 [*gpioCfgBufferSize*]
5427 [*gpioCfgClock*]
5428 [*gpioCfgDMAchannel*]
5429 [*gpioCfgDMAchannels*]
5430 [*gpioCfgPermissions*]
5431 [*gpioCfgInterfaces*]
5432 [*gpioCfgSocketPort*]
5433 [*gpioCfgMemAlloc*]
5434 
5435 gpioGetSamplesFunc_t::
5436 . .
5437 typedef void (*gpioGetSamplesFunc_t)
5438  (const gpioSample_t *samples, int numSamples);
5439 . .
5440 
5441 gpioGetSamplesFuncEx_t::
5442 . .
5443 typedef void (*gpioGetSamplesFuncEx_t)
5444  (const gpioSample_t *samples, int numSamples, void *userdata);
5445 . .
5446 
5447 gpioISRFunc_t::
5448 . .
5449 typedef void (*gpioISRFunc_t)
5450  (int gpio, int level, uint32_t tick);
5451 . .
5452 
5453 gpioISRFuncEx_t::
5454 . .
5455 typedef void (*gpioISRFuncEx_t)
5456  (int gpio, int level, uint32_t tick, void *userdata);
5457 . .
5458 
5459 gpioPulse_t::
5460 . .
5461 typedef struct
5462 {
5463  uint32_t gpioOn;
5464  uint32_t gpioOff;
5465  uint32_t usDelay;
5466 } gpioPulse_t;
5467 . .
5468 
5469 gpioSample_t::
5470 . .
5471 typedef struct
5472 {
5473  uint32_t tick;
5474  uint32_t level;
5475 } gpioSample_t;
5476 . .
5477 
5478 gpioSignalFunc_t::
5479 . .
5480 typedef void (*gpioSignalFunc_t) (int signum);
5481 . .
5482 
5483 gpioSignalFuncEx_t::
5484 . .
5485 typedef void (*gpioSignalFuncEx_t) (int signum, void *userdata);
5486 . .
5487 
5488 gpioThreadFunc_t::
5489 . .
5490 typedef void *(gpioThreadFunc_t) (void *);
5491 . .
5492 
5493 gpioTimerFunc_t::
5494 . .
5495 typedef void (*gpioTimerFunc_t) (void);
5496 . .
5497 
5498 gpioTimerFuncEx_t::
5499 . .
5500 typedef void (*gpioTimerFuncEx_t) (void *userdata);
5501 . .
5502 
5503 gpioWaveAdd*::
5504 
5505 One of
5506 
5507 [*gpioWaveAddNew*]
5508 [*gpioWaveAddGeneric*]
5509 [*gpioWaveAddSerial*]
5510 
5511 handle::>=0
5512 
5513 A number referencing an object opened by one of
5514 
5515 [*fileOpen*]
5516 [*gpioNotifyOpen*]
5517 [*i2cOpen*]
5518 [*serOpen*]
5519 [*spiOpen*]
5520 
5521 i2cAddr:: 0-0x7F
5522 The address of a device on the I2C bus.
5523 
5524 i2cBus::>=0
5525 
5526 An I2C bus number.
5527 
5528 i2cFlags::0
5529 
5530 Flags which modify an I2C open command. None are currently defined.
5531 
5532 i2cReg:: 0-255
5533 
5534 A register of an I2C device.
5535 
5536 ifFlags::0-3
5537 . .
5538 PI_DISABLE_FIFO_IF 1
5539 PI_DISABLE_SOCK_IF 2
5540 . .
5541 
5542 *inBuf::
5543 A buffer used to pass data to a function.
5544 
5545 inLen::
5546 The number of bytes of data in a buffer.
5547 
5548 int::
5549 A whole number, negative or positive.
5550 
5551 int32_t::
5552 A 32-bit signed value.
5553 
5554 invert::
5555 A flag used to set normal or inverted bit bang serial data level logic.
5556 
5557 level::
5558 The level of a GPIO. Low or High.
5559 
5560 . .
5561 PI_OFF 0
5562 PI_ON 1
5563 
5564 PI_CLEAR 0
5565 PI_SET 1
5566 
5567 PI_LOW 0
5568 PI_HIGH 1
5569 . .
5570 
5571 There is one exception. If a watchdog expires on a GPIO the level will be
5572 reported as PI_TIMEOUT. See [*gpioSetWatchdog*].
5573 
5574 . .
5575 PI_TIMEOUT 2
5576 . .
5577 
5578 
5579 lVal::0-4294967295 (Hex 0x0-0xFFFFFFFF, Octal 0-37777777777)
5580 
5581 A 32-bit word value.
5582 
5583 memAllocMode:: 0-2
5584 
5585 The DMA memory allocation mode.
5586 
5587 . .
5588 PI_MEM_ALLOC_AUTO 0
5589 PI_MEM_ALLOC_PAGEMAP 1
5590 PI_MEM_ALLOC_MAILBOX 2
5591 . .
5592 
5593 *micros::
5594 
5595 A value representing microseconds.
5596 
5597 micros::
5598 
5599 A value representing microseconds.
5600 
5601 millis::
5602 
5603 A value representing milliseconds.
5604 
5605 MISO::
5606 The GPIO used for the MISO signal when bit banging SPI.
5607 
5608 mode::
5609 
5610 1. The operational mode of a GPIO, normally INPUT or OUTPUT.
5611 
5612 . .
5613 PI_INPUT 0
5614 PI_OUTPUT 1
5615 PI_ALT0 4
5616 PI_ALT1 5
5617 PI_ALT2 6
5618 PI_ALT3 7
5619 PI_ALT4 3
5620 PI_ALT5 2
5621 . .
5622 
5623 2. A file open mode.
5624 
5625 . .
5626 PI_FILE_READ 1
5627 PI_FILE_WRITE 2
5628 PI_FILE_RW 3
5629 . .
5630 
5631 The following values can be or'd into the mode.
5632 
5633 . .
5634 PI_FILE_APPEND 4
5635 PI_FILE_CREATE 8
5636 PI_FILE_TRUNC 16
5637 . .
5638 
5639 MOSI::
5640 The GPIO used for the MOSI signal when bit banging SPI.
5641 
5642 numBits::
5643 
5644 The number of bits stored in a buffer.
5645 
5646 numBytes::
5647 The number of bytes used to store characters in a string. Depending
5648 on the number of bits per character there may be 1, 2, or 4 bytes
5649 per character.
5650 
5651 numPar:: 0-10
5652 The number of parameters passed to a script.
5653 
5654 numPulses::
5655 The number of pulses to be added to a waveform.
5656 
5657 numSegs::
5658 The number of segments in a combined I2C transaction.
5659 
5660 numSockAddr::
5661 The number of network addresses allowed to use the socket interface.
5662 
5663 0 means all addresses allowed.
5664 
5665 offset::
5666 The associated data starts this number of microseconds from the start of
5667 the waveform.
5668 
5669 *outBuf::
5670 A buffer used to return data from a function.
5671 
5672 outLen::
5673 The size in bytes of an output buffer.
5674 
5675 pad:: 0-2
5676 A set of GPIO which share common drivers.
5677 
5678 Pad @ GPIO
5679 0 @ 0-27
5680 1 @ 28-45
5681 2 @ 46-53
5682 
5683 padStrength:: 1-16
5684 The mA which may be drawn from each GPIO whilst still guaranteeing the
5685 high and low levels.
5686 
5687 *param::
5688 An array of script parameters.
5689 
5690 pi_i2c_msg_t::
5691 . .
5692 typedef struct
5693 {
5694  uint16_t addr; // slave address
5695  uint16_t flags;
5696  uint16_t len; // msg length
5697  uint8_t *buf; // pointer to msg data
5698 } pi_i2c_msg_t;
5699 . .
5700 
5701 port:: 1024-32000
5702 The port used to bind to the pigpio socket. Defaults to 8888.
5703 
5704 pos::
5705 The position of an item.
5706 
5707 primaryChannel:: 0-14
5708 The DMA channel used to time the sampling of GPIO and to time servo and
5709 PWM pulses.
5710 
5711 *pth::
5712 
5713 A thread identifier, returned by [*gpioStartThread*].
5714 
5715 pthread_t::
5716 
5717 A thread identifier.
5718 
5719 pud::0-2
5720 
5721 The setting of the pull up/down resistor for a GPIO, which may be off,
5722 pull-up, or pull-down.
5723 
5724 . .
5725 PI_PUD_OFF 0
5726 PI_PUD_DOWN 1
5727 PI_PUD_UP 2
5728 . .
5729 
5730 pulseLen::
5731 
5732 1-100, the length of a trigger pulse in microseconds.
5733 
5734 *pulses::
5735 
5736 An array of pulses to be added to a waveform.
5737 
5738 pulsewidth::0, 500-2500
5739 . .
5740 PI_SERVO_OFF 0
5741 PI_MIN_SERVO_PULSEWIDTH 500
5742 PI_MAX_SERVO_PULSEWIDTH 2500
5743 . .
5744 
5745 PWMduty::0-1000000 (1M)
5746 The hardware PWM dutycycle.
5747 
5748 . .
5749 PI_HW_PWM_RANGE 1000000
5750 . .
5751 
5752 PWMfreq::5-250K
5753 The hardware PWM frequency.
5754 
5755 . .
5756 PI_HW_PWM_MIN_FREQ 1
5757 PI_HW_PWM_MAX_FREQ 125000000
5758 . .
5759 
5760 range::25-40000
5761 . .
5762 PI_MIN_DUTYCYCLE_RANGE 25
5763 PI_MAX_DUTYCYCLE_RANGE 40000
5764 . .
5765 
5766 rawCbs_t::
5767 . .
5768 typedef struct // linux/arch/arm/mach-bcm2708/include/mach/dma.h
5769 {
5770  unsigned long info;
5771  unsigned long src;
5772  unsigned long dst;
5773  unsigned long length;
5774  unsigned long stride;
5775  unsigned long next;
5776  unsigned long pad[2];
5777 } rawCbs_t;
5778 . .
5779 
5780 rawSPI_t::
5781 . .
5782 typedef struct
5783 {
5784  int clk; // GPIO for clock
5785  int mosi; // GPIO for MOSI
5786  int miso; // GPIO for MISO
5787  int ss_pol; // slave select off state
5788  int ss_us; // delay after slave select
5789  int clk_pol; // clock off state
5790  int clk_pha; // clock phase
5791  int clk_us; // clock micros
5792 } rawSPI_t;
5793 . .
5794 
5795 rawWave_t::
5796 . .
5797 typedef struct
5798 {
5799  uint32_t gpioOn;
5800  uint32_t gpioOff;
5801  uint32_t usDelay;
5802  uint32_t flags;
5803 } rawWave_t;
5804 . .
5805 
5806 rawWaveInfo_t::
5807 . .
5808 typedef struct
5809 {
5810  uint16_t botCB; // first CB used by wave
5811  uint16_t topCB; // last CB used by wave
5812  uint16_t botOOL; // last OOL used by wave
5813  uint16_t topOOL; // first OOL used by wave
5814  uint16_t deleted;
5815  uint16_t numCB;
5816  uint16_t numBOOL;
5817  uint16_t numTOOL;
5818 } rawWaveInfo_t;
5819 . .
5820 
5821 *retBuf::
5822 
5823 A buffer to hold a number of bytes returned to a used customised function,
5824 
5825 retMax::
5826 
5827 The maximum number of bytes a user customised function should return.
5828 
5829 *rxBuf::
5830 
5831 A pointer to a buffer to receive data.
5832 
5833 SCL::
5834 The user GPIO to use for the clock when bit banging I2C.
5835 
5836 SCLK::
5837 The GPIO used for the SCLK signal when bit banging SPI.
5838 
5839 *script::
5840 A pointer to the text of a script.
5841 
5842 script_id::
5843 An id of a stored script as returned by [*gpioStoreScript*].
5844 
5845 *scriptName::
5846 The name of a [*shell*] script to be executed. The script must be present in
5847 /opt/pigpio/cgi and must have execute permission.
5848 
5849 *scriptString::
5850 The string to be passed to a [*shell*] script to be executed.
5851 
5852 SDA::
5853 The user GPIO to use for data when bit banging I2C.
5854 
5855 secondaryChannel:: 0-6
5856 
5857 The DMA channel used to time output waveforms.
5858 
5859 *seconds::
5860 
5861 A pointer to a uint32_t to store the second component of
5862 a returned time.
5863 
5864 seconds::
5865 The number of seconds.
5866 
5867 seekFrom::
5868 
5869 . .
5870 PI_FROM_START 0
5871 PI_FROM_CURRENT 1
5872 PI_FROM_END 2
5873 . .
5874 
5875 seekOffset::
5876 The number of bytes to move forward (positive) or backwards (negative)
5877 from the seek position (start, current, or end of file).
5878 
5879 *segs::
5880 An array of segments which make up a combined I2C transaction.
5881 
5882 serFlags::
5883 Flags which modify a serial open command. None are currently defined.
5884 
5885 *sertty::
5886 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
5887 
5888 setting::
5889 A value used to set a flag, 0 for false, non-zero for true.
5890 
5891 signum::0-63
5892 . .
5893 PI_MIN_SIGNUM 0
5894 PI_MAX_SIGNUM 63
5895 . .
5896 
5897 size_t::
5898 
5899 A standard type used to indicate the size of an object in bytes.
5900 
5901 *sockAddr::
5902 An array of network addresses allowed to use the socket interface encoded
5903 as 32 bit numbers.
5904 
5905 E.g. address 192.168.1.66 would be encoded as 0x4201a8c0.
5906 
5907 *spi::
5908 A pointer to a [*rawSPI_t*] structure.
5909 
5910 spiBitFirst::
5911 GPIO reads are made from spiBitFirst to spiBitLast.
5912 
5913 spiBitLast::
5914 
5915 GPIO reads are made from spiBitFirst to spiBitLast.
5916 
5917 spiBits::
5918 The number of bits to transfer in a raw SPI transaction.
5919 
5920 spiChan::
5921 A SPI channel, 0-2.
5922 
5923 spiFlags::
5924 See [*spiOpen*] and [*bbSPIOpen*].
5925 
5926 spiSS::
5927 The SPI slave select GPIO in a raw SPI transaction.
5928 
5929 spiTxBits::
5930 The number of bits to transfer dring a raw SPI transaction
5931 
5932 steady :: 0-300000
5933 
5934 The number of microseconds level changes must be stable for
5935 before reporting the level changed ([*gpioGlitchFilter*]) or triggering
5936 the active part of a noise filter ([*gpioNoiseFilter*]).
5937 
5938 stop_bits::2-8
5939 The number of (half) stop bits to be used when adding serial data
5940 to a waveform.
5941 
5942 . .
5943 PI_MIN_WAVE_HALFSTOPBITS 2
5944 PI_MAX_WAVE_HALFSTOPBITS 8
5945 . .
5946 
5947 *str::
5948 An array of characters.
5949 
5950 timeout::
5951 A GPIO level change timeout in milliseconds.
5952 
5953 [*gpioSetWatchdog*]
5954 . .
5955 PI_MIN_WDOG_TIMEOUT 0
5956 PI_MAX_WDOG_TIMEOUT 60000
5957 . .
5958 
5959 [*gpioSetISRFunc*] and [*gpioSetISRFuncEx*]
5960 . .
5961 <=0 cancel timeout
5962 >0 timeout after specified milliseconds
5963 . .
5964 
5965 timer::
5966 . .
5967 PI_MIN_TIMER 0
5968 PI_MAX_TIMER 9
5969 . .
5970 
5971 timetype::
5972 . .
5973 PI_TIME_RELATIVE 0
5974 PI_TIME_ABSOLUTE 1
5975 . .
5976 
5977 *txBuf::
5978 
5979 An array of bytes to transmit.
5980 
5981 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
5982 
5983 A 32-bit unsigned value.
5984 
5985 uint64_t::0-(2^64)-1
5986 
5987 A 64-bit unsigned value.
5988 
5989 unsigned::
5990 
5991 A whole number >= 0.
5992 
5993 updateMask::
5994 
5995 A 64 bit mask indicating which GPIO may be written to by the user.
5996 
5997 If GPIO#n may be written then bit (1<<n) is set.
5998 
5999 user_gpio::
6000 
6001 0-31, a Broadcom numbered GPIO.
6002 
6003 See [*gpio*].
6004 
6005 *userdata::
6006 A pointer to arbitrary user data. This may be used to identify the instance.
6007 
6008 You must ensure that the pointer is in scope at the time it is processed. If
6009 it is a pointer to a global this is automatic. Do not pass the address of a
6010 local variable. If you want to pass a transient object then use the
6011 following technique.
6012 
6013 In the calling function:
6014 
6015 . .
6016 user_type *userdata;
6017 user_type my_userdata;
6018 
6019 userdata = malloc(sizeof(user_type));
6020 *userdata = my_userdata;
6021 . .
6022 
6023 In the receiving function:
6024 
6025 . .
6026 user_type my_userdata = *(user_type*)userdata;
6027 
6028 free(userdata);
6029 . .
6030 
6031 void::
6032 
6033 Denoting no parameter is required
6034 
6035 wave_id::
6036 
6037 A number identifying a waveform created by [*gpioWaveCreate*].
6038 
6039 wave_mode::
6040 
6041 The mode determines if the waveform is sent once or cycles
6042 repeatedly. The SYNC variants wait for the current waveform
6043 to reach the end of a cycle or finish before starting the new
6044 waveform.
6045 
6046 . .
6047 PI_WAVE_MODE_ONE_SHOT 0
6048 PI_WAVE_MODE_REPEAT 1
6049 PI_WAVE_MODE_ONE_SHOT_SYNC 2
6050 PI_WAVE_MODE_REPEAT_SYNC 3
6051 . .
6052 
6053 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
6054 
6055 A 16-bit word value.
6056 
6057 PARAMS*/
6058 
6059 /*DEF_S Socket Command Codes*/
6060 
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
6115 
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
6133 
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
6139 
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
6147 
6148 #define PI_CMD_GDC 83
6149 #define PI_CMD_GPW 84
6150 
6151 #define PI_CMD_HC 85
6152 #define PI_CMD_HP 86
6153 
6154 #define PI_CMD_CF1 87
6155 #define PI_CMD_CF2 88
6156 
6157 #define PI_CMD_BI2CC 89
6158 #define PI_CMD_BI2CO 90
6159 #define PI_CMD_BI2CZ 91
6160 
6161 #define PI_CMD_I2CZ 92
6162 
6163 #define PI_CMD_WVCHA 93
6164 
6165 #define PI_CMD_SLRI 94
6166 
6167 #define PI_CMD_CGI 95
6168 #define PI_CMD_CSI 96
6169 
6170 #define PI_CMD_FG 97
6171 #define PI_CMD_FN 98
6172 
6173 #define PI_CMD_NOIB 99
6174 
6175 #define PI_CMD_WVTXM 100
6176 #define PI_CMD_WVTAT 101
6177 
6178 #define PI_CMD_PADS 102
6179 #define PI_CMD_PADG 103
6180 
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
6187 
6188 #define PI_CMD_SHELL 110
6189 
6190 #define PI_CMD_BSPIC 111
6191 #define PI_CMD_BSPIO 112
6192 #define PI_CMD_BSPIX 113
6193 
6194 #define PI_CMD_BSCX 114
6195 
6196 #define PI_CMD_EVM 115
6197 #define PI_CMD_EVT 116
6198 
6199 #define PI_CMD_PROCU 117
6200 
6201 /*DEF_E*/
6202 
6203 /*
6204 PI CMD_NOIB only works on the socket interface.
6205 It returns a spare notification handle. Notifications for
6206 that handle will be sent to the socket (rather than a
6207 /dev/pigpiox pipe).
6208 
6209 The socket should be dedicated to receiving notifications
6210 after this command is issued.
6211 */
6212 
6213 /* pseudo commands */
6214 
6215 #define PI_CMD_SCRIPT 800
6216 
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
6260 
6261 /*DEF_S Error Codes*/
6262 
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
6410 
6411 #define PI_PIGIF_ERR_0 -2000
6412 #define PI_PIGIF_ERR_99 -2099
6413 
6414 #define PI_CUSTOM_ERR_0 -3000
6415 #define PI_CUSTOM_ERR_999 -3999
6416 
6417 /*DEF_E*/
6418 
6419 /*DEF_S Defaults*/
6420 
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
6441 
6442 #define PI_DEFAULT_CFG_INTERNALS 0
6443 
6444 /*DEF_E*/
6445 
6446 #endif
6447 
void(* gpioISRFunc_t)(int gpio, int level, uint32_t tick)
Definition: pigpio.h:527
uint32_t tick
Definition: pigpio.h:418
int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpio.c:12219
int gpioWaveTxBusy(void)
Definition: pigpio.c:10056
uint8_t * buf
Definition: pigpio.h:494
uint32_t rawWaveGetOut(int pos)
Definition: pigpio.c:8293
uint32_t stride
Definition: pigpio.h:484
unsigned gpioVersion(void)
Definition: pigpio.c:13227
uint32_t gpioTick(void)
Definition: pigpio.c:13217
static uint64_t updateMask
Definition: pigpiod.c:63
int bscXfer(bsc_xfer_t *bsc_xfer)
Definition: pigpio.c:10588
int gpioWaveGetMaxMicros(void)
Definition: pigpio.c:10132
int serOpen(char *sertty, unsigned baud, unsigned serFlags)
Definition: pigpio.c:4800
int clk_pha
Definition: pigpio.h:475
uint32_t data
Definition: pigpio.h:405
int rawWaveAddSPI(rawSPI_t *spi, unsigned offset, unsigned spiSS, char *buf, unsigned spiTxBits, unsigned spiBitFirst, unsigned spiBitLast, unsigned spiBits)
Definition: pigpio.c:9244
static unsigned ifFlags
Definition: pigpiod.c:57
uint32_t gpioDelay(uint32_t micros)
Definition: pigpio.c:13196
uint16_t size
Definition: pigpio.h:398
void(* gpioISRFuncEx_t)(int gpio, int level, uint32_t tick, void *userdata)
Definition: pigpio.h:531
int ss_us
Definition: pigpio.h:473
int gpioWrite(unsigned gpio, unsigned level)
Definition: pigpio.c:8707
uint32_t src
Definition: pigpio.h:481
unsigned gpioHardwareRevision(void)
Definition: pigpio.c:13259
uint16_t numTOOL
Definition: pigpio.h:464
int i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf)
Definition: pigpio.c:3638
int bbI2CClose(unsigned SDA)
Definition: pigpio.c:10376
int bsc_xfer(int pi, bsc_xfer_t *bscxfer)
Definition: pigpiod_if2.c:2021
int gpioCfgSocketPort(unsigned port)
Definition: pigpio.c:13440
int gpioGetPWMrealRange(unsigned user_gpio)
Definition: pigpio.c:8869
uint16_t flags
Definition: pigpio.h:417
int txCnt
Definition: pigpio.h:506
int i2cWriteQuick(unsigned handle, unsigned bit)
Definition: pigpio.c:3336
uint16_t flags
Definition: pigpio.h:492
uint32_t gpioOff
Definition: pigpio.h:435
int i2cReadWordData(unsigned handle, unsigned i2cReg)
Definition: pigpio.c:3514
int rxCnt
Definition: pigpio.h:504
int gpioRead(unsigned gpio)
Definition: pigpio.c:8691
int fileClose(unsigned handle)
Definition: pigpio.c:12948
int serReadByte(unsigned handle)
Definition: pigpio.c:4934
int gpioCfgMemAlloc(unsigned memAllocMode)
Definition: pigpio.c:13457
void rawWaveSetOOL(int pos, uint32_t lVal)
Definition: pigpio.c:8279
void putBitInBytes(int bitPos, char *buf, int bit)
Definition: pigpio.c:8251
int serClose(unsigned handle)
Definition: pigpio.c:4889
int gpioSleep(unsigned timetype, int seconds, int micros)
Definition: pigpio.c:13155
int gpioGetPWMdutycycle(unsigned user_gpio)
Definition: pigpio.c:8776
int gpioWaveGetMicros(void)
Definition: pigpio.c:10110
int eventTrigger(unsigned event)
Definition: pigpio.c:11256
int i2cReadDevice(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:3913
int gpioSerialReadClose(unsigned user_gpio)
Definition: pigpio.c:11145
int gpioStopScript(unsigned script_id)
Definition: pigpio.c:12325
void time_sleep(double seconds)
Definition: pigpio.c:8374
int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses)
Definition: pigpio.c:9084
uint32_t tick
Definition: pigpio.h:410
uint32_t control
Definition: pigpio.h:503
void(* gpioTimerFuncEx_t)(void *userdata)
Definition: pigpio.h:538
unsigned rawWaveCB(void)
Definition: pigpio.c:5232
uint32_t length
Definition: pigpio.h:483
int gpioWaveCreate(void)
Definition: pigpio.c:9388
void(* eventFuncEx_t)(int event, uint32_t tick, void *userdata)
Definition: pigpio.h:523
int spiWrite(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:4755
uint16_t botOOL
Definition: pigpio.h:457
int gpioWrite_Bits_32_53_Set(uint32_t bits)
Definition: pigpio.c:12509
int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata)
Definition: pigpio.c:11218
int gpioWaveGetPulses(void)
Definition: pigpio.c:10143
handle
Definition: PCF8591.py:19
int gpioSerialReadInvert(unsigned user_gpio, unsigned invert)
Definition: pigpio.c:11076
void(* gpioGetSamplesFunc_t)(const gpioSample_t *samples, int numSamples)
Definition: pigpio.h:545
int gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpio.c:12268
int i2cClose(unsigned handle)
Definition: pigpio.c:4017
int gpioCustom2(unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)
int gpioCfgInterfaces(unsigned ifFlags)
Definition: pigpio.c:13424
int gpioGetServoPulsewidth(unsigned user_gpio)
Definition: pigpio.c:9016
int gpioCfgBufferSize(unsigned cfgMillis)
Definition: pigpio.c:13325
int gpioWaveClear(void)
Definition: pigpio.c:9034
#define BSC_FIFO_SIZE
Definition: pigpio.h:499
int gpioNotifyOpen(void)
Definition: pigpio.c:11635
int fileWrite(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:12968
int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level)
Definition: pigpio.c:11820
void samples(const gpioSample_t *samples, int numSamples)
Definition: freq_count_2.c:147
void rawDumpWave(void)
Definition: pigpio.c:8394
int gpioSetAlertFuncEx(unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata)
Definition: pigpio.c:11320
int gpioWaveGetMaxPulses(void)
Definition: pigpio.c:10165
int gpioSerialReadOpen(unsigned user_gpio, unsigned baud, unsigned data_bits)
Definition: pigpio.c:11021
uint32_t next
Definition: pigpio.h:485
uint16_t numBOOL
Definition: pigpio.h:463
int i2cWriteI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
Definition: pigpio.c:3837
int i2cReadByte(unsigned handle)
Definition: pigpio.c:3368
int gpioWrite_Bits_0_31_Clear(uint32_t bits)
Definition: pigpio.c:12467
int gpioHardwareClock(unsigned gpio, unsigned clkfreq)
Definition: pigpio.c:12522
uint16_t topCB
Definition: pigpio.h:456
int gpioWaveGetHighMicros(void)
Definition: pigpio.c:10121
pthread_t * gpioStartThread(gpioThreadFunc_t f, void *userdata)
Definition: pigpio.c:12098
int gpioNotifyClose(unsigned handle)
Definition: pigpio.c:11795
int i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal)
Definition: pigpio.c:3596
int ss_pol
Definition: pigpio.h:472
int gpioSetSignalFuncEx(unsigned signum, gpioSignalFuncEx_t f, void *userdata)
Definition: pigpio.c:12421
int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f)
Definition: pigpio.c:12401
void rawDumpScript(unsigned script_id)
Definition: pigpio.c:8418
void * ptr
Definition: pigpio.h:404
uint32_t level
Definition: pigpio.h:411
void(* gpioAlertFunc_t)(int gpio, int level, uint32_t tick)
Definition: pigpio.h:511
int clk
Definition: pigpio.h:469
int serWriteByte(unsigned handle, unsigned bVal)
Definition: pigpio.c:4909
int bbSPIClose(unsigned CS)
Definition: pigpio.c:10921
void(* gpioSignalFunc_t)(int signum)
Definition: pigpio.h:540
int i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal)
Definition: pigpio.c:3470
void(* eventFunc_t)(int event, uint32_t tick)
Definition: pigpio.h:520
int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom)
Definition: pigpio.c:13035
int gpioSetPullUpDown(unsigned gpio, unsigned pud)
Definition: pigpio.c:8661
int gpioInitialise(void)
Definition: pigpio.c:8459
int serRead(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:5000
int gpioWaveTxAt(void)
Definition: pigpio.c:10070
int spiClose(unsigned handle)
Definition: pigpio.c:4714
uint32_t dst
Definition: pigpio.h:482
void i2cSwitchCombined(int setting)
Definition: pigpio.c:4037
int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs)
Definition: pigpio.c:4060
rawWaveInfo_t rawWaveInfo(int wave_id)
Definition: pigpio.c:8350
int gpioGetPWMfrequency(unsigned user_gpio)
Definition: pigpio.c:8949
int gpioCustom1(unsigned arg1, unsigned arg2, char *argx, unsigned argc)
void(* gpioGetSamplesFuncEx_t)(const gpioSample_t *samples, int numSamples, void *userdata)
Definition: pigpio.h:548
int gpioNotifyPause(unsigned handle)
Definition: pigpio.c:11771
uint32_t info
Definition: pigpio.h:480
uint16_t deleted
Definition: pigpio.h:461
int gpioTime(unsigned timetype, int *seconds, int *micros)
Definition: pigpio.c:13121
size_t size
Definition: pigpio.h:403
int gpioNotifyOpenWithSize(int bufSize)
Definition: pigpio.c:11572
int gpioWaveGetHighPulses(void)
Definition: pigpio.c:10154
int gpioCfgInternals(unsigned cfgWhat, unsigned cfgVal)
Definition: pigpio.c:13512
int bbSPIXfer(unsigned CS, char *inBuf, char *outBuf, unsigned count)
Definition: pigpio.c:10967
void *( gpioThreadFunc_t)(void *)
Definition: pigpio.h:552
int clk_pol
Definition: pigpio.h:474
uint32_t gpioOn
Definition: pigpio.h:434
int gpioCfgDMAchannel(unsigned DMAchannel)
Definition: pigpio.c:13366
double time_time(void)
Definition: pigpio.c:8360
uint32_t rawWaveGetIn(int pos)
Definition: pigpio.c:8322
int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f)
Definition: pigpio.c:12057
int gpioSetPad(unsigned pad, unsigned padStrength)
Definition: pigpio.c:12717
int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency)
Definition: pigpio.c:8897
int miso
Definition: pigpio.h:471
uint32_t gpioRead_Bits_0_31(void)
Definition: pigpio.c:12443
int clk_us
Definition: pigpio.h:476
int fileOpen(char *file, unsigned mode)
Definition: pigpio.c:12850
uint16_t addr
Definition: pigpio.h:491
int gpioCfgSetInternals(uint32_t cfgVal)
Definition: pigpio.c:13504
int spiRead(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:4734
int gpioSetGetSamplesFuncEx(gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata)
Definition: pigpio.c:11963
int gpioSetISRFuncEx(unsigned gpio, unsigned edge, int timeout, gpioISRFuncEx_t f, void *userdata)
Definition: pigpio.c:11521
int gpioWaveAddSerial(unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)
Definition: pigpio.c:9111
int gpioSetTimerFuncEx(unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata)
Definition: pigpio.c:12077
int gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty)
Definition: pigpio.c:12603
int gpioCfgNetAddr(int numSockAddr, uint32_t *sockAddr)
Definition: pigpio.c:13474
void rawWaveSetIn(int pos, uint32_t lVal)
Definition: pigpio.c:8337
uint32_t rawWaveGetOOL(int pos)
Definition: pigpio.c:8264
void(* gpioTimerFunc_t)(void)
Definition: pigpio.h:536
int gpioWaveGetHighCbs(void)
Definition: pigpio.c:10187
void(* gpioAlertFuncEx_t)(int gpio, int level, uint32_t tick, void *userdata)
Definition: pigpio.h:515
int gpioGetMode(unsigned gpio)
Definition: pigpio.c:8641
uint32_t gpioOn
Definition: pigpio.h:424
int gpioWaveGetMaxCbs(void)
Definition: pigpio.c:10198
int gpioGlitchFilter(unsigned user_gpio, unsigned steady)
Definition: pigpio.c:11904
int gpioWaveChain(char *buf, unsigned bufSize)
Definition: pigpio.c:9764
int i2cReadI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
Definition: pigpio.c:3782
static unsigned memAllocMode
Definition: pigpiod.c:62
int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses)
Definition: pigpio.c:3204
int gpioSetISRFunc(unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f)
Definition: pigpio.c:11498
int gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active)
Definition: pigpio.c:11874
int gpioCfgDMAchannels(unsigned primaryChannel, unsigned secondaryChannel)
Definition: pigpio.c:13383
int bbI2CZip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpio.c:10410
uint16_t func
Definition: pigpio.h:397
int gpioGetPWMrange(unsigned user_gpio)
Definition: pigpio.c:8846
int fileRead(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:13000
int gpioWaveGetCbs(void)
Definition: pigpio.c:10176
uint32_t usDelay
Definition: pigpio.h:436
int gpioCfgPermissions(uint64_t updateMask)
Definition: pigpio.c:13408
int gpioDeleteScript(unsigned script_id)
Definition: pigpio.c:12354
int gpioServo(unsigned user_gpio, unsigned pulsewidth)
Definition: pigpio.c:8978
rawCbs_t * rawWaveCBAdr(int cbNum)
Definition: pigpio.c:2839
int getBitInBytes(int bitPos, char *buf, int numBits)
Definition: pigpio.c:8235
int bbSPIOpen(unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spiFlags)
Definition: pigpio.c:10806
int mosi
Definition: pigpio.h:470
int i2cBlockProcessCall(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
Definition: pigpio.c:3731
void gpioStopThread(pthread_t *pth)
Definition: pigpio.c:12134
uint32_t gpioOff
Definition: pigpio.h:425
int i2cZip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpio.c:4090
uint32_t flags
Definition: pigpio.h:437
int i2cWriteDevice(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:3884
int i2cReadByteData(unsigned handle, unsigned i2cReg)
Definition: pigpio.c:3436
void gpioTerminate(void)
Definition: pigpio.c:8495
int gpioWaveTxStop(void)
Definition: pigpio.c:10094
uint16_t botCB
Definition: pigpio.h:455
uint32_t usDelay
Definition: pigpio.h:426
int i2cWriteByte(unsigned handle, unsigned bVal)
Definition: pigpio.c:3399
int serWrite(unsigned handle, char *buf, unsigned count)
Definition: pigpio.c:4964
int gpioWaveAddNew(void)
Definition: pigpio.c:9063
int serDataAvailable(unsigned handle)
Definition: pigpio.c:5033
int shell(char *scriptName, char *scriptString)
Definition: pigpio.c:12760
int i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal)
Definition: pigpio.c:3552
int gpioSetMode(unsigned gpio, unsigned mode)
Definition: pigpio.c:8607
uint32_t gpioCfgGetInternals(void)
Definition: pigpio.c:13499
uint16_t len
Definition: pigpio.h:493
uint32_t gpioRead_Bits_32_53(void)
Definition: pigpio.c:12455
int gpioNotifyBegin(unsigned handle, uint32_t bits)
Definition: pigpio.c:11747
int gpioWaveDelete(unsigned wave_id)
Definition: pigpio.c:9484
int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f)
Definition: pigpio.c:11303
int fileList(char *fpat, char *buf, unsigned count)
Definition: pigpio.c:13079
int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits)
Definition: pigpio.c:11942
int gpioSerialRead(unsigned user_gpio, void *buf, size_t bufSize)
Definition: pigpio.c:11100
int gpioScriptStatus(unsigned script_id, uint32_t *param)
Definition: pigpio.c:12300
void(* gpioSignalFuncEx_t)(int signum, void *userdata)
Definition: pigpio.h:542
uint16_t numCB
Definition: pigpio.h:462
uint16_t seqno
Definition: pigpio.h:416
uint32_t level
Definition: pigpio.h:419
int gpioSetWatchdog(unsigned user_gpio, unsigned timeout)
Definition: pigpio.c:11850
int spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags)
Definition: pigpio.c:4654
int gpioCfgClock(unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource)
Definition: pigpio.c:13342
int i2cWriteBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)
Definition: pigpio.c:3684
int eventMonitor(unsigned handle, uint32_t bits)
Definition: pigpio.c:11236
void rawWaveSetOut(int pos, uint32_t lVal)
Definition: pigpio.c:8308
int gpioGetPad(unsigned pad)
Definition: pigpio.c:12741
int gpioPWM(unsigned user_gpio, unsigned dutycycle)
Definition: pigpio.c:8744
int gpioWrite_Bits_32_53_Clear(uint32_t bits)
Definition: pigpio.c:12481
int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode)
Definition: pigpio.c:9524
int eventSetFunc(unsigned event, eventFunc_t f)
Definition: pigpio.c:11201
int gpioStoreScript(char *script)
Definition: pigpio.c:12158
int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags)
Definition: pigpio.c:3942
int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud)
Definition: pigpio.c:10332
uint16_t topOOL
Definition: pigpio.h:459
int gpioWrite_Bits_0_31_Set(uint32_t bits)
Definition: pigpio.c:12495
int gpioSetPWMrange(unsigned user_gpio, unsigned range)
Definition: pigpio.c:8807
int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpio.c:4776


cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Tue Oct 20 2020 03:35:57