pigpio.h
Go to the documentation of this file.
00001 /*
00002 This is free and unencumbered software released into the public domain.
00003 
00004 Anyone is free to copy, modify, publish, use, compile, sell, or
00005 distribute this software, either in source code form or as a compiled
00006 binary, for any purpose, commercial or non-commercial, and by any
00007 means.
00008 
00009 In jurisdictions that recognize copyright laws, the author or authors
00010 of this software dedicate any and all copyright interest in the
00011 software to the public domain. We make this dedication for the benefit
00012 of the public at large and to the detriment of our heirs and
00013 successors. We intend this dedication to be an overt act of
00014 relinquishment in perpetuity of all present and future rights to this
00015 software under copyright law.
00016 
00017 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
00018 EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
00019 MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
00020 IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
00021 OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
00022 ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
00023 OTHER DEALINGS IN THE SOFTWARE.
00024 
00025 For more information, please refer to <http://unlicense.org/>
00026 */
00027 
00028 #ifndef PIGPIO_H
00029 #define PIGPIO_H
00030 
00031 #include <stdint.h>
00032 #include <pthread.h>
00033 
00034 #define PIGPIO_VERSION 67
00035 
00036 /*TEXT
00037 
00038 pigpio is a C library for the Raspberry which allows control of the GPIO.
00039 
00040 *Features*
00041 
00042 o hardware timed PWM on any of GPIO 0-31
00043 
00044 o hardware timed servo pulses on any of GPIO 0-31
00045 
00046 o callbacks when any of GPIO 0-31 change state
00047 
00048 o callbacks at timed intervals
00049 
00050 o reading/writing all of the GPIO in a bank as one operation
00051 
00052 o individually setting GPIO modes, reading and writing
00053 
00054 o notifications when any of GPIO 0-31 change state
00055 
00056 o the construction of output waveforms with microsecond timing
00057 
00058 o rudimentary permission control over GPIO
00059 
00060 o a simple interface to start and stop new threads
00061 
00062 o I2C, SPI, and serial link wrappers
00063 
00064 o creating and running scripts
00065 
00066 *GPIO*
00067 
00068 ALL GPIO are identified by their Broadcom number.
00069 
00070 *Credits*
00071 
00072 The PWM and servo pulses are timed using the DMA and PWM peripherals.
00073 
00074 This use was inspired by Richard Hirst's servoblaster kernel module.
00075 
00076 See [[https://github.com/richardghirst/PiBits/tree/master/ServoBlaster]]
00077 
00078 *Usage*
00079 
00080 Include <pigpio.h> in your source files.
00081 
00082 Assuming your source is in prog.c use the following command to build and
00083 run the executable.
00084 
00085 . .
00086 gcc -Wall -pthread -o prog prog.c -lpigpio -lrt
00087 sudo ./prog
00088 . .
00089 
00090 For examples of usage see the C programs within the pigpio archive file.
00091 
00092 *Notes*
00093 
00094 All the functions which return an int return < 0 on error.
00095 
00096 [*gpioInitialise*] must be called before all other library functions
00097 with the following exceptions:
00098 
00099 . .
00100 [*gpioCfg**]
00101 [*gpioVersion*]
00102 [*gpioHardwareRevision*]
00103 . .
00104 
00105 If the library is not initialised all but the [*gpioCfg**],
00106 [*gpioVersion*], and [*gpioHardwareRevision*] functions will
00107 return error PI_NOT_INITIALISED.
00108 
00109 If the library is initialised the [*gpioCfg**] functions will return
00110 error PI_INITIALISED.
00111 
00112 TEXT*/
00113 
00114 /*OVERVIEW
00115 
00116 ESSENTIAL
00117 
00118 gpioInitialise             Initialise library
00119 gpioTerminate              Stop library
00120 
00121 BEGINNER
00122 
00123 gpioSetMode                Set a GPIO mode
00124 gpioGetMode                Get a GPIO mode
00125 
00126 gpioSetPullUpDown          Set/clear GPIO pull up/down resistor
00127 
00128 gpioRead                   Read a GPIO
00129 gpioWrite                  Write a GPIO
00130 
00131 gpioPWM                    Start/stop PWM pulses on a GPIO
00132 gpioGetPWMdutycycle        Get dutycycle setting on a GPIO
00133 
00134 gpioServo                  Start/stop servo pulses on a GPIO
00135 gpioGetServoPulsewidth     Get pulsewidth setting on a GPIO
00136 
00137 gpioDelay                  Delay for a number of microseconds
00138 
00139 gpioSetAlertFunc           Request a GPIO level change callback
00140 
00141 gpioSetTimerFunc           Request a regular timed callback
00142 
00143 INTERMEDIATE
00144 
00145 gpioTrigger                Send a trigger pulse to a GPIO.
00146 
00147 gpioSetWatchdog            Set a watchdog on a GPIO.
00148 
00149 gpioSetPWMrange            Configure PWM range for a GPIO
00150 gpioGetPWMrange            Get configured PWM range for a GPIO
00151 
00152 gpioSetPWMfrequency        Configure PWM frequency for a GPIO
00153 gpioGetPWMfrequency        Get configured PWM frequency for a GPIO
00154 
00155 gpioRead_Bits_0_31         Read all GPIO in bank 1
00156 gpioRead_Bits_32_53        Read all GPIO in bank 2
00157 
00158 gpioWrite_Bits_0_31_Clear  Clear selected GPIO in bank 1
00159 gpioWrite_Bits_32_53_Clear Clear selected GPIO in bank 2
00160 
00161 gpioWrite_Bits_0_31_Set    Set selected GPIO in bank 1
00162 gpioWrite_Bits_32_53_Set   Set selected GPIO in bank 2
00163 
00164 gpioStartThread            Start a new thread
00165 gpioStopThread             Stop a previously started thread
00166 
00167 ADVANCED
00168 
00169 gpioGetPWMrealRange        Get underlying PWM range for a GPIO
00170 
00171 gpioSetAlertFuncEx         Request a GPIO change callback, extended
00172 
00173 gpioSetISRFunc             Request a GPIO interrupt callback
00174 gpioSetISRFuncEx           Request a GPIO interrupt callback, extended
00175 
00176 gpioSetSignalFunc          Request a signal callback
00177 gpioSetSignalFuncEx        Request a signal callback, extended
00178 
00179 gpioSetGetSamplesFunc      Requests a GPIO samples callback
00180 gpioSetGetSamplesFuncEx    Requests a GPIO samples callback, extended
00181 
00182 gpioSetTimerFuncEx         Request a regular timed callback, extended
00183 
00184 gpioNotifyOpen             Request a notification handle
00185 gpioNotifyOpenWithSize     Request a notification handle with sized pipe
00186 gpioNotifyBegin            Start notifications for selected GPIO
00187 gpioNotifyPause            Pause notifications
00188 gpioNotifyClose            Close a notification
00189 
00190 gpioSerialReadOpen         Opens a GPIO for bit bang serial reads
00191 gpioSerialReadInvert       Configures normal/inverted for serial reads
00192 gpioSerialRead             Reads bit bang serial data from a GPIO
00193 gpioSerialReadClose        Closes a GPIO for bit bang serial reads
00194 
00195 gpioHardwareClock          Start hardware clock on supported GPIO
00196 gpioHardwarePWM            Start hardware PWM on supported GPIO
00197 
00198 gpioGlitchFilter           Set a glitch filter on a GPIO
00199 gpioNoiseFilter            Set a noise filter on a GPIO
00200 
00201 gpioGetPad                 Gets a pads drive strength
00202 gpioSetPad                 Sets a pads drive strength
00203 
00204 shell                      Executes a shell command
00205 
00206 SCRIPTS
00207 
00208 gpioStoreScript            Store a script
00209 gpioRunScript              Run a stored script
00210 gpioUpdateScript           Set a scripts parameters
00211 gpioScriptStatus           Get script status and parameters
00212 gpioStopScript             Stop a running script
00213 gpioDeleteScript           Delete a stored script
00214 
00215 WAVES
00216 
00217 gpioWaveClear              Deletes all waveforms
00218 
00219 gpioWaveAddNew             Starts a new waveform
00220 gpioWaveAddGeneric         Adds a series of pulses to the waveform
00221 gpioWaveAddSerial          Adds serial data to the waveform
00222 
00223 gpioWaveCreate             Creates a waveform from added data
00224 gpioWaveDelete             Deletes a waveform
00225 
00226 gpioWaveTxSend             Transmits a waveform
00227 
00228 gpioWaveChain              Transmits a chain of waveforms
00229 
00230 gpioWaveTxAt               Returns the current transmitting waveform
00231 
00232 gpioWaveTxBusy             Checks to see if the waveform has ended
00233 gpioWaveTxStop             Aborts the current waveform
00234 
00235 gpioWaveGetMicros          Length in microseconds of the current waveform
00236 gpioWaveGetHighMicros      Length of longest waveform so far
00237 gpioWaveGetMaxMicros       Absolute maximum allowed micros
00238 
00239 gpioWaveGetPulses          Length in pulses of the current waveform
00240 gpioWaveGetHighPulses      Length of longest waveform so far
00241 gpioWaveGetMaxPulses       Absolute maximum allowed pulses
00242 
00243 gpioWaveGetCbs             Length in control blocks of the current waveform
00244 gpioWaveGetHighCbs         Length of longest waveform so far
00245 gpioWaveGetMaxCbs          Absolute maximum allowed control blocks
00246 
00247 I2C
00248 
00249 i2cOpen                    Opens an I2C device
00250 i2cClose                   Closes an I2C device
00251 
00252 i2cWriteQuick              SMBus write quick
00253 i2cWriteByte               SMBus write byte
00254 i2cReadByte                SMBus read byte
00255 i2cWriteByteData           SMBus write byte data
00256 i2cWriteWordData           SMBus write word data
00257 i2cReadByteData            SMBus read byte data
00258 i2cReadWordData            SMBus read word data
00259 i2cProcessCall             SMBus process call
00260 i2cWriteBlockData          SMBus write block data
00261 i2cReadBlockData           SMBus read block data
00262 i2cBlockProcessCall        SMBus block process call
00263 
00264 i2cWriteI2CBlockData       SMBus write I2C block data
00265 i2cReadI2CBlockData        SMBus read I2C block data
00266 
00267 i2cReadDevice              Reads the raw I2C device
00268 i2cWriteDevice             Writes the raw I2C device
00269 
00270 i2cSwitchCombined          Sets or clears the combined flag
00271 
00272 i2cSegments                Performs multiple I2C transactions
00273 
00274 i2cZip                     Performs multiple I2C transactions
00275 
00276 bbI2COpen                  Opens GPIO for bit banging I2C
00277 bbI2CClose                 Closes GPIO for bit banging I2C
00278 bbI2CZip                   Performs multiple bit banged I2C transactions
00279 
00280 SPI
00281 
00282 spiOpen                    Opens a SPI device
00283 spiClose                   Closes a SPI device
00284 
00285 spiRead                    Reads bytes from a SPI device
00286 spiWrite                   Writes bytes to a SPI device
00287 spiXfer                    Transfers bytes with a SPI device
00288 
00289 bbSPIOpen                  Opens GPIO for bit banging SPI
00290 bbSPIClose                 Closes GPIO for bit banging SPI
00291 bbSPIXfer                  Performs multiple bit banged SPI transactions
00292 
00293 I2C/SPI_SLAVE
00294 
00295 bscXfer                    I2C/SPI as slave transfer
00296 
00297 SERIAL
00298 
00299 serOpen                    Opens a serial device
00300 serClose                   Closes a serial device
00301 
00302 serReadByte                Reads a byte from a serial device
00303 serWriteByte               Writes a byte to a serial device
00304 serRead                    Reads bytes from a serial device
00305 serWrite                   Writes bytes to a serial device
00306 
00307 serDataAvailable           Returns number of bytes ready to be read
00308 
00309 FILES
00310 
00311 fileOpen                   Opens a file
00312 fileClose                  Closes a file
00313 fileRead                   Reads bytes from a file
00314 fileWrite                  Writes bytes to a file
00315 fileSeek                   Seeks to a position within a file
00316 fileList                   List files which match a pattern
00317 
00318 EVENTS
00319 
00320 eventMonitor               Sets the events to monitor
00321 eventSetFunc               Request an event callback
00322 eventSetFuncEx             Request an event callback, extended
00323 eventTrigger               Trigger an event
00324 
00325 CONFIGURATION
00326 
00327 gpioCfgBufferSize          Configure the GPIO sample buffer size
00328 gpioCfgClock               Configure the GPIO sample rate
00329 gpioCfgDMAchannel          Configure the DMA channel (DEPRECATED)
00330 gpioCfgDMAchannels         Configure the DMA channels
00331 gpioCfgPermissions         Configure the GPIO access permissions
00332 gpioCfgInterfaces          Configure user interfaces
00333 gpioCfgSocketPort          Configure socket port
00334 gpioCfgMemAlloc            Configure DMA memory allocation mode
00335 gpioCfgNetAddr             Configure allowed network addresses
00336 
00337 gpioCfgInternals           Configure miscellaneous internals (DEPRECATED)
00338 gpioCfgGetInternals        Get internal configuration settings
00339 gpioCfgSetInternals        Set internal configuration settings
00340 
00341 CUSTOM
00342 
00343 gpioCustom1                User custom function 1
00344 gpioCustom2                User custom function 2
00345 
00346 UTILITIES
00347 
00348 gpioTick                   Get current tick (microseconds)
00349 
00350 gpioHardwareRevision       Get hardware revision
00351 gpioVersion                Get the pigpio version
00352 
00353 getBitInBytes              Get the value of a bit
00354 putBitInBytes              Set the value of a bit
00355 
00356 gpioTime                   Get current time
00357 gpioSleep                  Sleep for specified time
00358 
00359 time_sleep                 Sleeps for a float number of seconds
00360 time_time                  Float number of seconds since the epoch
00361 
00362 EXPERT
00363 
00364 rawWaveAddSPI              Not intended for general use
00365 rawWaveAddGeneric          Not intended for general use
00366 rawWaveCB                  Not intended for general use
00367 rawWaveCBAdr               Not intended for general use
00368 rawWaveGetOOL              Not intended for general use
00369 rawWaveSetOOL              Not intended for general use
00370 rawWaveGetOut              Not intended for general use
00371 rawWaveSetOut              Not intended for general use
00372 rawWaveGetIn               Not intended for general use
00373 rawWaveSetIn               Not intended for general use
00374 rawWaveInfo                Not intended for general use
00375 rawDumpWave                Not intended for general use
00376 rawDumpScript              Not intended for general use
00377 
00378 OVERVIEW*/
00379 
00380 #define PI_INPFIFO "/dev/pigpio"
00381 #define PI_OUTFIFO "/dev/pigout"
00382 #define PI_ERRFIFO "/dev/pigerr"
00383 
00384 #define PI_ENVPORT "PIGPIO_PORT"
00385 #define PI_ENVADDR "PIGPIO_ADDR"
00386 
00387 #define PI_LOCKFILE "/var/run/pigpio.pid"
00388 
00389 #define PI_I2C_COMBINED "/sys/module/i2c_bcm2708/parameters/combined"
00390 
00391 #ifdef __cplusplus
00392 extern "C" {
00393 #endif
00394 
00395 typedef struct
00396 {
00397    uint16_t func;
00398    uint16_t size;
00399 } gpioHeader_t;
00400 
00401 typedef struct
00402 {
00403    size_t size;
00404    void *ptr;
00405    uint32_t data;
00406 } gpioExtent_t;
00407 
00408 typedef struct
00409 {
00410    uint32_t tick;
00411    uint32_t level;
00412 } gpioSample_t;
00413 
00414 typedef struct
00415 {
00416    uint16_t seqno;
00417    uint16_t flags;
00418    uint32_t tick;
00419    uint32_t level;
00420 } gpioReport_t;
00421 
00422 typedef struct
00423 {
00424    uint32_t gpioOn;
00425    uint32_t gpioOff;
00426    uint32_t usDelay;
00427 } gpioPulse_t;
00428 
00429 #define WAVE_FLAG_READ  1
00430 #define WAVE_FLAG_TICK  2
00431 
00432 typedef struct
00433 {
00434    uint32_t gpioOn;
00435    uint32_t gpioOff;
00436    uint32_t usDelay;
00437    uint32_t flags;
00438 } rawWave_t;
00439 
00440 /*
00441 CBs are used in order from the lowest numbered CB up to
00442 the maximum NUM_WAVE_CBS.
00443 
00444 OOLS are used from the bottom climbing up and from
00445 the top climbing down.
00446 
00447 The GPIO on and off settings climb up from the bottom (botOOL/numBOOL).
00448 
00449 The level and tick read values are stored in descending locations
00450 from the top (topOOL/numTOOL).
00451 */
00452 
00453 typedef struct
00454 {
00455    uint16_t botCB;  /* first CB used by wave  */
00456    uint16_t topCB;  /* last CB used by wave   */
00457    uint16_t botOOL; /* first bottom OOL used by wave  */
00458                     /* botOOL to botOOL + numBOOL - 1 are in use */
00459    uint16_t topOOL; /* last top OOL used by wave */
00460                     /* topOOL - numTOOL to topOOL are in use.*/
00461    uint16_t deleted;
00462    uint16_t numCB;
00463    uint16_t numBOOL;
00464    uint16_t numTOOL;
00465 } rawWaveInfo_t;
00466 
00467 typedef struct
00468 {
00469    int clk;     /* GPIO for clock           */
00470    int mosi;    /* GPIO for MOSI            */
00471    int miso;    /* GPIO for MISO            */
00472    int ss_pol;  /* slave select off state   */
00473    int ss_us;   /* delay after slave select */
00474    int clk_pol; /* clock off state          */
00475    int clk_pha; /* clock phase              */
00476    int clk_us;  /* clock micros             */
00477 } rawSPI_t;
00478 
00479 typedef struct { /* linux/arch/arm/mach-bcm2708/include/mach/dma.h */
00480    uint32_t info;
00481    uint32_t src;
00482    uint32_t dst;
00483    uint32_t length;
00484    uint32_t stride;
00485    uint32_t next;
00486    uint32_t pad[2];
00487 } rawCbs_t;
00488 
00489 typedef struct
00490 {
00491    uint16_t addr;  /* slave address       */
00492    uint16_t flags;
00493    uint16_t len;   /* msg length          */
00494    uint8_t  *buf;  /* pointer to msg data */
00495 } pi_i2c_msg_t;
00496 
00497 /* BSC FIFO size */
00498 
00499 #define BSC_FIFO_SIZE 512
00500 
00501 typedef struct
00502 {
00503    uint32_t control;          /* Write */
00504    int rxCnt;                 /* Read only */
00505    char rxBuf[BSC_FIFO_SIZE]; /* Read only */
00506    int txCnt;                 /* Write */
00507    char txBuf[BSC_FIFO_SIZE]; /* Write */
00508 } bsc_xfer_t;
00509 
00510 
00511 typedef void (*gpioAlertFunc_t)    (int      gpio,
00512                                     int      level,
00513                                     uint32_t tick);
00514 
00515 typedef void (*gpioAlertFuncEx_t)  (int      gpio,
00516                                     int      level,
00517                                     uint32_t tick,
00518                                     void    *userdata);
00519 
00520 typedef void (*eventFunc_t)        (int      event,
00521                                     uint32_t tick);
00522 
00523 typedef void (*eventFuncEx_t)      (int      event,
00524                                     uint32_t tick,
00525                                     void    *userdata);
00526 
00527 typedef void (*gpioISRFunc_t)      (int      gpio,
00528                                     int      level,
00529                                     uint32_t tick);
00530 
00531 typedef void (*gpioISRFuncEx_t)    (int      gpio,
00532                                     int      level,
00533                                     uint32_t tick,
00534                                     void    *userdata);
00535 
00536 typedef void (*gpioTimerFunc_t)    (void);
00537 
00538 typedef void (*gpioTimerFuncEx_t)  (void *userdata);
00539 
00540 typedef void (*gpioSignalFunc_t)   (int signum);
00541 
00542 typedef void (*gpioSignalFuncEx_t) (int    signum,
00543                                     void  *userdata);
00544 
00545 typedef void (*gpioGetSamplesFunc_t)   (const gpioSample_t *samples,
00546                                         int                 numSamples);
00547 
00548 typedef void (*gpioGetSamplesFuncEx_t) (const gpioSample_t *samples,
00549                                         int                 numSamples,
00550                                         void               *userdata);
00551 
00552 typedef void *(gpioThreadFunc_t) (void *);
00553 
00554 
00555 /* gpio: 0-53 */
00556 
00557 #define PI_MIN_GPIO       0
00558 #define PI_MAX_GPIO      53
00559 
00560 /* user_gpio: 0-31 */
00561 
00562 #define PI_MAX_USER_GPIO 31
00563 
00564 /* level: 0-1 */
00565 
00566 #define PI_OFF   0
00567 #define PI_ON    1
00568 
00569 #define PI_CLEAR 0
00570 #define PI_SET   1
00571 
00572 #define PI_LOW   0
00573 #define PI_HIGH  1
00574 
00575 /* level: only reported for GPIO time-out, see gpioSetWatchdog */
00576 
00577 #define PI_TIMEOUT 2
00578 
00579 /* mode: 0-7 */
00580 
00581 #define PI_INPUT  0
00582 #define PI_OUTPUT 1
00583 #define PI_ALT0   4
00584 #define PI_ALT1   5
00585 #define PI_ALT2   6
00586 #define PI_ALT3   7
00587 #define PI_ALT4   3
00588 #define PI_ALT5   2
00589 
00590 /* pud: 0-2 */
00591 
00592 #define PI_PUD_OFF  0
00593 #define PI_PUD_DOWN 1
00594 #define PI_PUD_UP   2
00595 
00596 /* dutycycle: 0-range */
00597 
00598 #define PI_DEFAULT_DUTYCYCLE_RANGE   255
00599 
00600 /* range: 25-40000 */
00601 
00602 #define PI_MIN_DUTYCYCLE_RANGE        25
00603 #define PI_MAX_DUTYCYCLE_RANGE     40000
00604 
00605 /* pulsewidth: 0, 500-2500 */
00606 
00607 #define PI_SERVO_OFF 0
00608 #define PI_MIN_SERVO_PULSEWIDTH 500
00609 #define PI_MAX_SERVO_PULSEWIDTH 2500
00610 
00611 /* hardware PWM */
00612 
00613 #define PI_HW_PWM_MIN_FREQ 1
00614 #define PI_HW_PWM_MAX_FREQ 125000000
00615 #define PI_HW_PWM_RANGE 1000000
00616 
00617 /* hardware clock */
00618 
00619 #define PI_HW_CLK_MIN_FREQ 4689
00620 #define PI_HW_CLK_MAX_FREQ 250000000
00621 
00622 #define PI_NOTIFY_SLOTS  32
00623 
00624 #define PI_NTFY_FLAGS_EVENT    (1 <<7)
00625 #define PI_NTFY_FLAGS_ALIVE    (1 <<6)
00626 #define PI_NTFY_FLAGS_WDOG     (1 <<5)
00627 #define PI_NTFY_FLAGS_BIT(x) (((x)<<0)&31)
00628 
00629 #define PI_WAVE_BLOCKS     4
00630 #define PI_WAVE_MAX_PULSES (PI_WAVE_BLOCKS * 3000)
00631 #define PI_WAVE_MAX_CHARS  (PI_WAVE_BLOCKS *  300)
00632 
00633 #define PI_BB_I2C_MIN_BAUD     50
00634 #define PI_BB_I2C_MAX_BAUD 500000
00635 
00636 #define PI_BB_SPI_MIN_BAUD     50
00637 #define PI_BB_SPI_MAX_BAUD 250000
00638 
00639 #define PI_BB_SER_MIN_BAUD     50
00640 #define PI_BB_SER_MAX_BAUD 250000
00641 
00642 #define PI_BB_SER_NORMAL 0
00643 #define PI_BB_SER_INVERT 1
00644 
00645 #define PI_WAVE_MIN_BAUD      50
00646 #define PI_WAVE_MAX_BAUD 1000000
00647 
00648 #define PI_SPI_MIN_BAUD     32000
00649 #define PI_SPI_MAX_BAUD 125000000
00650 
00651 #define PI_MIN_WAVE_DATABITS 1
00652 #define PI_MAX_WAVE_DATABITS 32
00653 
00654 #define PI_MIN_WAVE_HALFSTOPBITS 2
00655 #define PI_MAX_WAVE_HALFSTOPBITS 8
00656 
00657 #define PI_WAVE_MAX_MICROS (30 * 60 * 1000000) /* half an hour */
00658 
00659 #define PI_MAX_WAVES 250
00660 
00661 #define PI_MAX_WAVE_CYCLES 65535
00662 #define PI_MAX_WAVE_DELAY  65535
00663 
00664 #define PI_WAVE_COUNT_PAGES 10
00665 
00666 /* wave tx mode */
00667 
00668 #define PI_WAVE_MODE_ONE_SHOT      0
00669 #define PI_WAVE_MODE_REPEAT        1
00670 #define PI_WAVE_MODE_ONE_SHOT_SYNC 2
00671 #define PI_WAVE_MODE_REPEAT_SYNC   3
00672 
00673 /* special wave at return values */
00674 
00675 #define PI_WAVE_NOT_FOUND  9998 /* Transmitted wave not found. */
00676 #define PI_NO_TX_WAVE      9999 /* No wave being transmitted. */
00677 
00678 /* Files, I2C, SPI, SER */
00679 
00680 #define PI_FILE_SLOTS 16
00681 #define PI_I2C_SLOTS  64
00682 #define PI_SPI_SLOTS  32
00683 #define PI_SER_SLOTS  16
00684 
00685 #define PI_MAX_I2C_ADDR 0x7F
00686 
00687 #define PI_NUM_AUX_SPI_CHANNEL 3
00688 #define PI_NUM_STD_SPI_CHANNEL 2
00689 
00690 #define PI_MAX_I2C_DEVICE_COUNT (1<<16)
00691 #define PI_MAX_SPI_DEVICE_COUNT (1<<16)
00692 
00693 /* max pi_i2c_msg_t per transaction */
00694 
00695 #define  PI_I2C_RDRW_IOCTL_MAX_MSGS 42
00696 
00697 /* flags for i2cTransaction, pi_i2c_msg_t */
00698 
00699 #define PI_I2C_M_WR           0x0000 /* write data */
00700 #define PI_I2C_M_RD           0x0001 /* read data */
00701 #define PI_I2C_M_TEN          0x0010 /* ten bit chip address */
00702 #define PI_I2C_M_RECV_LEN     0x0400 /* length will be first received byte */
00703 #define PI_I2C_M_NO_RD_ACK    0x0800 /* if I2C_FUNC_PROTOCOL_MANGLING */
00704 #define PI_I2C_M_IGNORE_NAK   0x1000 /* if I2C_FUNC_PROTOCOL_MANGLING */
00705 #define PI_I2C_M_REV_DIR_ADDR 0x2000 /* if I2C_FUNC_PROTOCOL_MANGLING */
00706 #define PI_I2C_M_NOSTART      0x4000 /* if I2C_FUNC_PROTOCOL_MANGLING */
00707 
00708 /* bbI2CZip and i2cZip commands */
00709 
00710 #define PI_I2C_END          0
00711 #define PI_I2C_ESC          1
00712 #define PI_I2C_START        2
00713 #define PI_I2C_COMBINED_ON  2
00714 #define PI_I2C_STOP         3
00715 #define PI_I2C_COMBINED_OFF 3
00716 #define PI_I2C_ADDR         4
00717 #define PI_I2C_FLAGS        5
00718 #define PI_I2C_READ         6
00719 #define PI_I2C_WRITE        7
00720 
00721 /* SPI */
00722 
00723 #define PI_SPI_FLAGS_BITLEN(x) ((x&63)<<16)
00724 #define PI_SPI_FLAGS_RX_LSB(x)  ((x&1)<<15)
00725 #define PI_SPI_FLAGS_TX_LSB(x)  ((x&1)<<14)
00726 #define PI_SPI_FLAGS_3WREN(x)  ((x&15)<<10)
00727 #define PI_SPI_FLAGS_3WIRE(x)   ((x&1)<<9)
00728 #define PI_SPI_FLAGS_AUX_SPI(x) ((x&1)<<8)
00729 #define PI_SPI_FLAGS_RESVD(x)   ((x&7)<<5)
00730 #define PI_SPI_FLAGS_CSPOLS(x)  ((x&7)<<2)
00731 #define PI_SPI_FLAGS_MODE(x)    ((x&3))
00732 
00733 /* BSC registers */
00734 
00735 #define BSC_DR         0
00736 #define BSC_RSR        1
00737 #define BSC_SLV        2
00738 #define BSC_CR         3
00739 #define BSC_FR         4
00740 #define BSC_IFLS       5
00741 #define BSC_IMSC       6
00742 #define BSC_RIS        7
00743 #define BSC_MIS        8
00744 #define BSC_ICR        9
00745 #define BSC_DMACR     10
00746 #define BSC_TDR       11
00747 #define BSC_GPUSTAT   12
00748 #define BSC_HCTRL     13
00749 #define BSC_DEBUG_I2C 14
00750 #define BSC_DEBUG_SPI 15
00751 
00752 #define BSC_CR_TESTFIFO 2048
00753 #define BSC_CR_RXE  512
00754 #define BSC_CR_TXE  256
00755 #define BSC_CR_BRK  128
00756 #define BSC_CR_CPOL  16
00757 #define BSC_CR_CPHA   8
00758 #define BSC_CR_I2C    4
00759 #define BSC_CR_SPI    2
00760 #define BSC_CR_EN     1
00761 
00762 #define BSC_FR_RXBUSY 32
00763 #define BSC_FR_TXFE   16
00764 #define BSC_FR_RXFF    8
00765 #define BSC_FR_TXFF    4
00766 #define BSC_FR_RXFE    2
00767 #define BSC_FR_TXBUSY  1
00768 
00769 /* BSC GPIO */
00770 
00771 #define BSC_SDA_MOSI 18
00772 #define BSC_SCL_SCLK 19
00773 #define BSC_MISO     20
00774 #define BSC_CE_N     21
00775 
00776 /* Longest busy delay */
00777 
00778 #define PI_MAX_BUSY_DELAY 100
00779 
00780 /* timeout: 0-60000 */
00781 
00782 #define PI_MIN_WDOG_TIMEOUT 0
00783 #define PI_MAX_WDOG_TIMEOUT 60000
00784 
00785 /* timer: 0-9 */
00786 
00787 #define PI_MIN_TIMER 0
00788 #define PI_MAX_TIMER 9
00789 
00790 /* millis: 10-60000 */
00791 
00792 #define PI_MIN_MS 10
00793 #define PI_MAX_MS 60000
00794 
00795 #define PI_MAX_SCRIPTS       32
00796 
00797 #define PI_MAX_SCRIPT_TAGS   50
00798 #define PI_MAX_SCRIPT_VARS  150
00799 #define PI_MAX_SCRIPT_PARAMS 10
00800 
00801 /* script status */
00802 
00803 #define PI_SCRIPT_INITING 0
00804 #define PI_SCRIPT_HALTED  1
00805 #define PI_SCRIPT_RUNNING 2
00806 #define PI_SCRIPT_WAITING 3
00807 #define PI_SCRIPT_FAILED  4
00808 
00809 /* signum: 0-63 */
00810 
00811 #define PI_MIN_SIGNUM 0
00812 #define PI_MAX_SIGNUM 63
00813 
00814 /* timetype: 0-1 */
00815 
00816 #define PI_TIME_RELATIVE 0
00817 #define PI_TIME_ABSOLUTE 1
00818 
00819 #define PI_MAX_MICS_DELAY 1000000 /* 1 second */
00820 #define PI_MAX_MILS_DELAY 60000   /* 60 seconds */
00821 
00822 /* cfgMillis */
00823 
00824 #define PI_BUF_MILLIS_MIN 100
00825 #define PI_BUF_MILLIS_MAX 10000
00826 
00827 /* cfgMicros: 1, 2, 4, 5, 8, or 10 */
00828 
00829 /* cfgPeripheral: 0-1 */
00830 
00831 #define PI_CLOCK_PWM 0
00832 #define PI_CLOCK_PCM 1
00833 
00834 /* DMA channel: 0-14 */
00835 
00836 #define PI_MIN_DMA_CHANNEL 0
00837 #define PI_MAX_DMA_CHANNEL 14
00838 
00839 /* port */
00840 
00841 #define PI_MIN_SOCKET_PORT 1024
00842 #define PI_MAX_SOCKET_PORT 32000
00843 
00844 
00845 /* ifFlags: */
00846 
00847 #define PI_DISABLE_FIFO_IF   1
00848 #define PI_DISABLE_SOCK_IF   2
00849 #define PI_LOCALHOST_SOCK_IF 4
00850 #define PI_DISABLE_ALERT     8
00851 
00852 /* memAllocMode */
00853 
00854 #define PI_MEM_ALLOC_AUTO    0
00855 #define PI_MEM_ALLOC_PAGEMAP 1
00856 #define PI_MEM_ALLOC_MAILBOX 2
00857 
00858 /* filters */
00859 
00860 #define PI_MAX_STEADY  300000
00861 #define PI_MAX_ACTIVE 1000000
00862 
00863 /* gpioCfgInternals */
00864 
00865 #define PI_CFG_DBG_LEVEL         0 /* bits 0-3 */
00866 #define PI_CFG_ALERT_FREQ        4 /* bits 4-7 */
00867 #define PI_CFG_RT_PRIORITY       (1<<8)
00868 #define PI_CFG_STATS             (1<<9)
00869 #define PI_CFG_NOSIGHANDLER      (1<<10)
00870 
00871 #define PI_CFG_ILLEGAL_VAL       (1<<11)
00872 
00873 
00874 /* gpioISR */
00875 
00876 #define RISING_EDGE  0
00877 #define FALLING_EDGE 1
00878 #define EITHER_EDGE  2
00879 
00880 
00881 /* pads */
00882 
00883 #define PI_MAX_PAD 2
00884 
00885 #define PI_MIN_PAD_STRENGTH 1
00886 #define PI_MAX_PAD_STRENGTH 16
00887 
00888 /* files */
00889 
00890 #define PI_FILE_NONE   0
00891 #define PI_FILE_MIN    1
00892 #define PI_FILE_READ   1
00893 #define PI_FILE_WRITE  2
00894 #define PI_FILE_RW     3
00895 #define PI_FILE_APPEND 4
00896 #define PI_FILE_CREATE 8
00897 #define PI_FILE_TRUNC  16
00898 #define PI_FILE_MAX    31
00899 
00900 #define PI_FROM_START   0
00901 #define PI_FROM_CURRENT 1
00902 #define PI_FROM_END     2
00903 
00904 /* Allowed socket connect addresses */
00905 
00906 #define MAX_CONNECT_ADDRESSES 256
00907 
00908 /* events */
00909 
00910 #define PI_MAX_EVENT 31
00911 
00912 /* Event auto generated on BSC slave activity */
00913 
00914 #define PI_EVENT_BSC 31
00915 
00916 /*F*/
00917 int gpioInitialise(void);
00918 /*D
00919 Initialises the library.
00920 
00921 Returns the pigpio version number if OK, otherwise PI_INIT_FAILED.
00922 
00923 gpioInitialise must be called before using the other library functions
00924 with the following exceptions:
00925 
00926 . .
00927 [*gpioCfg**]
00928 [*gpioVersion*]
00929 [*gpioHardwareRevision*]
00930 . .
00931 
00932 ...
00933 if (gpioInitialise() < 0)
00934 {
00935    // pigpio initialisation failed.
00936 }
00937 else
00938 {
00939    // pigpio initialised okay.
00940 }
00941 ...
00942 D*/
00943 
00944 
00945 /*F*/
00946 void gpioTerminate(void);
00947 /*D
00948 Terminates the library.
00949 
00950 Returns nothing.
00951 
00952 Call before program exit.
00953 
00954 This function resets the used DMA channels, releases memory, and
00955 terminates any running threads.
00956 
00957 ...
00958 gpioTerminate();
00959 ...
00960 D*/
00961 
00962 
00963 /*F*/
00964 int gpioSetMode(unsigned gpio, unsigned mode);
00965 /*D
00966 Sets the GPIO mode, typically input or output.
00967 
00968 . .
00969 gpio: 0-53
00970 mode: 0-7
00971 . .
00972 
00973 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE.
00974 
00975 Arduino style: pinMode.
00976 
00977 ...
00978 gpioSetMode(17, PI_INPUT);  // Set GPIO17 as input.
00979 
00980 gpioSetMode(18, PI_OUTPUT); // Set GPIO18 as output.
00981 
00982 gpioSetMode(22,PI_ALT0);    // Set GPIO22 to alternative mode 0.
00983 ...
00984 
00985 See [[http://www.raspberrypi.org/documentation/hardware/raspberrypi/bcm2835/BCM2835-ARM-Peripherals.pdf]] page 102 for an overview of the modes.
00986 D*/
00987 
00988 
00989 /*F*/
00990 int gpioGetMode(unsigned gpio);
00991 /*D
00992 Gets the GPIO mode.
00993 
00994 . .
00995 gpio: 0-53
00996 . .
00997 
00998 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
00999 
01000 ...
01001 if (gpioGetMode(17) != PI_ALT0)
01002 {
01003    gpioSetMode(17, PI_ALT0);  // set GPIO17 to ALT0
01004 }
01005 ...
01006 D*/
01007 
01008 
01009 /*F*/
01010 int gpioSetPullUpDown(unsigned gpio, unsigned pud);
01011 /*D
01012 Sets or clears resistor pull ups or downs on the GPIO.
01013 
01014 . .
01015 gpio: 0-53
01016  pud: 0-2
01017 . .
01018 
01019 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD.
01020 
01021 ...
01022 gpioSetPullUpDown(17, PI_PUD_UP);   // Sets a pull-up.
01023 
01024 gpioSetPullUpDown(18, PI_PUD_DOWN); // Sets a pull-down.
01025 
01026 gpioSetPullUpDown(23, PI_PUD_OFF);  // Clear any pull-ups/downs.
01027 ...
01028 D*/
01029 
01030 
01031 /*F*/
01032 int gpioRead (unsigned gpio);
01033 /*D
01034 Reads the GPIO level, on or off.
01035 
01036 . .
01037 gpio: 0-53
01038 . .
01039 
01040 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
01041 
01042 Arduino style: digitalRead.
01043 
01044 ...
01045 printf("GPIO24 is level %d", gpioRead(24));
01046 ...
01047 D*/
01048 
01049 
01050 /*F*/
01051 int gpioWrite(unsigned gpio, unsigned level);
01052 /*D
01053 Sets the GPIO level, on or off.
01054 
01055 . .
01056  gpio: 0-53
01057 level: 0-1
01058 . .
01059 
01060 Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL.
01061 
01062 If PWM or servo pulses are active on the GPIO they are switched off.
01063 
01064 Arduino style: digitalWrite
01065 
01066 ...
01067 gpioWrite(24, 1); // Set GPIO24 high.
01068 ...
01069 D*/
01070 
01071 
01072 /*F*/
01073 int gpioPWM(unsigned user_gpio, unsigned dutycycle);
01074 /*D
01075 Starts PWM on the GPIO, dutycycle between 0 (off) and range (fully on).
01076 Range defaults to 255.
01077 
01078 . .
01079 user_gpio: 0-31
01080 dutycycle: 0-range
01081 . .
01082 
01083 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE.
01084 
01085 Arduino style: analogWrite
01086 
01087 This and the servo functionality use the DMA and PWM or PCM peripherals
01088 to control and schedule the pulse lengths and dutycycles.
01089 
01090 The [*gpioSetPWMrange*] function may be used to change the default
01091 range of 255.
01092 
01093 ...
01094 gpioPWM(17, 255); // Sets GPIO17 full on.
01095 
01096 gpioPWM(18, 128); // Sets GPIO18 half on.
01097 
01098 gpioPWM(23, 0);   // Sets GPIO23 full off.
01099 ...
01100 D*/
01101 
01102 
01103 /*F*/
01104 int gpioGetPWMdutycycle(unsigned user_gpio);
01105 /*D
01106 Returns the PWM dutycycle setting for the GPIO.
01107 
01108 . .
01109 user_gpio: 0-31
01110 . .
01111 
01112 Returns between 0 (off) and range (fully on) if OK, otherwise
01113 PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
01114 
01115 For normal PWM the dutycycle will be out of the defined range
01116 for the GPIO (see [*gpioGetPWMrange*]).
01117 
01118 If a hardware clock is active on the GPIO the reported dutycycle
01119 will be 500000 (500k) out of 1000000 (1M).
01120 
01121 If hardware PWM is active on the GPIO the reported dutycycle
01122 will be out of a 1000000 (1M).
01123 
01124 Normal PWM range defaults to 255.
01125 D*/
01126 
01127 
01128 /*F*/
01129 int gpioSetPWMrange(unsigned user_gpio, unsigned range);
01130 /*D
01131 Selects the dutycycle range to be used for the GPIO.  Subsequent calls
01132 to gpioPWM will use a dutycycle between 0 (off) and range (fully on).
01133 
01134 . .
01135 user_gpio: 0-31
01136     range: 25-40000
01137 . .
01138 
01139 Returns the real range for the given GPIO's frequency if OK,
01140 otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE.
01141 
01142 If PWM is currently active on the GPIO its dutycycle will be scaled
01143 to reflect the new range.
01144 
01145 The real range, the number of steps between fully off and fully
01146 on for each frequency, is given in the following table.
01147 
01148 . .
01149   25,   50,  100,  125,  200,  250,  400,   500,   625,
01150  800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000
01151 . .
01152 
01153 The real value set by [*gpioPWM*] is (dutycycle * real range) / range.
01154 
01155 ...
01156 gpioSetPWMrange(24, 2000); // Now 2000 is fully on
01157                            //     1000 is half on
01158                            //      500 is quarter on, etc.
01159 ...
01160 D*/
01161 
01162 
01163 /*F*/
01164 int gpioGetPWMrange(unsigned user_gpio);
01165 /*D
01166 Returns the dutycycle range used for the GPIO if OK, otherwise
01167 PI_BAD_USER_GPIO.
01168 
01169 . .
01170 user_gpio: 0-31
01171 . .
01172 
01173 If a hardware clock or hardware PWM is active on the GPIO
01174 the reported range will be 1000000 (1M).
01175 
01176 ...
01177 r = gpioGetPWMrange(23);
01178 ...
01179 D*/
01180 
01181 
01182 /*F*/
01183 int gpioGetPWMrealRange(unsigned user_gpio);
01184 /*D
01185 Returns the real range used for the GPIO if OK, otherwise
01186 PI_BAD_USER_GPIO.
01187 
01188 . .
01189 user_gpio: 0-31
01190 . .
01191 
01192 If a hardware clock is active on the GPIO the reported real
01193 range will be 1000000 (1M).
01194 
01195 If hardware PWM is active on the GPIO the reported real range
01196 will be approximately 250M divided by the set PWM frequency.
01197 
01198 ...
01199 rr = gpioGetPWMrealRange(17);
01200 ...
01201 D*/
01202 
01203 
01204 /*F*/
01205 int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency);
01206 /*D
01207 Sets the frequency in hertz to be used for the GPIO.
01208 
01209 . .
01210 user_gpio: 0-31
01211 frequency: >=0
01212 . .
01213 
01214 Returns the numerically closest frequency if OK, otherwise
01215 PI_BAD_USER_GPIO.
01216 
01217 If PWM is currently active on the GPIO it will be
01218 switched off and then back on at the new frequency.
01219 
01220 Each GPIO can be independently set to one of 18 different PWM
01221 frequencies.
01222 
01223 The selectable frequencies depend upon the sample rate which
01224 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5).
01225 
01226 The frequencies for each sample rate are:
01227 
01228 . .
01229                        Hertz
01230 
01231        1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
01232            1250  1000   800  500  400  250  200  100   50
01233 
01234        2: 20000 10000  5000 4000 2500 2000 1250 1000  800
01235             625   500   400  250  200  125  100   50   25
01236 
01237        4: 10000  5000  2500 2000 1250 1000  625  500  400
01238             313   250   200  125  100   63   50   25   13
01239 sample
01240  rate
01241  (us)  5:  8000  4000  2000 1600 1000  800  500  400  320
01242             250   200   160  100   80   50   40   20   10
01243 
01244        8:  5000  2500  1250 1000  625  500  313  250  200
01245             156   125   100   63   50   31   25   13    6
01246 
01247       10:  4000  2000  1000  800  500  400  250  200  160
01248             125   100    80   50   40   25   20   10    5
01249 . .
01250 
01251 ...
01252 gpioSetPWMfrequency(23, 0); // Set GPIO23 to lowest frequency.
01253 
01254 gpioSetPWMfrequency(24, 500); // Set GPIO24 to 500Hz.
01255 
01256 gpioSetPWMfrequency(25, 100000); // Set GPIO25 to highest frequency.
01257 ...
01258 D*/
01259 
01260 
01261 /*F*/
01262 int gpioGetPWMfrequency(unsigned user_gpio);
01263 /*D
01264 Returns the frequency (in hertz) used for the GPIO if OK, otherwise
01265 PI_BAD_USER_GPIO.
01266 
01267 . .
01268 user_gpio: 0-31
01269 . .
01270 
01271 For normal PWM the frequency will be that defined for the GPIO by
01272 [*gpioSetPWMfrequency*].
01273 
01274 If a hardware clock is active on the GPIO the reported frequency
01275 will be that set by [*gpioHardwareClock*].
01276 
01277 If hardware PWM is active on the GPIO the reported frequency
01278 will be that set by [*gpioHardwarePWM*].
01279 
01280 ...
01281 f = gpioGetPWMfrequency(23); // Get frequency used for GPIO23.
01282 ...
01283 D*/
01284 
01285 
01286 /*F*/
01287 int gpioServo(unsigned user_gpio, unsigned pulsewidth);
01288 /*D
01289 Starts servo pulses on the GPIO, 0 (off), 500 (most anti-clockwise) to
01290 2500 (most clockwise).
01291 
01292 . .
01293  user_gpio: 0-31
01294 pulsewidth: 0, 500-2500
01295 . .
01296 
01297 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH.
01298 
01299 The range supported by servos varies and should probably be determined
01300 by experiment.  A value of 1500 should always be safe and represents
01301 the mid-point of rotation.  You can DAMAGE a servo if you command it
01302 to move beyond its limits.
01303 
01304 The following causes an on pulse of 1500 microseconds duration to be
01305 transmitted on GPIO 17 at a rate of 50 times per second. This will
01306 command a servo connected to GPIO 17 to rotate to its mid-point.
01307 
01308 ...
01309 gpioServo(17, 1000); // Move servo to safe position anti-clockwise.
01310 
01311 gpioServo(23, 1500); // Move servo to centre position.
01312 
01313 gpioServo(25, 2000); // Move servo to safe position clockwise.
01314 ...
01315 
01316 OTHER UPDATE RATES:
01317 
01318 This function updates servos at 50Hz.  If you wish to use a different
01319 update frequency you will have to use the PWM functions.
01320 
01321 . .
01322 PWM Hz    50   100  200  400  500
01323 1E6/Hz 20000 10000 5000 2500 2000
01324 . .
01325 
01326 Firstly set the desired PWM frequency using [*gpioSetPWMfrequency*].
01327 
01328 Then set the PWM range using [*gpioSetPWMrange*] to 1E6/frequency.
01329 Doing this allows you to use units of microseconds when setting
01330 the servo pulsewidth.
01331 
01332 E.g. If you want to update a servo connected to GPIO25 at 400Hz
01333 
01334 . .
01335 gpioSetPWMfrequency(25, 400);
01336 
01337 gpioSetPWMrange(25, 2500);
01338 . .
01339 
01340 Thereafter use the PWM command to move the servo,
01341 e.g. gpioPWM(25, 1500) will set a 1500 us pulse.
01342 D*/
01343 
01344 
01345 /*F*/
01346 int gpioGetServoPulsewidth(unsigned user_gpio);
01347 /*D
01348 Returns the servo pulsewidth setting for the GPIO.
01349 
01350 . .
01351 user_gpio: 0-31
01352 . .
01353 
01354 Returns 0 (off), 500 (most anti-clockwise) to 2500 (most clockwise)
01355 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
01356 D*/
01357 
01358 
01359 /*F*/
01360 int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f);
01361 /*D
01362 Registers a function to be called (a callback) when the specified
01363 GPIO changes state.
01364 
01365 . .
01366 user_gpio: 0-31
01367         f: the callback function
01368 . .
01369 
01370 Returns 0 if OK, otherwise PI_BAD_USER_GPIO.
01371 
01372 One callback may be registered per GPIO.
01373 
01374 The callback is passed the GPIO, the new level, and the tick.
01375 
01376 . .
01377 Parameter   Value    Meaning
01378 
01379 GPIO        0-31     The GPIO which has changed state
01380 
01381 level       0-2      0 = change to low (a falling edge)
01382                      1 = change to high (a rising edge)
01383                      2 = no level change (a watchdog timeout)
01384 
01385 tick        32 bit   The number of microseconds since boot
01386                      WARNING: this wraps around from
01387                      4294967295 to 0 roughly every 72 minutes
01388 . .
01389 
01390 The alert may be cancelled by passing NULL as the function.
01391 
01392 The GPIO are sampled at a rate set when the library is started.
01393 
01394 If a value isn't specifically set the default of 5 us is used.
01395 
01396 The number of samples per second is given in the following table.
01397 
01398 . .
01399               samples
01400               per sec
01401 
01402          1  1,000,000
01403          2    500,000
01404 sample   4    250,000
01405 rate     5    200,000
01406 (us)     8    125,000
01407         10    100,000
01408 . .
01409 
01410 Level changes shorter than the sample rate may be missed.
01411 
01412 The thread which calls the alert functions is triggered nominally
01413 1000 times per second.  The active alert functions will be called
01414 once per level change since the last time the thread was activated.
01415 i.e. The active alert functions will get all level changes but there
01416 will be a latency.
01417 
01418 The tick value is the time stamp of the sample in microseconds, see
01419 [*gpioTick*] for more details.
01420 
01421 ...
01422 void aFunction(int gpio, int level, uint32_t tick)
01423 {
01424    printf("GPIO %d became %d at %d", gpio, level, tick);
01425 }
01426 
01427 // call aFunction whenever GPIO 4 changes state
01428 
01429 gpioSetAlertFunc(4, aFunction);
01430 ...
01431 D*/
01432 
01433 
01434 /*F*/
01435 int gpioSetAlertFuncEx(
01436    unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata);
01437 /*D
01438 Registers a function to be called (a callback) when the specified
01439 GPIO changes state.
01440 
01441 . .
01442 user_gpio: 0-31
01443         f: the callback function
01444  userdata: pointer to arbitrary user data
01445 . .
01446 
01447 Returns 0 if OK, otherwise PI_BAD_USER_GPIO.
01448 
01449 One callback may be registered per GPIO.
01450 
01451 The callback is passed the GPIO, the new level, the tick, and
01452 the userdata pointer.
01453 
01454 . .
01455 Parameter   Value    Meaning
01456 
01457 GPIO        0-31     The GPIO which has changed state
01458 
01459 level       0-2      0 = change to low (a falling edge)
01460                      1 = change to high (a rising edge)
01461                      2 = no level change (a watchdog timeout)
01462 
01463 tick        32 bit   The number of microseconds since boot
01464                      WARNING: this wraps around from
01465                      4294967295 to 0 roughly every 72 minutes
01466 
01467 userdata    pointer  Pointer to an arbitrary object
01468 . .
01469 
01470 See [*gpioSetAlertFunc*] for further details.
01471 
01472 Only one of [*gpioSetAlertFunc*] or [*gpioSetAlertFuncEx*] can be
01473 registered per GPIO.
01474 D*/
01475 
01476 
01477 /*F*/
01478 int gpioSetISRFunc(
01479    unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f);
01480 /*D
01481 Registers a function to be called (a callback) whenever the specified
01482 GPIO interrupt occurs.
01483 
01484 . .
01485    gpio: 0-53
01486    edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE
01487 timeout: interrupt timeout in milliseconds (<=0 to cancel)
01488       f: the callback function
01489 . .
01490 
01491 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE,
01492 or PI_BAD_ISR_INIT.
01493 
01494 One function may be registered per GPIO.
01495 
01496 The function is passed the GPIO, the current level, and the
01497 current tick.  The level will be PI_TIMEOUT if the optional
01498 interrupt timeout expires.
01499 
01500 . .
01501 Parameter   Value    Meaning
01502 
01503 GPIO        0-53     The GPIO which has changed state
01504 
01505 level       0-2      0 = change to low (a falling edge)
01506                      1 = change to high (a rising edge)
01507                      2 = no level change (interrupt timeout)
01508 
01509 tick        32 bit   The number of microseconds since boot
01510                      WARNING: this wraps around from
01511                      4294967295 to 0 roughly every 72 minutes
01512 . .
01513 
01514 The underlying Linux sysfs GPIO interface is used to provide
01515 the interrupt services.
01516 
01517 The first time the function is called, with a non-NULL f, the
01518 GPIO is exported, set to be an input, and set to interrupt
01519 on the given edge and timeout.
01520 
01521 Subsequent calls, with a non-NULL f, can vary one or more of the
01522 edge, timeout, or function.
01523 
01524 The ISR may be cancelled by passing a NULL f, in which case the
01525 GPIO is unexported.
01526 
01527 The tick is that read at the time the process was informed of
01528 the interrupt.  This will be a variable number of microseconds
01529 after the interrupt occurred.  Typically the latency will be of
01530 the order of 50 microseconds.  The latency is not guaranteed
01531 and will vary with system load.
01532 
01533 The level is that read at the time the process was informed of
01534 the interrupt, or PI_TIMEOUT if the optional interrupt timeout
01535 expired.  It may not be the same as the expected edge as
01536 interrupts happening in rapid succession may be missed by the
01537 kernel (i.e. this mechanism can not be used to capture several
01538 interrupts only a few microseconds apart).
01539 D*/
01540 
01541 
01542 /*F*/
01543 int gpioSetISRFuncEx(
01544    unsigned gpio,
01545    unsigned edge,
01546    int timeout,
01547    gpioISRFuncEx_t f,
01548    void *userdata);
01549 /*D
01550 Registers a function to be called (a callback) whenever the specified
01551 GPIO interrupt occurs.
01552 
01553 . .
01554     gpio: 0-53
01555     edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE
01556  timeout: interrupt timeout in milliseconds (<=0 to cancel)
01557        f: the callback function
01558 userdata: pointer to arbitrary user data
01559 . .
01560 
01561 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE,
01562 or PI_BAD_ISR_INIT.
01563 
01564 The function is passed the GPIO, the current level, the
01565 current tick, and the userdata pointer.
01566 
01567 . .
01568 Parameter   Value    Meaning
01569 
01570 GPIO        0-53     The GPIO which has changed state
01571 
01572 level       0-2      0 = change to low (a falling edge)
01573                      1 = change to high (a rising edge)
01574                      2 = no level change (interrupt timeout)
01575 
01576 tick        32 bit   The number of microseconds since boot
01577                      WARNING: this wraps around from
01578                      4294967295 to 0 roughly every 72 minutes
01579 
01580 userdata    pointer  Pointer to an arbitrary object
01581 . .
01582 
01583 Only one of [*gpioSetISRFunc*] or [*gpioSetISRFuncEx*] can be
01584 registered per GPIO.
01585 
01586 See [*gpioSetISRFunc*] for further details.
01587 D*/
01588 
01589 
01590 /*F*/
01591 int gpioNotifyOpen(void);
01592 /*D
01593 This function requests a free notification handle.
01594 
01595 Returns a handle greater than or equal to zero if OK,
01596 otherwise PI_NO_HANDLE.
01597 
01598 A notification is a method for being notified of GPIO state changes
01599 via a pipe or socket.
01600 
01601 Pipe notifications for handle x will be available at the pipe
01602 named /dev/pigpiox (where x is the handle number).  E.g. if the
01603 function returns 15 then the notifications must be read
01604 from /dev/pigpio15.
01605 
01606 Socket notifications are returned to the socket which requested the
01607 handle.
01608 
01609 ...
01610 h = gpioNotifyOpen();
01611 
01612 if (h >= 0)
01613 {
01614    sprintf(str, "/dev/pigpio%d", h);
01615 
01616    fd = open(str, O_RDONLY);
01617 
01618    if (fd >= 0)
01619    {
01620       // Okay.
01621    }
01622    else
01623    {
01624       // Error.
01625    }
01626 }
01627 else
01628 {
01629    // Error.
01630 }
01631 ...
01632 D*/
01633 
01634 
01635 /*F*/
01636 int gpioNotifyOpenWithSize(int bufSize);
01637 /*D
01638 This function requests a free notification handle.
01639 
01640 It differs from [*gpioNotifyOpen*] in that the pipe size may be
01641 specified, whereas [*gpioNotifyOpen*] uses the default pipe size.
01642 
01643 See [*gpioNotifyOpen*] for further details.
01644 D*/
01645 
01646 
01647 /*F*/
01648 int gpioNotifyBegin(unsigned handle, uint32_t bits);
01649 /*D
01650 This function starts notifications on a previously opened handle.
01651 
01652 . .
01653 handle: >=0, as returned by [*gpioNotifyOpen*]
01654   bits: a bit mask indicating the GPIO of interest
01655 . .
01656 
01657 Returns 0 if OK, otherwise PI_BAD_HANDLE.
01658 
01659 The notification sends state changes for each GPIO whose corresponding
01660 bit in bits is set.
01661 
01662 Each notification occupies 12 bytes in the fifo and has the
01663 following structure.
01664 
01665 . .
01666 typedef struct
01667 {
01668    uint16_t seqno;
01669    uint16_t flags;
01670    uint32_t tick;
01671    uint32_t level;
01672 } gpioReport_t;
01673 . .
01674 
01675 seqno: starts at 0 each time the handle is opened and then increments
01676 by one for each report.
01677 
01678 flags: three flags are defined, PI_NTFY_FLAGS_WDOG,
01679 PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT.
01680 
01681 If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags
01682 indicate a GPIO which has had a watchdog timeout.
01683 
01684 If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive
01685 signal on the pipe/socket and is sent once a minute in the absence
01686 of other notification activity.
01687 
01688 If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags
01689 indicate an event which has been triggered.
01690 
01691 tick: the number of microseconds since system boot.  It wraps around
01692 after 1h12m.
01693 
01694 level: indicates the level of each GPIO.  If bit 1<<x is set then
01695 GPIO x is high.
01696 
01697 ...
01698 // Start notifications for GPIO 1, 4, 6, 7, 10.
01699 
01700 //                         1
01701 //                         0  76 4  1
01702 // (1234 = 0x04D2 = 0b0000010011010010)
01703 
01704 gpioNotifyBegin(h, 1234);
01705 ...
01706 D*/
01707 
01708 
01709 /*F*/
01710 int gpioNotifyPause(unsigned handle);
01711 /*D
01712 This function pauses notifications on a previously opened handle.
01713 
01714 . .
01715 handle: >=0, as returned by [*gpioNotifyOpen*]
01716 . .
01717 
01718 Returns 0 if OK, otherwise PI_BAD_HANDLE.
01719 
01720 Notifications for the handle are suspended until [*gpioNotifyBegin*]
01721 is called again.
01722 
01723 ...
01724 gpioNotifyPause(h);
01725 ...
01726 D*/
01727 
01728 
01729 /*F*/
01730 int gpioNotifyClose(unsigned handle);
01731 /*D
01732 This function stops notifications on a previously opened handle
01733 and releases the handle for reuse.
01734 
01735 . .
01736 handle: >=0, as returned by [*gpioNotifyOpen*]
01737 . .
01738 
01739 Returns 0 if OK, otherwise PI_BAD_HANDLE.
01740 
01741 ...
01742 gpioNotifyClose(h);
01743 ...
01744 D*/
01745 
01746 
01747 /*F*/
01748 int gpioWaveClear(void);
01749 /*D
01750 This function clears all waveforms and any data added by calls to the
01751 [*gpioWaveAdd**] functions.
01752 
01753 Returns 0 if OK.
01754 
01755 ...
01756 gpioWaveClear();
01757 ...
01758 D*/
01759 
01760 
01761 /*F*/
01762 int gpioWaveAddNew(void);
01763 /*D
01764 This function starts a new empty waveform.
01765 
01766 You wouldn't normally need to call this function as it is automatically
01767 called after a waveform is created with the [*gpioWaveCreate*] function.
01768 
01769 Returns 0 if OK.
01770 
01771 ...
01772 gpioWaveAddNew();
01773 ...
01774 D*/
01775 
01776 
01777 /*F*/
01778 int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses);
01779 /*D
01780 This function adds a number of pulses to the current waveform.
01781 
01782 . .
01783 numPulses: the number of pulses
01784    pulses: an array of pulses
01785 . .
01786 
01787 Returns the new total number of pulses in the current waveform if OK,
01788 otherwise PI_TOO_MANY_PULSES.
01789 
01790 The pulses are interleaved in time order within the existing waveform
01791 (if any).
01792 
01793 Merging allows the waveform to be built in parts, that is the settings
01794 for GPIO#1 can be added, and then GPIO#2 etc.
01795 
01796 If the added waveform is intended to start after or within the existing
01797 waveform then the first pulse should consist of a delay.
01798 
01799 ...
01800 // Construct and send a 30 microsecond square wave.
01801 
01802 gpioSetMode(gpio, PI_OUTPUT);
01803 
01804 pulse[0].gpioOn = (1<<gpio);
01805 pulse[0].gpioOff = 0;
01806 pulse[0].usDelay = 15;
01807 
01808 pulse[1].gpioOn = 0;
01809 pulse[1].gpioOff = (1<<gpio);
01810 pulse[1].usDelay = 15;
01811 
01812 gpioWaveAddNew();
01813 
01814 gpioWaveAddGeneric(2, pulse);
01815 
01816 wave_id = gpioWaveCreate();
01817 
01818 if (wave_id >= 0)
01819 {
01820    gpioWaveTxSend(wave_id, PI_WAVE_MODE_REPEAT);
01821 
01822    // Transmit for 30 seconds.
01823 
01824    sleep(30);
01825 
01826    gpioWaveTxStop();
01827 }
01828 else
01829 {
01830    // Wave create failed.
01831 }
01832 ...
01833 D*/
01834 
01835 
01836 /*F*/
01837 int gpioWaveAddSerial
01838    (unsigned user_gpio,
01839     unsigned baud,
01840     unsigned data_bits,
01841     unsigned stop_bits,
01842     unsigned offset,
01843     unsigned numBytes,
01844     char     *str);
01845 /*D
01846 This function adds a waveform representing serial data to the
01847 existing waveform (if any).  The serial data starts offset
01848 microseconds from the start of the waveform.
01849 
01850 . .
01851 user_gpio: 0-31
01852      baud: 50-1000000
01853 data_bits: 1-32
01854 stop_bits: 2-8
01855    offset: >=0
01856  numBytes: >=1
01857       str: an array of chars (which may contain nulls)
01858 . .
01859 
01860 Returns the new total number of pulses in the current waveform if OK,
01861 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
01862 PI_BAD_STOPBITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
01863 or PI_TOO_MANY_PULSES.
01864 
01865 NOTES:
01866 
01867 The serial data is formatted as one start bit, data_bits data bits, and
01868 stop_bits/2 stop bits.
01869 
01870 It is legal to add serial data streams with different baud rates to
01871 the same waveform.
01872 
01873 numBytes is the number of bytes of data in str.
01874 
01875 The bytes required for each character depend upon data_bits.
01876 
01877 For data_bits 1-8 there will be one byte per character. 
01878 For data_bits 9-16 there will be two bytes per character. 
01879 For data_bits 17-32 there will be four bytes per character.
01880 
01881 ...
01882 #define MSG_LEN 8
01883 
01884 int i;
01885 char *str;
01886 char data[MSG_LEN];
01887 
01888 str = "Hello world!";
01889 
01890 gpioWaveAddSerial(4, 9600, 8, 2, 0, strlen(str), str);
01891 
01892 for (i=0; i<MSG_LEN; i++) data[i] = i;
01893 
01894 // Data added is offset 1 second from the waveform start.
01895 gpioWaveAddSerial(4, 9600, 8, 2, 1000000, MSG_LEN, data);
01896 ...
01897 D*/
01898 
01899 
01900 /*F*/
01901 int gpioWaveCreate(void);
01902 /*D
01903 This function creates a waveform from the data provided by the prior
01904 calls to the [*gpioWaveAdd**] functions.  Upon success a wave id
01905 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
01906 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
01907 
01908 The data provided by the [*gpioWaveAdd**] functions is consumed by this
01909 function.
01910 
01911 As many waveforms may be created as there is space available.  The
01912 wave id is passed to [*gpioWaveTxSend*] to specify the waveform to transmit.
01913 
01914 Normal usage would be
01915 
01916 Step 1. [*gpioWaveClear*] to clear all waveforms and added data.
01917 
01918 Step 2. [*gpioWaveAdd**] calls to supply the waveform data.
01919 
01920 Step 3. [*gpioWaveCreate*] to create the waveform and get a unique id
01921 
01922 Repeat steps 2 and 3 as needed.
01923 
01924 Step 4. [*gpioWaveTxSend*] with the id of the waveform to transmit.
01925 
01926 A waveform comprises one of more pulses.  Each pulse consists of a
01927 [*gpioPulse_t*] structure.
01928 
01929 . .
01930 typedef struct
01931 {
01932    uint32_t gpioOn;
01933    uint32_t gpioOff;
01934    uint32_t usDelay;
01935 } gpioPulse_t;
01936 . .
01937 
01938 The fields specify
01939 
01940 1) the GPIO to be switched on at the start of the pulse. 
01941 2) the GPIO to be switched off at the start of the pulse. 
01942 3) the delay in microseconds before the next pulse.
01943 
01944 Any or all the fields can be zero.  It doesn't make any sense to
01945 set all the fields to zero (the pulse will be ignored).
01946 
01947 When a waveform is started each pulse is executed in order with the
01948 specified delay between the pulse and the next.
01949 
01950 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
01951 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
01952 D*/
01953 
01954 
01955 /*F*/
01956 int gpioWaveDelete(unsigned wave_id);
01957 /*D
01958 This function deletes the waveform with id wave_id.
01959 
01960 The wave is flagged for deletion.  The resources used by the wave
01961 will only be reused when either of the following apply.
01962 
01963 - all waves with higher numbered wave ids have been deleted or have
01964 been flagged for deletion.
01965 
01966 - a new wave is created which uses exactly the same resources as
01967 the current wave (see the C source for gpioWaveCreate for details).
01968 
01969 . .
01970 wave_id: >=0, as returned by [*gpioWaveCreate*]
01971 . .
01972 
01973 Wave ids are allocated in order, 0, 1, 2, etc.
01974 
01975 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
01976 D*/
01977 
01978 
01979 /*F*/
01980 int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode);
01981 /*D
01982 This function transmits the waveform with id wave_id.  The mode
01983 determines whether the waveform is sent once or cycles endlessly.
01984 The SYNC variants wait for the current waveform to reach the
01985 end of a cycle or finish before starting the new waveform.
01986 
01987 WARNING: bad things may happen if you delete the previous
01988 waveform before it has been synced to the new waveform.
01989 
01990 NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled.
01991 
01992 . .
01993   wave_id: >=0, as returned by [*gpioWaveCreate*]
01994 wave_mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT,
01995            PI_WAVE_MODE_ONE_SHOT_SYNC, PI_WAVE_MODE_REPEAT_SYNC
01996 . .
01997 
01998 Returns the number of DMA control blocks in the waveform if OK,
01999 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
02000 D*/
02001 
02002 
02003 /*F*/
02004 int gpioWaveChain(char *buf, unsigned bufSize);
02005 /*D
02006 This function transmits a chain of waveforms.
02007 
02008 NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled.
02009 
02010 The waves to be transmitted are specified by the contents of buf
02011 which contains an ordered list of [*wave_id*]s and optional command
02012 codes and related data.
02013 
02014 . .
02015     buf: pointer to the wave_ids and optional command codes
02016 bufSize: the number of bytes in buf
02017 . .
02018 
02019 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
02020 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
02021 
02022 Each wave is transmitted in the order specified.  A wave may
02023 occur multiple times per chain.
02024 
02025 A blocks of waves may be transmitted multiple times by using
02026 the loop commands. The block is bracketed by loop start and
02027 end commands.  Loops may be nested.
02028 
02029 Delays between waves may be added with the delay command.
02030 
02031 The following command codes are supported:
02032 
02033 Name         @ Cmd & Data @ Meaning
02034 Loop Start   @ 255 0      @ Identify start of a wave block
02035 Loop Repeat  @ 255 1 x y  @ loop x + y*256 times
02036 Delay        @ 255 2 x y  @ delay x + y*256 microseconds
02037 Loop Forever @ 255 3      @ loop forever
02038 
02039 If present Loop Forever must be the last entry in the chain.
02040 
02041 The code is currently dimensioned to support a chain with roughly
02042 600 entries and 20 loop counters.
02043 
02044 ...
02045 #include <stdio.h>
02046 #include <pigpio.h>
02047 
02048 #define WAVES 5
02049 #define GPIO 4
02050 
02051 int main(int argc, char *argv[])
02052 {
02053    int i, wid[WAVES];
02054 
02055    if (gpioInitialise()<0) return -1;
02056 
02057    gpioSetMode(GPIO, PI_OUTPUT);
02058 
02059    printf("start piscope, press return"); getchar();
02060 
02061    for (i=0; i<WAVES; i++)
02062    {
02063       gpioWaveAddGeneric(2, (gpioPulse_t[])
02064          {{1<<GPIO, 0,        20},
02065           {0, 1<<GPIO, (i+1)*200}});
02066 
02067       wid[i] = gpioWaveCreate();
02068    }
02069 
02070    gpioWaveChain((char []) {
02071       wid[4], wid[3], wid[2],       // transmit waves 4+3+2
02072       255, 0,                       // loop start
02073          wid[0], wid[0], wid[0],    // transmit waves 0+0+0
02074          255, 0,                    // loop start
02075             wid[0], wid[1],         // transmit waves 0+1
02076             255, 2, 0x88, 0x13,     // delay 5000us
02077          255, 1, 30, 0,             // loop end (repeat 30 times)
02078          255, 0,                    // loop start
02079             wid[2], wid[3], wid[0], // transmit waves 2+3+0
02080             wid[3], wid[1], wid[2], // transmit waves 3+1+2
02081          255, 1, 10, 0,             // loop end (repeat 10 times)
02082       255, 1, 5, 0,                 // loop end (repeat 5 times)
02083       wid[4], wid[4], wid[4],       // transmit waves 4+4+4
02084       255, 2, 0x20, 0x4E,           // delay 20000us
02085       wid[0], wid[0], wid[0],       // transmit waves 0+0+0
02086 
02087       }, 46);
02088 
02089    while (gpioWaveTxBusy()) time_sleep(0.1);
02090 
02091    for (i=0; i<WAVES; i++) gpioWaveDelete(wid[i]);
02092 
02093    printf("stop piscope, press return"); getchar();
02094 
02095    gpioTerminate();
02096 }
02097 ...
02098 D*/
02099 
02100 
02101 /*F*/
02102 int gpioWaveTxAt(void);
02103 /*D
02104 This function returns the id of the waveform currently being
02105 transmitted.
02106 
02107 Returns the waveform id or one of the following special values:
02108 
02109 PI_WAVE_NOT_FOUND (9998) - transmitted wave not found. 
02110 PI_NO_TX_WAVE (9999) - no wave being transmitted.
02111 D*/
02112 
02113 
02114 /*F*/
02115 int gpioWaveTxBusy(void);
02116 /*D
02117 This function checks to see if a waveform is currently being
02118 transmitted.
02119 
02120 Returns 1 if a waveform is currently being transmitted, otherwise 0.
02121 D*/
02122 
02123 
02124 /*F*/
02125 int gpioWaveTxStop(void);
02126 /*D
02127 This function aborts the transmission of the current waveform.
02128 
02129 Returns 0 if OK.
02130 
02131 This function is intended to stop a waveform started in repeat mode.
02132 D*/
02133 
02134 
02135 /*F*/
02136 int gpioWaveGetMicros(void);
02137 /*D
02138 This function returns the length in microseconds of the current
02139 waveform.
02140 D*/
02141 
02142 
02143 /*F*/
02144 int gpioWaveGetHighMicros(void);
02145 /*D
02146 This function returns the length in microseconds of the longest waveform
02147 created since [*gpioInitialise*] was called.
02148 D*/
02149 
02150 
02151 /*F*/
02152 int gpioWaveGetMaxMicros(void);
02153 /*D
02154 This function returns the maximum possible size of a waveform in
02155 microseconds.
02156 D*/
02157 
02158 
02159 /*F*/
02160 int gpioWaveGetPulses(void);
02161 /*D
02162 This function returns the length in pulses of the current waveform.
02163 D*/
02164 
02165 
02166 /*F*/
02167 int gpioWaveGetHighPulses(void);
02168 /*D
02169 This function returns the length in pulses of the longest waveform
02170 created since [*gpioInitialise*] was called.
02171 D*/
02172 
02173 
02174 /*F*/
02175 int gpioWaveGetMaxPulses(void);
02176 /*D
02177 This function returns the maximum possible size of a waveform in pulses.
02178 D*/
02179 
02180 
02181 /*F*/
02182 int gpioWaveGetCbs(void);
02183 /*D
02184 This function returns the length in DMA control blocks of the current
02185 waveform.
02186 D*/
02187 
02188 
02189 /*F*/
02190 int gpioWaveGetHighCbs(void);
02191 /*D
02192 This function returns the length in DMA control blocks of the longest
02193 waveform created since [*gpioInitialise*] was called.
02194 D*/
02195 
02196 
02197 /*F*/
02198 int gpioWaveGetMaxCbs(void);
02199 /*D
02200 This function returns the maximum possible size of a waveform in DMA
02201 control blocks.
02202 D*/
02203 
02204 
02205 /*F*/
02206 int gpioSerialReadOpen(unsigned user_gpio, unsigned baud, unsigned data_bits);
02207 /*D
02208 This function opens a GPIO for bit bang reading of serial data.
02209 
02210 . .
02211 user_gpio: 0-31
02212      baud: 50-250000
02213 data_bits: 1-32
02214 . .
02215 
02216 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
02217 PI_BAD_DATABITS, or PI_GPIO_IN_USE.
02218 
02219 The serial data is returned in a cyclic buffer and is read using
02220 [*gpioSerialRead*].
02221 
02222 It is the caller's responsibility to read data from the cyclic buffer
02223 in a timely fashion.
02224 D*/
02225 
02226 /*F*/
02227 int gpioSerialReadInvert(unsigned user_gpio, unsigned invert);
02228 /*D
02229 This function configures the level logic for bit bang serial reads.
02230 
02231 Use PI_BB_SER_INVERT to invert the serial logic and PI_BB_SER_NORMAL for
02232 normal logic.  Default is PI_BB_SER_NORMAL.
02233 
02234 . .
02235 user_gpio: 0-31
02236    invert: 0-1
02237 . .
02238 
02239 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_GPIO_IN_USE,
02240 PI_NOT_SERIAL_GPIO, or PI_BAD_SER_INVERT.
02241 
02242 The GPIO must be opened for bit bang reading of serial data using
02243 [*gpioSerialReadOpen*] prior to calling this function.
02244 D*/
02245 
02246 
02247 /*F*/
02248 int gpioSerialRead(unsigned user_gpio, void *buf, size_t bufSize);
02249 /*D
02250 This function copies up to bufSize bytes of data read from the
02251 bit bang serial cyclic buffer to the buffer starting at buf.
02252 
02253 . .
02254 user_gpio: 0-31, previously opened with [*gpioSerialReadOpen*]
02255       buf: an array to receive the read bytes
02256   bufSize: >=0
02257 . .
02258 
02259 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
02260 or PI_NOT_SERIAL_GPIO.
02261 
02262 The bytes returned for each character depend upon the number of
02263 data bits [*data_bits*] specified in the [*gpioSerialReadOpen*] command.
02264 
02265 For [*data_bits*] 1-8 there will be one byte per character. 
02266 For [*data_bits*] 9-16 there will be two bytes per character. 
02267 For [*data_bits*] 17-32 there will be four bytes per character.
02268 D*/
02269 
02270 
02271 /*F*/
02272 int gpioSerialReadClose(unsigned user_gpio);
02273 /*D
02274 This function closes a GPIO for bit bang reading of serial data.
02275 
02276 . .
02277 user_gpio: 0-31, previously opened with [*gpioSerialReadOpen*]
02278 . .
02279 
02280 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
02281 D*/
02282 
02283 /*F*/
02284 int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags);
02285 /*D
02286 This returns a handle for the device at the address on the I2C bus.
02287 
02288 . .
02289   i2cBus: >=0
02290  i2cAddr: 0-0x7F
02291 i2cFlags: 0
02292 . .
02293 
02294 No flags are currently defined.  This parameter should be set to zero.
02295 
02296 Physically buses 0 and 1 are available on the Pi.  Higher numbered buses
02297 will be available if a kernel supported bus multiplexor is being used.
02298 
02299 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
02300 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
02301 
02302 For the SMBus commands the low level transactions are shown at the end
02303 of the function description.  The following abbreviations are used.
02304 
02305 . .
02306 S      (1 bit) : Start bit
02307 P      (1 bit) : Stop bit
02308 Rd/Wr  (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
02309 A, NA  (1 bit) : Accept and not accept bit. 
02310 Addr   (7 bits): I2C 7 bit address.
02311 i2cReg (8 bits): Command byte, a byte which often selects a register.
02312 Data   (8 bits): A data byte.
02313 Count  (8 bits): A byte defining the length of a block operation.
02314 
02315 [..]: Data sent by the device.
02316 . .
02317 D*/
02318 
02319 
02320 /*F*/
02321 int i2cClose(unsigned handle);
02322 /*D
02323 This closes the I2C device associated with the handle.
02324 
02325 . .
02326 handle: >=0, as returned by a call to [*i2cOpen*]
02327 . .
02328 
02329 Returns 0 if OK, otherwise PI_BAD_HANDLE.
02330 D*/
02331 
02332 
02333 /*F*/
02334 int i2cWriteQuick(unsigned handle, unsigned bit);
02335 /*D
02336 This sends a single bit (in the Rd/Wr bit) to the device associated
02337 with handle.
02338 
02339 . .
02340 handle: >=0, as returned by a call to [*i2cOpen*]
02341    bit: 0-1, the value to write
02342 . .
02343 
02344 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02345 PI_I2C_WRITE_FAILED.
02346 
02347 Quick command. SMBus 2.0 5.5.1
02348 . .
02349 S Addr bit [A] P
02350 . .
02351 D*/
02352 
02353 
02354 /*F*/
02355 int i2cWriteByte(unsigned handle, unsigned bVal);
02356 /*D
02357 This sends a single byte to the device associated with handle.
02358 
02359 . .
02360 handle: >=0, as returned by a call to [*i2cOpen*]
02361   bVal: 0-0xFF, the value to write
02362 . .
02363 
02364 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02365 PI_I2C_WRITE_FAILED.
02366 
02367 Send byte. SMBus 2.0 5.5.2
02368 . .
02369 S Addr Wr [A] bVal [A] P
02370 . .
02371 D*/
02372 
02373 
02374 /*F*/
02375 int i2cReadByte(unsigned handle);
02376 /*D
02377 This reads a single byte from the device associated with handle.
02378 
02379 . .
02380 handle: >=0, as returned by a call to [*i2cOpen*]
02381 . .
02382 
02383 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
02384 or PI_I2C_READ_FAILED.
02385 
02386 Receive byte. SMBus 2.0 5.5.3
02387 . .
02388 S Addr Rd [A] [Data] NA P
02389 . .
02390 D*/
02391 
02392 
02393 /*F*/
02394 int i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal);
02395 /*D
02396 This writes a single byte to the specified register of the device
02397 associated with handle.
02398 
02399 . .
02400 handle: >=0, as returned by a call to [*i2cOpen*]
02401 i2cReg: 0-255, the register to write
02402   bVal: 0-0xFF, the value to write
02403 . .
02404 
02405 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02406 PI_I2C_WRITE_FAILED.
02407 
02408 Write byte. SMBus 2.0 5.5.4
02409 . .
02410 S Addr Wr [A] i2cReg [A] bVal [A] P
02411 . .
02412 D*/
02413 
02414 
02415 /*F*/
02416 int i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal);
02417 /*D
02418 This writes a single 16 bit word to the specified register of the device
02419 associated with handle.
02420 
02421 . .
02422 handle: >=0, as returned by a call to [*i2cOpen*]
02423 i2cReg: 0-255, the register to write
02424   wVal: 0-0xFFFF, the value to write
02425 . .
02426 
02427 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02428 PI_I2C_WRITE_FAILED.
02429 
02430 Write word. SMBus 2.0 5.5.4
02431 . .
02432 S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] P
02433 . .
02434 D*/
02435 
02436 
02437 /*F*/
02438 int i2cReadByteData(unsigned handle, unsigned i2cReg);
02439 /*D
02440 This reads a single byte from the specified register of the device
02441 associated with handle.
02442 
02443 . .
02444 handle: >=0, as returned by a call to [*i2cOpen*]
02445 i2cReg: 0-255, the register to read
02446 . .
02447 
02448 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
02449 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02450 
02451 Read byte. SMBus 2.0 5.5.5
02452 . .
02453 S Addr Wr [A] i2cReg [A] S Addr Rd [A] [Data] NA P
02454 . .
02455 D*/
02456 
02457 
02458 /*F*/
02459 int i2cReadWordData(unsigned handle, unsigned i2cReg);
02460 /*D
02461 This reads a single 16 bit word from the specified register of the device
02462 associated with handle.
02463 
02464 . .
02465 handle: >=0, as returned by a call to [*i2cOpen*]
02466 i2cReg: 0-255, the register to read
02467 . .
02468 
02469 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
02470 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02471 
02472 Read word. SMBus 2.0 5.5.5
02473 . .
02474 S Addr Wr [A] i2cReg [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P
02475 . .
02476 D*/
02477 
02478 
02479 /*F*/
02480 int i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal);
02481 /*D
02482 This writes 16 bits of data to the specified register of the device
02483 associated with handle and reads 16 bits of data in return.
02484 
02485 . .
02486 handle: >=0, as returned by a call to [*i2cOpen*]
02487 i2cReg: 0-255, the register to write/read
02488   wVal: 0-0xFFFF, the value to write
02489 . .
02490 
02491 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
02492 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02493 
02494 Process call. SMBus 2.0 5.5.6
02495 . .
02496 S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A]
02497    S Addr Rd [A] [DataLow] A [DataHigh] NA P
02498 . .
02499 D*/
02500 
02501 
02502 /*F*/
02503 int i2cWriteBlockData(
02504 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
02505 /*D
02506 This writes up to 32 bytes to the specified register of the device
02507 associated with handle.
02508 
02509 . .
02510 handle: >=0, as returned by a call to [*i2cOpen*]
02511 i2cReg: 0-255, the register to write
02512    buf: an array with the data to send
02513  count: 1-32, the number of bytes to write
02514 . .
02515 
02516 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02517 PI_I2C_WRITE_FAILED.
02518 
02519 Block write. SMBus 2.0 5.5.7
02520 . .
02521 S Addr Wr [A] i2cReg [A] count [A]
02522    buf0 [A] buf1 [A] ... [A] bufn [A] P
02523 . .
02524 D*/
02525 
02526 
02527 /*F*/
02528 int i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf);
02529 /*D
02530 This reads a block of up to 32 bytes from the specified register of
02531 the device associated with handle.
02532 
02533 . .
02534 handle: >=0, as returned by a call to [*i2cOpen*]
02535 i2cReg: 0-255, the register to read
02536    buf: an array to receive the read data
02537 . .
02538 
02539 The amount of returned data is set by the device.
02540 
02541 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
02542 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02543 
02544 Block read. SMBus 2.0 5.5.7
02545 . .
02546 S Addr Wr [A] i2cReg [A]
02547    S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P
02548 . .
02549 D*/
02550 
02551 
02552 /*F*/
02553 int i2cBlockProcessCall(
02554 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
02555 /*D
02556 This writes data bytes to the specified register of the device
02557 associated with handle and reads a device specified number
02558 of bytes of data in return.
02559 
02560 . .
02561 handle: >=0, as returned by a call to [*i2cOpen*]
02562 i2cReg: 0-255, the register to write/read
02563    buf: an array with the data to send and to receive the read data
02564  count: 1-32, the number of bytes to write
02565 . .
02566 
02567 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
02568 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02569 
02570 The SMBus 2.0 documentation states that a minimum of 1 byte may be
02571 sent and a minimum of 1 byte may be received.  The total number of
02572 bytes sent/received must be 32 or less.
02573 
02574 Block write-block read. SMBus 2.0 5.5.8
02575 . .
02576 S Addr Wr [A] i2cReg [A] count [A] buf0 [A] ... bufn [A]
02577    S Addr Rd [A] [Count] A [buf0] A ... [bufn] A P
02578 . .
02579 D*/
02580 
02581 
02582 /*F*/
02583 int i2cReadI2CBlockData(
02584 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
02585 /*D
02586 This reads count bytes from the specified register of the device
02587 associated with handle .  The count may be 1-32.
02588 
02589 . .
02590 handle: >=0, as returned by a call to [*i2cOpen*]
02591 i2cReg: 0-255, the register to read
02592    buf: an array to receive the read data
02593  count: 1-32, the number of bytes to read
02594 . .
02595 
02596 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
02597 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02598 
02599 . .
02600 S Addr Wr [A] i2cReg [A]
02601    S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
02602 . .
02603 D*/
02604 
02605 
02606 /*F*/
02607 int i2cWriteI2CBlockData(
02608 unsigned handle, unsigned i2cReg, char *buf, unsigned count);
02609 /*D
02610 This writes 1 to 32 bytes to the specified register of the device
02611 associated with handle.
02612 
02613 . .
02614 handle: >=0, as returned by a call to [*i2cOpen*]
02615 i2cReg: 0-255, the register to write
02616    buf: the data to write
02617  count: 1-32, the number of bytes to write
02618 . .
02619 
02620 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02621 PI_I2C_WRITE_FAILED.
02622 
02623 . .
02624 S Addr Wr [A] i2cReg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
02625 . .
02626 D*/
02627 
02628 /*F*/
02629 int i2cReadDevice(unsigned handle, char *buf, unsigned count);
02630 /*D
02631 This reads count bytes from the raw device into buf.
02632 
02633 . .
02634 handle: >=0, as returned by a call to [*i2cOpen*]
02635    buf: an array to receive the read data bytes
02636  count: >0, the number of bytes to read
02637 . .
02638 
02639 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02640 PI_I2C_READ_FAILED.
02641 
02642 . .
02643 S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
02644 . .
02645 D*/
02646 
02647 
02648 /*F*/
02649 int i2cWriteDevice(unsigned handle, char *buf, unsigned count);
02650 /*D
02651 This writes count bytes from buf to the raw device.
02652 
02653 . .
02654 handle: >=0, as returned by a call to [*i2cOpen*]
02655    buf: an array containing the data bytes to write
02656  count: >0, the number of bytes to write
02657 . .
02658 
02659 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02660 PI_I2C_WRITE_FAILED.
02661 
02662 . .
02663 S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
02664 . .
02665 D*/
02666 
02667 /*F*/
02668 void i2cSwitchCombined(int setting);
02669 /*D
02670 This sets the I2C (i2c-bcm2708) module "use combined transactions"
02671 parameter on or off.
02672 
02673 . .
02674 setting: 0 to set the parameter off, non-zero to set it on
02675 . .
02676 
02677 
02678 NOTE: when the flag is on a write followed by a read to the same
02679 slave address will use a repeated start (rather than a stop/start).
02680 D*/
02681 
02682 /*F*/
02683 int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs);
02684 /*D
02685 This function executes multiple I2C segments in one transaction by
02686 calling the I2C_RDWR ioctl.
02687 
02688 . .
02689  handle: >=0, as returned by a call to [*i2cOpen*]
02690    segs: an array of I2C segments
02691 numSegs: >0, the number of I2C segments
02692 . .
02693 
02694 Returns the number of segments if OK, otherwise PI_BAD_I2C_SEG.
02695 D*/
02696 
02697 /*F*/
02698 int i2cZip(
02699    unsigned handle,
02700    char    *inBuf,
02701    unsigned inLen,
02702    char    *outBuf,
02703    unsigned outLen);
02704 /*D
02705 This function executes a sequence of I2C operations.  The
02706 operations to be performed are specified by the contents of inBuf
02707 which contains the concatenated command codes and associated data.
02708 
02709 . .
02710 handle: >=0, as returned by a call to [*i2cOpen*]
02711  inBuf: pointer to the concatenated I2C commands, see below
02712  inLen: size of command buffer
02713 outBuf: pointer to buffer to hold returned data
02714 outLen: size of output buffer
02715 . .
02716 
02717 Returns >= 0 if OK (the number of bytes read), otherwise
02718 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
02719 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
02720 
02721 The following command codes are supported:
02722 
02723 Name    @ Cmd & Data @ Meaning
02724 End     @ 0          @ No more commands
02725 Escape  @ 1          @ Next P is two bytes
02726 On      @ 2          @ Switch combined flag on
02727 Off     @ 3          @ Switch combined flag off
02728 Address @ 4 P        @ Set I2C address to P
02729 Flags   @ 5 lsb msb  @ Set I2C flags to lsb + (msb << 8)
02730 Read    @ 6 P        @ Read P bytes of data
02731 Write   @ 7 P ...    @ Write P bytes of data
02732 
02733 The address, read, and write commands take a parameter P.
02734 Normally P is one byte (0-255).  If the command is preceded by
02735 the Escape command then P is two bytes (0-65535, least significant
02736 byte first).
02737 
02738 The address defaults to that associated with the handle.
02739 The flags default to 0.  The address and flags maintain their
02740 previous value until updated.
02741 
02742 The returned I2C data is stored in consecutive locations of outBuf.
02743 
02744 ...
02745 Set address 0x53, write 0x32, read 6 bytes
02746 Set address 0x1E, write 0x03, read 6 bytes
02747 Set address 0x68, write 0x1B, read 8 bytes
02748 End
02749 
02750 0x04 0x53   0x07 0x01 0x32   0x06 0x06
02751 0x04 0x1E   0x07 0x01 0x03   0x06 0x06
02752 0x04 0x68   0x07 0x01 0x1B   0x06 0x08
02753 0x00
02754 ...
02755 D*/
02756 
02757 /*F*/
02758 int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud);
02759 /*D
02760 This function selects a pair of GPIO for bit banging I2C at a
02761 specified baud rate.
02762 
02763 Bit banging I2C allows for certain operations which are not possible
02764 with the standard I2C driver.
02765 
02766 o baud rates as low as 50 
02767 o repeated starts 
02768 o clock stretching 
02769 o I2C on any pair of spare GPIO
02770 
02771 . .
02772  SDA: 0-31
02773  SCL: 0-31
02774 baud: 50-500000
02775 . .
02776 
02777 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
02778 PI_GPIO_IN_USE.
02779 
02780 NOTE:
02781 
02782 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected.  As
02783 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
02784 D*/
02785 
02786 /*F*/
02787 int bbI2CClose(unsigned SDA);
02788 /*D
02789 This function stops bit banging I2C on a pair of GPIO previously
02790 opened with [*bbI2COpen*].
02791 
02792 . .
02793 SDA: 0-31, the SDA GPIO used in a prior call to [*bbI2COpen*]
02794 . .
02795 
02796 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
02797 D*/
02798 
02799 /*F*/
02800 int bbI2CZip(
02801    unsigned SDA,
02802    char    *inBuf,
02803    unsigned inLen,
02804    char    *outBuf,
02805    unsigned outLen);
02806 /*D
02807 This function executes a sequence of bit banged I2C operations.  The
02808 operations to be performed are specified by the contents of inBuf
02809 which contains the concatenated command codes and associated data.
02810 
02811 . .
02812    SDA: 0-31 (as used in a prior call to [*bbI2COpen*])
02813  inBuf: pointer to the concatenated I2C commands, see below
02814  inLen: size of command buffer
02815 outBuf: pointer to buffer to hold returned data
02816 outLen: size of output buffer
02817 . .
02818 
02819 Returns >= 0 if OK (the number of bytes read), otherwise
02820 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
02821 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
02822 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
02823 
02824 The following command codes are supported:
02825 
02826 Name    @ Cmd & Data   @ Meaning
02827 End     @ 0            @ No more commands
02828 Escape  @ 1            @ Next P is two bytes
02829 Start   @ 2            @ Start condition
02830 Stop    @ 3            @ Stop condition
02831 Address @ 4 P          @ Set I2C address to P
02832 Flags   @ 5 lsb msb    @ Set I2C flags to lsb + (msb << 8)
02833 Read    @ 6 P          @ Read P bytes of data
02834 Write   @ 7 P ...      @ Write P bytes of data
02835 
02836 The address, read, and write commands take a parameter P.
02837 Normally P is one byte (0-255).  If the command is preceded by
02838 the Escape command then P is two bytes (0-65535, least significant
02839 byte first).
02840 
02841 The address and flags default to 0.  The address and flags maintain
02842 their previous value until updated.
02843 
02844 No flags are currently defined.
02845 
02846 The returned I2C data is stored in consecutive locations of outBuf.
02847 
02848 ...
02849 Set address 0x53
02850 start, write 0x32, (re)start, read 6 bytes, stop
02851 Set address 0x1E
02852 start, write 0x03, (re)start, read 6 bytes, stop
02853 Set address 0x68
02854 start, write 0x1B, (re)start, read 8 bytes, stop
02855 End
02856 
02857 0x04 0x53
02858 0x02 0x07 0x01 0x32   0x02 0x06 0x06 0x03
02859 
02860 0x04 0x1E
02861 0x02 0x07 0x01 0x03   0x02 0x06 0x06 0x03
02862 
02863 0x04 0x68
02864 0x02 0x07 0x01 0x1B   0x02 0x06 0x08 0x03
02865 
02866 0x00
02867 ...
02868 D*/
02869 
02870 /*F*/
02871 int bscXfer(bsc_xfer_t *bsc_xfer);
02872 /*D
02873 This function provides a low-level interface to the
02874 SPI/I2C Slave peripheral.  This peripheral allows the
02875 Pi to act as a slave device on an I2C or SPI bus.
02876 
02877 I can't get SPI to work properly.  I tried with a
02878 control word of 0x303 and swapped MISO and MOSI.
02879 
02880 The function sets the BSC mode, writes any data in
02881 the transmit buffer to the BSC transmit FIFO, and
02882 copies any data in the BSC receive FIFO to the
02883 receive buffer.
02884 
02885 . .
02886 bsc_xfer:= a structure defining the transfer
02887 
02888 typedef struct
02889 {
02890    uint32_t control;          // Write
02891    int rxCnt;                 // Read only
02892    char rxBuf[BSC_FIFO_SIZE]; // Read only
02893    int txCnt;                 // Write
02894    char txBuf[BSC_FIFO_SIZE]; // Write
02895 } bsc_xfer_t;
02896 . .
02897 
02898 To start a transfer set control (see below) and copy the bytes to
02899 be sent (if any) to txBuf and set the byte count in txCnt.
02900 
02901 Upon return rxCnt will be set to the number of received bytes placed
02902 in rxBuf.
02903 
02904 Note that the control word sets the BSC mode.  The BSC will stay in
02905 that mode until a different control word is sent.
02906 
02907 The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode
02908 and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode.  You
02909 need to swap MISO/MOSI between master and slave.
02910 
02911 When a zero control word is received GPIO 18-21 will be reset
02912 to INPUT mode.
02913 
02914 The returned function value is the status of the transfer (see below).
02915 
02916 If there was an error the status will be less than zero
02917 (and will contain the error code).
02918 
02919 The most significant word of the returned status contains the number
02920 of bytes actually copied from txBuf to the BSC transmit FIFO (may be
02921 less than requested if the FIFO already contained untransmitted data).
02922 
02923 control consists of the following bits.
02924 
02925 . .
02926 22 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
02927  a  a  a  a  a  a  a  -  - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN
02928 . .
02929 
02930 Bits 0-13 are copied unchanged to the BSC CR register.  See
02931 pages 163-165 of the Broadcom peripherals document for full
02932 details.
02933 
02934 aaaaaaa @ defines the I2C slave address (only relevant in I2C mode)
02935 IT      @ invert transmit status flags
02936 HC      @ enable host control
02937 TF      @ enable test FIFO
02938 IR      @ invert receive status flags
02939 RE      @ enable receive
02940 TE      @ enable transmit
02941 BK      @ abort operation and clear FIFOs
02942 EC      @ send control register as first I2C byte
02943 ES      @ send status register as first I2C byte
02944 PL      @ set SPI polarity high
02945 PH      @ set SPI phase high
02946 I2      @ enable I2C mode
02947 SP      @ enable SPI mode
02948 EN      @ enable BSC peripheral
02949 
02950 The returned status has the following format
02951 
02952 . .
02953 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
02954  S  S  S  S  S  R  R  R  R  R  T  T  T  T  T RB TE RF TF RE TB
02955 . .
02956 
02957 Bits 0-15 are copied unchanged from the BSC FR register.  See
02958 pages 165-166 of the Broadcom peripherals document for full
02959 details.
02960 
02961 SSSSS @ number of bytes successfully copied to transmit FIFO
02962 RRRRR @ number of bytes in receieve FIFO
02963 TTTTT @ number of bytes in transmit FIFO
02964 RB    @ receive busy
02965 TE    @ transmit FIFO empty
02966 RF    @ receive FIFO full
02967 TF    @ transmit FIFO full
02968 RE    @ receive FIFO empty
02969 TB    @ transmit busy
02970 
02971 The following example shows how to configure the BSC peripheral as
02972 an I2C slave with address 0x13 and send four bytes.
02973 
02974 ...
02975 bsc_xfer_t xfer;
02976 
02977 xfer.control = (0x13<<16) | 0x305;
02978 
02979 memcpy(xfer.txBuf, "ABCD", 4);
02980 xfer.txCnt = 4;
02981 
02982 status = bscXfer(&xfer);
02983 
02984 if (status >= 0)
02985 {
02986    // process transfer
02987 }
02988 ...
02989 D*/
02990 
02991 /*F*/
02992 int bbSPIOpen(
02993    unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK,
02994    unsigned baud, unsigned spiFlags);
02995 /*D
02996 This function selects a set of GPIO for bit banging SPI with
02997 a specified baud rate and mode.
02998 
02999 . .
03000       CS: 0-31
03001     MISO: 0-31
03002     MOSI: 0-31
03003     SCLK: 0-31
03004     baud: 50-250000
03005 spiFlags: see below
03006 . .
03007 
03008 spiFlags consists of the least significant 22 bits.
03009 
03010 . .
03011 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
03012  0  0  0  0  0  0  R  T  0  0  0  0  0  0  0  0  0  0  0  p  m  m
03013 . .
03014 
03015 mm defines the SPI mode, defaults to 0
03016 
03017 . .
03018 Mode CPOL CPHA
03019  0    0    0
03020  1    0    1
03021  2    1    0
03022  3    1    1
03023 . .
03024 
03025 p is 0 if CS is active low (default) and 1 for active high.
03026 
03027 T is 1 if the least significant bit is transmitted on MOSI first, the
03028 default (0) shifts the most significant bit out first.
03029 
03030 R is 1 if the least significant bit is received on MISO first, the
03031 default (0) receives the most significant bit first.
03032 
03033 The other bits in flags should be set to zero.
03034 
03035 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or
03036 PI_GPIO_IN_USE.
03037 
03038 If more than one device is connected to the SPI bus (defined by
03039 SCLK, MOSI, and MISO) each must have its own CS.
03040 
03041 ...
03042 bbSPIOpen(10, MISO, MOSI, SCLK, 10000, 0); // device 1
03043 bbSPIOpen(11, MISO, MOSI, SCLK, 20000, 3); // device 2
03044 ...
03045 D*/
03046 
03047 /*F*/
03048 int bbSPIClose(unsigned CS);
03049 /*D
03050 This function stops bit banging SPI on a set of GPIO
03051 opened with [*bbSPIOpen*].
03052 
03053 . .
03054 CS: 0-31, the CS GPIO used in a prior call to [*bbSPIOpen*]
03055 . .
03056 
03057 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO.
03058 D*/
03059 
03060 /*F*/
03061 int bbSPIXfer(
03062    unsigned CS,
03063    char    *inBuf,
03064    char    *outBuf,
03065    unsigned count);
03066 /*D
03067 This function executes a bit banged SPI transfer.
03068 
03069 . .
03070     CS: 0-31 (as used in a prior call to [*bbSPIOpen*])
03071  inBuf: pointer to buffer to hold data to be sent
03072 outBuf: pointer to buffer to hold returned data
03073  count: size of data transfer
03074 . .
03075 
03076 Returns >= 0 if OK (the number of bytes read), otherwise
03077 PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER.
03078 
03079 ...
03080 // gcc -Wall -pthread -o bbSPIx_test bbSPIx_test.c -lpigpio
03081 // sudo ./bbSPIx_test
03082 
03083 
03084 #include <stdio.h>
03085 
03086 #include "pigpio.h"
03087 
03088 #define CE0 5
03089 #define CE1 6
03090 #define MISO 13
03091 #define MOSI 19
03092 #define SCLK 12
03093 
03094 int main(int argc, char *argv[])
03095 {
03096    int i, count, set_val, read_val;
03097    unsigned char inBuf[3];
03098    char cmd1[] = {0, 0};
03099    char cmd2[] = {12, 0};
03100    char cmd3[] = {1, 128, 0};
03101 
03102    if (gpioInitialise() < 0)
03103    {
03104       fprintf(stderr, "pigpio initialisation failed.\n");
03105       return 1;
03106    }
03107 
03108    bbSPIOpen(CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC
03109    bbSPIOpen(CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC
03110 
03111    for (i=0; i<256; i++)
03112    {
03113       cmd1[1] = i;
03114 
03115       count = bbSPIXfer(CE0, cmd1, (char *)inBuf, 2); // > DAC
03116 
03117       if (count == 2)
03118       {
03119          count = bbSPIXfer(CE0, cmd2, (char *)inBuf, 2); // < DAC
03120 
03121          if (count == 2)
03122          {
03123             set_val = inBuf[1];
03124 
03125             count = bbSPIXfer(CE1, cmd3, (char *)inBuf, 3); // < ADC
03126 
03127             if (count == 3)
03128             {
03129                read_val = ((inBuf[1]&3)<<8) | inBuf[2];
03130                printf("%d %d\n", set_val, read_val);
03131             }
03132          }
03133       }
03134    }
03135 
03136    bbSPIClose(CE0);
03137    bbSPIClose(CE1);
03138 
03139    gpioTerminate();
03140 
03141    return 0;
03142 }
03143 ...
03144 D*/
03145 
03146 /*F*/
03147 int spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags);
03148 /*D
03149 This function returns a handle for the SPI device on the channel.
03150 Data will be transferred at baud bits per second.  The flags may
03151 be used to modify the default behaviour of 4-wire operation, mode 0,
03152 active low chip select.
03153 
03154 An auxiliary SPI device is available on all models but the
03155 A and B and may be selected by setting the A bit in the flags.
03156 The auxiliary device has 3 chip selects and a selectable word
03157 size in bits.
03158 
03159 . .
03160  spiChan: 0-1 (0-2 for the auxiliary SPI device)
03161     baud: 32K-125M (values above 30M are unlikely to work)
03162 spiFlags: see below
03163 . .
03164 
03165 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
03166 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
03167 
03168 spiFlags consists of the least significant 22 bits.
03169 
03170 . .
03171 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
03172  b  b  b  b  b  b  R  T  n  n  n  n  W  A u2 u1 u0 p2 p1 p0  m  m
03173 . .
03174 
03175 mm defines the SPI mode.
03176 
03177 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
03178 
03179 . .
03180 Mode POL PHA
03181  0    0   0
03182  1    0   1
03183  2    1   0
03184  3    1   1
03185 . .
03186 
03187 px is 0 if CEx is active low (default) and 1 for active high.
03188 
03189 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
03190 
03191 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
03192 
03193 W is 0 if the device is not 3-wire, 1 if the device is 3-wire.  Standard
03194 SPI device only.
03195 
03196 nnnn defines the number of bytes (0-15) to write before switching
03197 the MOSI line to MISO to read data.  This field is ignored
03198 if W is not set.  Standard SPI device only.
03199 
03200 T is 1 if the least significant bit is transmitted on MOSI first, the
03201 default (0) shifts the most significant bit out first.  Auxiliary SPI
03202 device only.
03203 
03204 R is 1 if the least significant bit is received on MISO first, the
03205 default (0) receives the most significant bit first.  Auxiliary SPI
03206 device only.
03207 
03208 bbbbbb defines the word size in bits (0-32).  The default (0)
03209 sets 8 bits per word.  Auxiliary SPI device only.
03210 
03211 The [*spiRead*], [*spiWrite*], and [*spiXfer*] functions
03212 transfer data packed into 1, 2, or 4 bytes according to
03213 the word size in bits.
03214 
03215 For bits 1-8 there will be one byte per word. 
03216 For bits 9-16 there will be two bytes per word. 
03217 For bits 17-32 there will be four bytes per word.
03218 
03219 Multi-byte transfers are made in least significant byte first order.
03220 
03221 E.g. to transfer 32 11-bit words buf should contain 64 bytes
03222 and count should be 64.
03223 
03224 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
03225 by 0x1A.
03226 
03227 The other bits in flags should be set to zero.
03228 D*/
03229 
03230 /*F*/
03231 int spiClose(unsigned handle);
03232 /*D
03233 This functions closes the SPI device identified by the handle.
03234 
03235 . .
03236 handle: >=0, as returned by a call to [*spiOpen*]
03237 . .
03238 
03239 Returns 0 if OK, otherwise PI_BAD_HANDLE.
03240 D*/
03241 
03242 
03243 /*F*/
03244 int spiRead(unsigned handle, char *buf, unsigned count);
03245 /*D
03246 This function reads count bytes of data from the SPI
03247 device associated with the handle.
03248 
03249 . .
03250 handle: >=0, as returned by a call to [*spiOpen*]
03251    buf: an array to receive the read data bytes
03252  count: the number of bytes to read
03253 . .
03254 
03255 Returns the number of bytes transferred if OK, otherwise
03256 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
03257 D*/
03258 
03259 
03260 /*F*/
03261 int spiWrite(unsigned handle, char *buf, unsigned count);
03262 /*D
03263 This function writes count bytes of data from buf to the SPI
03264 device associated with the handle.
03265 
03266 . .
03267 handle: >=0, as returned by a call to [*spiOpen*]
03268    buf: the data bytes to write
03269  count: the number of bytes to write
03270 . .
03271 
03272 Returns the number of bytes transferred if OK, otherwise
03273 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
03274 D*/
03275 
03276 /*F*/
03277 int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count);
03278 /*D
03279 This function transfers count bytes of data from txBuf to the SPI
03280 device associated with the handle.  Simultaneously count bytes of
03281 data are read from the device and placed in rxBuf.
03282 
03283 . .
03284 handle: >=0, as returned by a call to [*spiOpen*]
03285  txBuf: the data bytes to write
03286  rxBuf: the received data bytes
03287  count: the number of bytes to transfer
03288 . .
03289 
03290 Returns the number of bytes transferred if OK, otherwise
03291 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
03292 D*/
03293 
03294 
03295 /*F*/
03296 int serOpen(char *sertty, unsigned baud, unsigned serFlags);
03297 /*D
03298 This function opens a serial device at a specified baud rate
03299 and with specified flags.  The device name must start with
03300 /dev/tty or /dev/serial.
03301 
03302 . .
03303   sertty: the serial device to open
03304     baud: the baud rate in bits per second, see below
03305 serFlags: 0
03306 . .
03307 
03308 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
03309 PI_SER_OPEN_FAILED.
03310 
03311 The baud rate must be one of 50, 75, 110, 134, 150,
03312 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
03313 38400, 57600, 115200, or 230400.
03314 
03315 No flags are currently defined.  This parameter should be set to zero.
03316 D*/
03317 
03318 
03319 /*F*/
03320 int serClose(unsigned handle);
03321 /*D
03322 This function closes the serial device associated with handle.
03323 
03324 . .
03325 handle: >=0, as returned by a call to [*serOpen*]
03326 . .
03327 
03328 Returns 0 if OK, otherwise PI_BAD_HANDLE.
03329 D*/
03330 
03331 /*F*/
03332 int serWriteByte(unsigned handle, unsigned bVal);
03333 /*D
03334 This function writes bVal to the serial port associated with handle.
03335 
03336 . .
03337 handle: >=0, as returned by a call to [*serOpen*]
03338 . .
03339 
03340 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
03341 PI_SER_WRITE_FAILED.
03342 D*/
03343 
03344 /*F*/
03345 int serReadByte(unsigned handle);
03346 /*D
03347 This function reads a byte from the serial port associated with handle.
03348 
03349 . .
03350 handle: >=0, as returned by a call to [*serOpen*]
03351 . .
03352 
03353 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
03354 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
03355 
03356 If no data is ready PI_SER_READ_NO_DATA is returned.
03357 D*/
03358 
03359 /*F*/
03360 int serWrite(unsigned handle, char *buf, unsigned count);
03361 /*D
03362 This function writes count bytes from buf to the the serial port
03363 associated with handle.
03364 
03365 . .
03366 handle: >=0, as returned by a call to [*serOpen*]
03367    buf: the array of bytes to write
03368  count: the number of bytes to write
03369 . .
03370 
03371 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
03372 PI_SER_WRITE_FAILED.
03373 D*/
03374 
03375 
03376 /*F*/
03377 int serRead(unsigned handle, char *buf, unsigned count);
03378 /*D
03379 This function reads up count bytes from the the serial port
03380 associated with handle and writes them to buf.
03381 
03382 . .
03383 handle: >=0, as returned by a call to [*serOpen*]
03384    buf: an array to receive the read data
03385  count: the maximum number of bytes to read
03386 . .
03387 
03388 Returns the number of bytes read (>0=) if OK, otherwise PI_BAD_HANDLE,
03389 PI_BAD_PARAM, or PI_SER_READ_NO_DATA.
03390 
03391 If no data is ready zero is returned.
03392 D*/
03393 
03394 
03395 /*F*/
03396 int serDataAvailable(unsigned handle);
03397 /*D
03398 This function returns the number of bytes available
03399 to be read from the device associated with handle.
03400 
03401 . .
03402 handle: >=0, as returned by a call to [*serOpen*]
03403 . .
03404 
03405 Returns the number of bytes of data available (>=0) if OK,
03406 otherwise PI_BAD_HANDLE.
03407 D*/
03408 
03409 
03410 /*F*/
03411 int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level);
03412 /*D
03413 This function sends a trigger pulse to a GPIO.  The GPIO is set to
03414 level for pulseLen microseconds and then reset to not level.
03415 
03416 . .
03417 user_gpio: 0-31
03418  pulseLen: 1-100
03419     level: 0,1
03420 . .
03421 
03422 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
03423 or PI_BAD_PULSELEN.
03424 D*/
03425 
03426 
03427 /*F*/
03428 int gpioSetWatchdog(unsigned user_gpio, unsigned timeout);
03429 /*D
03430 Sets a watchdog for a GPIO.
03431 
03432 . .
03433 user_gpio: 0-31
03434   timeout: 0-60000
03435 . .
03436 
03437 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT.
03438 
03439 The watchdog is nominally in milliseconds.
03440 
03441 One watchdog may be registered per GPIO.
03442 
03443 The watchdog may be cancelled by setting timeout to 0.
03444 
03445 Until cancelled a timeout will be reported every timeout milliseconds
03446 after the last GPIO activity.
03447 
03448 In particular:
03449 
03450 1) any registered alert function for the GPIO will be called with
03451    the level set to PI_TIMEOUT.
03452 
03453 2) any notification for the GPIO will have a report written to the
03454    fifo with the flags set to indicate a watchdog timeout.
03455 
03456 ...
03457 void aFunction(int gpio, int level, uint32_t tick)
03458 {
03459    printf("GPIO %d became %d at %d", gpio, level, tick);
03460 }
03461 
03462 // call aFunction whenever GPIO 4 changes state
03463 gpioSetAlertFunc(4, aFunction);
03464 
03465 //  or approximately every 5 millis
03466 gpioSetWatchdog(4, 5);
03467 ...
03468 D*/
03469 
03470 
03471 /*F*/
03472 int gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active);
03473 /*D
03474 Sets a noise filter on a GPIO.
03475 
03476 Level changes on the GPIO are ignored until a level which has
03477 been stable for [*steady*] microseconds is detected.  Level changes
03478 on the GPIO are then reported for [*active*] microseconds after
03479 which the process repeats.
03480 
03481 . .
03482 user_gpio: 0-31
03483    steady: 0-300000
03484    active: 0-1000000
03485 . .
03486 
03487 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
03488 
03489 This filter affects the GPIO samples returned to callbacks set up
03490 with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*],
03491 and [*gpioSetGetSamplesFuncEx*].
03492 
03493 It does not affect interrupts set up with [*gpioSetISRFunc*],
03494 [*gpioSetISRFuncEx*], or levels read by [*gpioRead*],
03495 [*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*].
03496 
03497 Level changes before and after the active period may
03498 be reported.  Your software must be designed to cope with
03499 such reports.
03500 D*/
03501 
03502 
03503 /*F*/
03504 int gpioGlitchFilter(unsigned user_gpio, unsigned steady);
03505 /*D
03506 Sets a glitch filter on a GPIO.
03507 
03508 Level changes on the GPIO are not reported unless the level
03509 has been stable for at least [*steady*] microseconds.  The
03510 level is then reported.  Level changes of less than [*steady*]
03511 microseconds are ignored.
03512 
03513 . .
03514 user_gpio: 0-31
03515    steady: 0-300000
03516 . .
03517 
03518 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
03519 
03520 This filter affects the GPIO samples returned to callbacks set up
03521 with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*],
03522 and [*gpioSetGetSamplesFuncEx*].
03523 
03524 It does not affect interrupts set up with [*gpioSetISRFunc*],
03525 [*gpioSetISRFuncEx*], or levels read by [*gpioRead*],
03526 [*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*].
03527 
03528 Each (stable) edge will be timestamped [*steady*] microseconds
03529 after it was first detected.
03530 D*/
03531 
03532 
03533 /*F*/
03534 int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits);
03535 /*D
03536 Registers a function to be called (a callback) every millisecond
03537 with the latest GPIO samples.
03538 
03539 . .
03540    f: the function to call
03541 bits: the GPIO of interest
03542 . .
03543 
03544 Returns 0 if OK.
03545 
03546 The function is passed a pointer to the samples (an array of
03547 [*gpioSample_t*]),  and the number of samples.
03548 
03549 Only one function can be registered.
03550 
03551 The callback may be cancelled by passing NULL as the function.
03552 
03553 The samples returned will be the union of bits, plus any active alerts,
03554 plus any active notifications.
03555 
03556 e.g.  if there are alerts for GPIO 7, 8, and 9, notifications for GPIO
03557 8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for GPIO
03558 7, 8, 9, 10, 17, 23, and 24 will be reported.
03559 D*/
03560 
03561 
03562 /*F*/
03563 int gpioSetGetSamplesFuncEx(
03564    gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata);
03565 /*D
03566 Registers a function to be called (a callback) every millisecond
03567 with the latest GPIO samples.
03568 
03569 . .
03570        f: the function to call
03571     bits: the GPIO of interest
03572 userdata: a pointer to arbitrary user data
03573 . .
03574 
03575 Returns 0 if OK.
03576 
03577 The function is passed a pointer to the samples (an array of
03578 [*gpioSample_t*]), the number of samples, and the userdata pointer.
03579 
03580 Only one of [*gpioGetSamplesFunc*] or [*gpioGetSamplesFuncEx*] can be
03581 registered.
03582 
03583 See [*gpioSetGetSamplesFunc*] for further details.
03584 D*/
03585 
03586 
03587 /*F*/
03588 int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f);
03589 /*D
03590 Registers a function to be called (a callback) every millis milliseconds.
03591 
03592 . .
03593  timer: 0-9
03594 millis: 10-60000
03595      f: the function to call
03596 . .
03597 
03598 Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED.
03599 
03600 10 timers are supported numbered 0 to 9.
03601 
03602 One function may be registered per timer.
03603 
03604 The timer may be cancelled by passing NULL as the function.
03605 
03606 ...
03607 void bFunction(void)
03608 {
03609    printf("two seconds have elapsed");
03610 }
03611 
03612 // call bFunction every 2000 milliseconds
03613 gpioSetTimerFunc(0, 2000, bFunction);
03614 ...
03615 D*/
03616 
03617 
03618 /*F*/
03619 int gpioSetTimerFuncEx(
03620    unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata);
03621 /*D
03622 Registers a function to be called (a callback) every millis milliseconds.
03623 
03624 . .
03625    timer: 0-9.
03626   millis: 10-60000
03627        f: the function to call
03628 userdata: a pointer to arbitrary user data
03629 . .
03630 
03631 Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED.
03632 
03633 The function is passed the userdata pointer.
03634 
03635 Only one of [*gpioSetTimerFunc*] or [*gpioSetTimerFuncEx*] can be
03636 registered per timer.
03637 
03638 See [*gpioSetTimerFunc*] for further details.
03639 D*/
03640 
03641 
03642 /*F*/
03643 pthread_t *gpioStartThread(gpioThreadFunc_t f, void *userdata);
03644 /*D
03645 Starts a new thread of execution with f as the main routine.
03646 
03647 . .
03648        f: the main function for the new thread
03649 userdata: a pointer to arbitrary user data
03650 . .
03651 
03652 Returns a pointer to pthread_t if OK, otherwise NULL.
03653 
03654 The function is passed the single argument arg.
03655 
03656 The thread can be cancelled by passing the pointer to pthread_t to
03657 [*gpioStopThread*].
03658 
03659 ...
03660 #include <stdio.h>
03661 #include <pigpio.h>
03662 
03663 void *myfunc(void *arg)
03664 {
03665    while (1)
03666    {
03667       printf("%s", arg);
03668       sleep(1);
03669    }
03670 }
03671 
03672 int main(int argc, char *argv[])
03673 {
03674    pthread_t *p1, *p2, *p3;
03675 
03676    if (gpioInitialise() < 0) return 1;
03677 
03678    p1 = gpioStartThread(myfunc, "thread 1"); sleep(3);
03679 
03680    p2 = gpioStartThread(myfunc, "thread 2"); sleep(3);
03681 
03682    p3 = gpioStartThread(myfunc, "thread 3"); sleep(3);
03683 
03684    gpioStopThread(p3); sleep(3);
03685 
03686    gpioStopThread(p2); sleep(3);
03687 
03688    gpioStopThread(p1); sleep(3);
03689 
03690    gpioTerminate();
03691 }
03692 ...
03693 D*/
03694 
03695 
03696 /*F*/
03697 void gpioStopThread(pthread_t *pth);
03698 /*D
03699 Cancels the thread pointed at by pth.
03700 
03701 . .
03702 pth: a thread pointer returned by [*gpioStartThread*]
03703 . .
03704 
03705 No value is returned.
03706 
03707 The thread to be stopped should have been started with [*gpioStartThread*].
03708 D*/
03709 
03710 
03711 /*F*/
03712 int gpioStoreScript(char *script);
03713 /*D
03714 This function stores a null terminated script for later execution.
03715 
03716 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
03717 
03718 . .
03719 script: the text of the script
03720 . .
03721 
03722 The function returns a script id if the script is valid,
03723 otherwise PI_BAD_SCRIPT.
03724 D*/
03725 
03726 
03727 /*F*/
03728 int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param);
03729 /*D
03730 This function runs a stored script.
03731 
03732 . .
03733 script_id: >=0, as returned by [*gpioStoreScript*]
03734    numPar: 0-10, the number of parameters
03735     param: an array of parameters
03736 . .
03737 
03738 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
03739 PI_TOO_MANY_PARAM.
03740 
03741 param is an array of up to 10 parameters which may be referenced in
03742 the script as p0 to p9.
03743 D*/
03744 
03745 /*F*/
03746 int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param);
03747 /*D
03748 This function runs a stored script.
03749 
03750 . .
03751 script_id: >=0, as returned by [*gpioStoreScript*]
03752    numPar: 0-10, the number of parameters
03753     param: an array of parameters
03754 . .
03755 
03756 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
03757 PI_TOO_MANY_PARAM.
03758 
03759 param is an array of up to 10 parameters which may be referenced in
03760 the script as p0 to p9.
03761 D*/
03762 
03763 
03764 
03765 /*F*/
03766 int gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param);
03767 /*D
03768 This function sets the parameters of a script.  The script may or
03769 may not be running.  The first numPar parameters of the script are
03770 overwritten with the new values.
03771 
03772 . .
03773 script_id: >=0, as returned by [*gpioStoreScript*]
03774    numPar: 0-10, the number of parameters
03775     param: an array of parameters
03776 . .
03777 
03778 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
03779 PI_TOO_MANY_PARAM.
03780 
03781 param is an array of up to 10 parameters which may be referenced in
03782 the script as p0 to p9.
03783 D*/
03784 
03785 
03786 /*F*/
03787 int gpioScriptStatus(unsigned script_id, uint32_t *param);
03788 /*D
03789 This function returns the run status of a stored script as well as
03790 the current values of parameters 0 to 9.
03791 
03792 . .
03793 script_id: >=0, as returned by [*gpioStoreScript*]
03794     param: an array to hold the returned 10 parameters
03795 . .
03796 
03797 The function returns greater than or equal to 0 if OK,
03798 otherwise PI_BAD_SCRIPT_ID.
03799 
03800 The run status may be
03801 
03802 . .
03803 PI_SCRIPT_INITING
03804 PI_SCRIPT_HALTED
03805 PI_SCRIPT_RUNNING
03806 PI_SCRIPT_WAITING
03807 PI_SCRIPT_FAILED
03808 . .
03809 
03810 The current value of script parameters 0 to 9 are returned in param.
03811 D*/
03812 
03813 
03814 /*F*/
03815 int gpioStopScript(unsigned script_id);
03816 /*D
03817 This function stops a running script.
03818 
03819 . .
03820 script_id: >=0, as returned by [*gpioStoreScript*]
03821 . .
03822 
03823 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
03824 D*/
03825 
03826 
03827 /*F*/
03828 int gpioDeleteScript(unsigned script_id);
03829 /*D
03830 This function deletes a stored script.
03831 
03832 . .
03833 script_id: >=0, as returned by [*gpioStoreScript*]
03834 . .
03835 
03836 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
03837 D*/
03838 
03839 
03840 /*F*/
03841 int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f);
03842 /*D
03843 Registers a function to be called (a callback) when a signal occurs.
03844 
03845 . .
03846 signum: 0-63
03847      f: the callback function
03848 . .
03849 
03850 Returns 0 if OK, otherwise PI_BAD_SIGNUM.
03851 
03852 The function is passed the signal number.
03853 
03854 One function may be registered per signal.
03855 
03856 The callback may be cancelled by passing NULL.
03857 
03858 By default all signals are treated as fatal and cause the library
03859 to call gpioTerminate and then exit.
03860 D*/
03861 
03862 
03863 /*F*/
03864 int gpioSetSignalFuncEx(
03865    unsigned signum, gpioSignalFuncEx_t f, void *userdata);
03866 /*D
03867 Registers a function to be called (a callback) when a signal occurs.
03868 
03869 . .
03870   signum: 0-63
03871        f: the callback function
03872 userdata: a pointer to arbitrary user data
03873 . .
03874 
03875 Returns 0 if OK, otherwise PI_BAD_SIGNUM.
03876 
03877 The function is passed the signal number and the userdata pointer.
03878 
03879 Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be
03880 registered per signal.
03881 
03882 See gpioSetSignalFunc for further details.
03883 D*/
03884 
03885 
03886 /*F*/
03887 uint32_t gpioRead_Bits_0_31(void);
03888 /*D
03889 Returns the current level of GPIO 0-31.
03890 D*/
03891 
03892 
03893 /*F*/
03894 uint32_t gpioRead_Bits_32_53(void);
03895 /*D
03896 Returns the current level of GPIO 32-53.
03897 D*/
03898 
03899 
03900 /*F*/
03901 int gpioWrite_Bits_0_31_Clear(uint32_t bits);
03902 /*D
03903 Clears GPIO 0-31 if the corresponding bit in bits is set.
03904 
03905 . .
03906 bits: a bit mask of GPIO to clear
03907 . .
03908 
03909 Returns 0 if OK.
03910 
03911 ...
03912 // To clear (set to 0) GPIO 4, 7, and 15
03913 gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) );
03914 ...
03915 D*/
03916 
03917 
03918 /*F*/
03919 int gpioWrite_Bits_32_53_Clear(uint32_t bits);
03920 /*D
03921 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
03922 
03923 . .
03924 bits: a bit mask of GPIO to clear
03925 . .
03926 
03927 Returns 0 if OK.
03928 D*/
03929 
03930 
03931 /*F*/
03932 int gpioWrite_Bits_0_31_Set(uint32_t bits);
03933 /*D
03934 Sets GPIO 0-31 if the corresponding bit in bits is set.
03935 
03936 . .
03937 bits: a bit mask of GPIO to set
03938 . .
03939 
03940 Returns 0 if OK.
03941 D*/
03942 
03943 
03944 /*F*/
03945 int gpioWrite_Bits_32_53_Set(uint32_t bits);
03946 /*D
03947 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
03948 
03949 . .
03950 bits: a bit mask of GPIO to set
03951 . .
03952 
03953 Returns 0 if OK.
03954 
03955 ...
03956 // To set (set to 1) GPIO 32, 40, and 53
03957 gpioWrite_Bits_32_53_Set((1<<(32-32)) | (1<<(40-32)) | (1<<(53-32)));
03958 ...
03959 D*/
03960 
03961 /*F*/
03962 int gpioHardwareClock(unsigned gpio, unsigned clkfreq);
03963 /*D
03964 Starts a hardware clock on a GPIO at the specified frequency.
03965 Frequencies above 30MHz are unlikely to work.
03966 
03967 . .
03968    gpio: see description
03969 clkfreq: 0 (off) or 4689-250000000 (250M)
03970 . .
03971 
03972 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HCLK_GPIO,
03973 PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
03974 
03975 The same clock is available on multiple GPIO.  The latest
03976 frequency setting will be used by all GPIO which share a clock.
03977 
03978 The GPIO must be one of the following.
03979 
03980 . .
03981 4   clock 0  All models
03982 5   clock 1  All models but A and B (reserved for system use)
03983 6   clock 2  All models but A and B
03984 20  clock 0  All models but A and B
03985 21  clock 1  All models but A and Rev.2 B (reserved for system use)
03986 
03987 32  clock 0  Compute module only
03988 34  clock 0  Compute module only
03989 42  clock 1  Compute module only (reserved for system use)
03990 43  clock 2  Compute module only
03991 44  clock 1  Compute module only (reserved for system use)
03992 . .
03993 
03994 Access to clock 1 is protected by a password as its use will likely
03995 crash the Pi.  The password is given by or'ing 0x5A000000 with the
03996 GPIO number.
03997 D*/
03998 
03999 /*F*/
04000 int gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty);
04001 /*D
04002 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
04003 Frequencies above 30MHz are unlikely to work.
04004 
04005 NOTE: Any waveform started by [*gpioWaveTxSend*], or
04006 [*gpioWaveChain*] will be cancelled.
04007 
04008 This function is only valid if the pigpio main clock is PCM.  The
04009 main clock defaults to PCM but may be overridden by a call to
04010 [*gpioCfgClock*].
04011 
04012 . .
04013    gpio: see description
04014 PWMfreq: 0 (off) or 1-125000000 (125M)
04015 PWMduty: 0 (off) to 1000000 (1M)(fully on)
04016 . .
04017 
04018 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HPWM_GPIO,
04019 PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, or PI_HPWM_ILLEGAL.
04020 
04021 The same PWM channel is available on multiple GPIO.  The latest
04022 frequency and dutycycle setting will be used by all GPIO which
04023 share a PWM channel.
04024 
04025 The GPIO must be one of the following.
04026 
04027 . .
04028 12  PWM channel 0  All models but A and B
04029 13  PWM channel 1  All models but A and B
04030 18  PWM channel 0  All models
04031 19  PWM channel 1  All models but A and B
04032 
04033 40  PWM channel 0  Compute module only
04034 41  PWM channel 1  Compute module only
04035 45  PWM channel 1  Compute module only
04036 52  PWM channel 0  Compute module only
04037 53  PWM channel 1  Compute module only
04038 . .
04039 
04040 The actual number of steps beween off and fully on is the
04041 integral part of 250 million divided by PWMfreq.
04042 
04043 The actual frequency set is 250 million / steps.
04044 
04045 There will only be a million steps for a PWMfreq of 250.
04046 Lower frequencies will have more steps and higher
04047 frequencies will have fewer steps.  PWMduty is
04048 automatically scaled to take this into account.
04049 D*/
04050 
04051 /*F*/
04052 int gpioTime(unsigned timetype, int *seconds, int *micros);
04053 /*D
04054 Updates the seconds and micros variables with the current time.
04055 
04056 . .
04057 timetype: 0 (relative), 1 (absolute)
04058  seconds: a pointer to an int to hold seconds
04059   micros: a pointer to an int to hold microseconds
04060 . .
04061 
04062 Returns 0 if OK, otherwise PI_BAD_TIMETYPE.
04063 
04064 If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the
04065 number of seconds and microseconds since the epoch (1st January 1970).
04066 
04067 If timetype is PI_TIME_RELATIVE updates seconds and micros with the
04068 number of seconds and microseconds since the library was initialised.
04069 
04070 ...
04071 int secs, mics;
04072 
04073 // print the number of seconds since the library was started
04074 gpioTime(PI_TIME_RELATIVE, &secs, &mics);
04075 printf("library started %d.%03d seconds ago", secs, mics/1000);
04076 ...
04077 D*/
04078 
04079 
04080 /*F*/
04081 int gpioSleep(unsigned timetype, int seconds, int micros);
04082 /*D
04083 Sleeps for the number of seconds and microseconds specified by seconds
04084 and micros.
04085 
04086 . .
04087 timetype: 0 (relative), 1 (absolute)
04088  seconds: seconds to sleep
04089   micros: microseconds to sleep
04090 . .
04091 
04092 Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS,
04093 or PI_BAD_MICROS.
04094 
04095 If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds
04096 and microseconds since the epoch (1st January 1970) has elapsed.  System
04097 clock changes are taken into account.
04098 
04099 If timetype is PI_TIME_RELATIVE the sleep is for the specified number
04100 of seconds and microseconds.  System clock changes do not effect the
04101 sleep length.
04102 
04103 For short delays (say, 50 microseonds or less) use [*gpioDelay*].
04104 
04105 ...
04106 gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds
04107 
04108 gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 0.1 seconds
04109 
04110 gpioSleep(PI_TIME_RELATIVE, 60, 0);     // sleep for one minute
04111 ...
04112 D*/
04113 
04114 
04115 /*F*/
04116 uint32_t gpioDelay(uint32_t micros);
04117 /*D
04118 Delays for at least the number of microseconds specified by micros.
04119 
04120 . .
04121 micros: the number of microseconds to sleep
04122 . .
04123 
04124 Returns the actual length of the delay in microseconds.
04125 
04126 Delays of 100 microseconds or less use busy waits.
04127 D*/
04128 
04129 
04130 /*F*/
04131 uint32_t gpioTick(void);
04132 /*D
04133 Returns the current system tick.
04134 
04135 Tick is the number of microseconds since system boot.
04136 
04137 As tick is an unsigned 32 bit quantity it wraps around after
04138 2^32 microseconds, which is approximately 1 hour 12 minutes.
04139 
04140 You don't need to worry about the wrap around as long as you
04141 take a tick (uint32_t) from another tick, i.e. the following
04142 code will always provide the correct difference.
04143 
04144 ...
04145 uint32_t startTick, endTick;
04146 int diffTick;
04147 
04148 startTick = gpioTick();
04149 
04150 // do some processing
04151 
04152 endTick = gpioTick();
04153 
04154 diffTick = endTick - startTick;
04155 
04156 printf("some processing took %d microseconds", diffTick);
04157 ...
04158 D*/
04159 
04160 
04161 /*F*/
04162 unsigned gpioHardwareRevision(void);
04163 /*D
04164 Returns the hardware revision.
04165 
04166 If the hardware revision can not be found or is not a valid hexadecimal
04167 number the function returns 0.
04168 
04169 The hardware revision is the last few characters on the Revision line of
04170 /proc/cpuinfo.
04171 
04172 The revision number can be used to determine the assignment of GPIO
04173 to pins (see [*gpio*]).
04174 
04175 There are at least three types of board.
04176 
04177 Type 1 boards have hardware revision numbers of 2 and 3.
04178 
04179 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
04180 
04181 Type 3 boards have hardware revision numbers of 16 or greater.
04182 
04183 for "Revision       : 0002" the function returns 2. 
04184 for "Revision       : 000f" the function returns 15. 
04185 for "Revision       : 000g" the function returns 0.
04186 D*/
04187 
04188 
04189 /*F*/
04190 unsigned gpioVersion(void);
04191 /*D
04192 Returns the pigpio version.
04193 D*/
04194 
04195 
04196 /*F*/
04197 int gpioGetPad(unsigned pad);
04198 /*D
04199 This function returns the pad drive strength in mA.
04200 
04201 . .
04202 pad: 0-2, the pad to get
04203 . .
04204 
04205 Returns the pad drive strength if OK, otherwise PI_BAD_PAD.
04206 
04207 Pad @ GPIO
04208 0   @ 0-27
04209 1   @ 28-45
04210 2   @ 46-53
04211 
04212 ...
04213 strength = gpioGetPad(1); // get pad 1 strength
04214 ...
04215 D*/
04216 
04217 
04218 /*F*/
04219 int gpioSetPad(unsigned pad, unsigned padStrength);
04220 /*D
04221 This function sets the pad drive strength in mA.
04222 
04223 . .
04224         pad: 0-2, the pad to set
04225 padStrength: 1-16 mA
04226 . .
04227 
04228 Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH.
04229 
04230 Pad @ GPIO
04231 0   @ 0-27
04232 1   @ 28-45
04233 2   @ 46-53
04234 
04235 ...
04236 gpioSetPad(0, 16); // set pad 0 strength to 16 mA
04237 ...
04238 D*/
04239 
04240 /*F*/
04241 int eventMonitor(unsigned handle, uint32_t bits);
04242 /*D
04243 This function selects the events to be reported on a previously
04244 opened handle.
04245 
04246 . .
04247 handle: >=0, as returned by [*gpioNotifyOpen*]
04248   bits: a bit mask indicating the events of interest
04249 . .
04250 
04251 Returns 0 if OK, otherwise PI_BAD_HANDLE.
04252 
04253 A report is sent each time an event is triggered providing the
04254 corresponding bit in bits is set.
04255 
04256 See [*gpioNotifyBegin*] for the notification format.
04257 
04258 ...
04259 // Start reporting events 3, 6, and 7.
04260 
04261 //  bit      76543210
04262 // (0xC8 = 0b11001000)
04263 
04264 eventMonitor(h, 0xC8);
04265 ...
04266 
04267 D*/
04268 
04269 /*F*/
04270 int eventSetFunc(unsigned event, eventFunc_t f);
04271 /*D
04272 Registers a function to be called (a callback) when the specified
04273 event occurs.
04274 
04275 . .
04276 event: 0-31
04277     f: the callback function
04278 . .
04279 
04280 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
04281 
04282 One function may be registered per event.
04283 
04284 The function is passed the event, and the tick.
04285 
04286 The callback may be cancelled by passing NULL as the function.
04287 D*/
04288 
04289 /*F*/
04290 int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata);
04291 /*D
04292 Registers a function to be called (a callback) when the specified
04293 event occurs.
04294 
04295 . .
04296    event: 0-31
04297        f: the callback function
04298 userdata: pointer to arbitrary user data
04299 . .
04300 
04301 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
04302 
04303 One function may be registered per event.
04304 
04305 The function is passed the event, the tick, and the ueserdata pointer.
04306 
04307 The callback may be cancelled by passing NULL as the function.
04308 
04309 Only one of [*eventSetFunc*] or [*eventSetFuncEx*] can be
04310 registered per event.
04311 D*/
04312 
04313 /*F*/
04314 int eventTrigger(unsigned event);
04315 /*D
04316 This function signals the occurrence of an event.
04317 
04318 . .
04319 event: 0-31, the event
04320 . .
04321 
04322 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
04323 
04324 An event is a signal used to inform one or more consumers
04325 to start an action.  Each consumer which has registered an interest
04326 in the event (e.g. by calling [*eventSetFunc*]) will be informed by
04327 a callback.
04328 
04329 One event, PI_EVENT_BSC (31) is predefined.  This event is
04330 auto generated on BSC slave activity.
04331 
04332 The meaning of other events is arbitrary.
04333 
04334 Note that other than its id and its tick there is no data associated
04335 with an event.
04336 D*/
04337 
04338 
04339 /*F*/
04340 int shell(char *scriptName, char *scriptString);
04341 /*D
04342 This function uses the system call to execute a shell script
04343 with the given string as its parameter.
04344 
04345 . .
04346   scriptName: the name of the script, only alphanumeric characters,
04347               '-' and '_' are allowed in the name
04348 scriptString: the string to pass to the script
04349 . .
04350 
04351 The exit status of the system call is returned if OK, otherwise
04352 PI_BAD_SHELL_STATUS.
04353 
04354 scriptName must exist in /opt/pigpio/cgi and must be executable.
04355 
04356 The returned exit status is normally 256 times that set by the
04357 shell script exit function.  If the script can't be found 32512 will
04358 be returned.
04359 
04360 The following table gives some example returned statuses.
04361 
04362 Script exit status @ Returned system call status
04363 1                  @ 256
04364 5                  @ 1280
04365 10                 @ 2560
04366 200                @ 51200
04367 script not found   @ 32512
04368 
04369 ...
04370 // pass two parameters, hello and world
04371 status = shell("scr1", "hello world");
04372 
04373 // pass three parameters, hello, string with spaces, and world
04374 status = shell("scr1", "hello 'string with spaces' world");
04375 
04376 // pass one parameter, hello string with spaces world
04377 status = shell("scr1", "\"hello string with spaces world\"");
04378 ...
04379 D*/
04380 
04381 #pragma GCC diagnostic push
04382 
04383 #pragma GCC diagnostic ignored "-Wcomment"
04384 
04385 /*F*/
04386 int fileOpen(char *file, unsigned mode);
04387 /*D
04388 This function returns a handle to a file opened in a specified mode.
04389 
04390 . .
04391 file: the file to open
04392 mode: the file open mode
04393 . .
04394 
04395 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS,
04396 PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR.
04397 
04398 File
04399 
04400 A file may only be opened if permission is granted by an entry in
04401 /opt/pigpio/access.  This is intended to allow remote access to files
04402 in a more or less controlled manner.
04403 
04404 Each entry in /opt/pigpio/access takes the form of a file path
04405 which may contain wildcards followed by a single letter permission.
04406 The permission may be R for read, W for write, U for read/write,
04407 and N for no access.
04408 
04409 Where more than one entry matches a file the most specific rule
04410 applies.  If no entry matches a file then access is denied.
04411 
04412 Suppose /opt/pigpio/access contains the following entries
04413 
04414 . .
04415 /home/* n
04416 /home/pi/shared/dir_1/* w
04417 /home/pi/shared/dir_2/* r
04418 /home/pi/shared/dir_3/* u
04419 /home/pi/shared/dir_1/file.txt n
04420 . .
04421 
04422 Files may be written in directory dir_1 with the exception
04423 of file.txt.
04424 
04425 Files may be read in directory dir_2.
04426 
04427 Files may be read and written in directory dir_3.
04428 
04429 If a directory allows read, write, or read/write access then files may
04430 be created in that directory.
04431 
04432 In an attempt to prevent risky permissions the following paths are
04433 ignored in /opt/pigpio/access.
04434 
04435 . .
04436 a path containing ..
04437 a path containing only wildcards (*?)
04438 a path containing less than two non-wildcard parts
04439 . .
04440 
04441 Mode
04442 
04443 The mode may have the following values.
04444 
04445 Macro         @ Value @ Meaning
04446 PI_FILE_READ  @   1   @ open file for reading
04447 PI_FILE_WRITE @   2   @ open file for writing
04448 PI_FILE_RW    @   3   @ open file for reading and writing
04449 
04450 The following values may be or'd into the mode.
04451 
04452 Macro          @ Value @ Meaning
04453 PI_FILE_APPEND @ 4     @ Writes append data to the end of the file
04454 PI_FILE_CREATE @ 8     @ The file is created if it doesn't exist
04455 PI_FILE_TRUNC  @ 16    @ The file is truncated
04456 
04457 Newly created files are owned by root with permissions owner read and write.
04458 
04459 ...
04460 #include <stdio.h>
04461 #include <pigpio.h>
04462 
04463 int main(int argc, char *argv[])
04464 {
04465    int handle, c;
04466    char buf[60000];
04467 
04468    if (gpioInitialise() < 0) return 1;
04469 
04470    // assumes /opt/pigpio/access contains the following line
04471    // /ram/*.c r
04472 
04473    handle = fileOpen("/ram/pigpio.c", PI_FILE_READ);
04474 
04475    if (handle >= 0)
04476    {
04477       while ((c=fileRead(handle, buf, sizeof(buf)-1)))
04478       {
04479          buf[c] = 0;
04480          printf("%s", buf);
04481       }
04482 
04483       fileClose(handle);
04484    }
04485 
04486    gpioTerminate();
04487 }
04488 ...
04489 D*/
04490 
04491 #pragma GCC diagnostic pop
04492 
04493 /*F*/
04494 int fileClose(unsigned handle);
04495 /*D
04496 This function closes the file associated with handle.
04497 
04498 . .
04499 handle: >=0, as returned by a call to [*fileOpen*]
04500 . .
04501 
04502 Returns 0 if OK, otherwise PI_BAD_HANDLE.
04503 
04504 ...
04505 fileClose(h);
04506 ...
04507 D*/
04508 
04509 
04510 /*F*/
04511 int fileWrite(unsigned handle, char *buf, unsigned count);
04512 /*D
04513 This function writes count bytes from buf to the the file
04514 associated with handle.
04515 
04516 . .
04517 handle: >=0, as returned by a call to [*fileOpen*]
04518    buf: the array of bytes to write
04519  count: the number of bytes to write
04520 . .
04521 
04522 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM,
04523 PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE.
04524 
04525 ...
04526 status = fileWrite(h, buf, count);
04527 if (status == 0)
04528 {
04529    // okay
04530 }
04531 else
04532 {
04533    // error
04534 }
04535 ...
04536 D*/
04537 
04538 
04539 /*F*/
04540 int fileRead(unsigned handle, char *buf, unsigned count);
04541 /*D
04542 This function reads up to count bytes from the the file
04543 associated with handle and writes them to buf.
04544 
04545 . .
04546 handle: >=0, as returned by a call to [*fileOpen*]
04547    buf: an array to receive the read data
04548  count: the maximum number of bytes to read
04549 . .
04550 
04551 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.
04552 
04553 ...
04554 if (fileRead(h, buf, sizeof(buf)) > 0)
04555 {
04556    // process read data
04557 }
04558 ...
04559 D*/
04560 
04561 
04562 /*F*/
04563 int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom);
04564 /*D
04565 This function seeks to a position within the file associated
04566 with handle.
04567 
04568 . .
04569     handle: >=0, as returned by a call to [*fileOpen*]
04570 seekOffset: the number of bytes to move.  Positive offsets
04571             move forward, negative offsets backwards.
04572   seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1),
04573             or PI_FROM_END (2)
04574 . .
04575 
04576 Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK.
04577 
04578 ...
04579 fileSeek(0, 20, PI_FROM_START); // Seek to start plus 20
04580 
04581 size = fileSeek(0, 0, PI_FROM_END); // Seek to end, return size
04582 
04583 pos = fileSeek(0, 0, PI_FROM_CURRENT); // Return current position
04584 ...
04585 D*/
04586 
04587 #pragma GCC diagnostic push
04588 
04589 #pragma GCC diagnostic ignored "-Wcomment"
04590 
04591 /*F*/
04592 int fileList(char *fpat,  char *buf, unsigned count);
04593 /*D
04594 This function returns a list of files which match a pattern.  The
04595 pattern may contain wildcards.
04596 
04597 . .
04598  fpat: file pattern to match
04599   buf: an array to receive the matching file names
04600 count: the maximum number of bytes to read
04601 . .
04602 
04603 Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS,
04604 or PI_NO_FILE_MATCH.
04605 
04606 The pattern must match an entry in /opt/pigpio/access.  The pattern
04607 may contain wildcards.  See [*fileOpen*].
04608 
04609 NOTE
04610 
04611 The returned value is not the number of files, it is the number
04612 of bytes in the buffer.  The file names are separated by newline
04613 characters.
04614 
04615 ...
04616 #include <stdio.h>
04617 #include <pigpio.h>
04618 
04619 int main(int argc, char *argv[])
04620 {
04621    int c;
04622    char buf[1000];
04623 
04624    if (gpioInitialise() < 0) return 1;
04625 
04626    // assumes /opt/pigpio/access contains the following line
04627    // /ram/*.c r
04628 
04629    c = fileList("/ram/p*.c", buf, sizeof(buf));
04630 
04631    if (c >= 0)
04632    {
04633       // terminate string
04634       buf[c] = 0;
04635       printf("%s", buf);
04636    }
04637 
04638    gpioTerminate();
04639 }
04640 ...
04641 D*/
04642 
04643 #pragma GCC diagnostic pop
04644 
04645 
04646 /*F*/
04647 int gpioCfgBufferSize(unsigned cfgMillis);
04648 /*D
04649 Configures pigpio to buffer cfgMillis milliseconds of GPIO samples.
04650 
04651 This function is only effective if called before [*gpioInitialise*].
04652 
04653 . .
04654 cfgMillis: 100-10000
04655 . .
04656 
04657 The default setting is 120 milliseconds.
04658 
04659 The intention is to allow for bursts of data and protection against
04660 other processes hogging cpu time.
04661 
04662 I haven't seen a process locked out for more than 100 milliseconds.
04663 
04664 Making the buffer bigger uses a LOT of memory at the more frequent
04665 sampling rates as shown in the following table in MBs.
04666 
04667 . .
04668                      buffer milliseconds
04669                120 250 500 1sec 2sec 4sec 8sec
04670 
04671          1      16  31  55  107  ---  ---  ---
04672          2      10  18  31   55  107  ---  ---
04673 sample   4       8  12  18   31   55  107  ---
04674  rate    5       8  10  14   24   45   87  ---
04675  (us)    8       6   8  12   18   31   55  107
04676         10       6   8  10   14   24   45   87
04677 . .
04678 D*/
04679 
04680 
04681 /*F*/
04682 int gpioCfgClock(
04683    unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource);
04684 /*D
04685 Configures pigpio to use a particular sample rate timed by a specified
04686 peripheral.
04687 
04688 This function is only effective if called before [*gpioInitialise*].
04689 
04690 . .
04691     cfgMicros: 1, 2, 4, 5, 8, 10
04692 cfgPeripheral: 0 (PWM), 1 (PCM)
04693     cfgSource: deprecated, value is ignored
04694 . .
04695 
04696 The timings are provided by the specified peripheral (PWM or PCM).
04697 
04698 The default setting is 5 microseconds using the PCM peripheral.
04699 
04700 The approximate CPU percentage used for each sample rate is:
04701 
04702 . .
04703 sample  cpu
04704  rate    %
04705 
04706   1     25
04707   2     16
04708   4     11
04709   5     10
04710   8     15
04711  10     14
04712 . .
04713 
04714 A sample rate of 5 microseconds seeems to be the sweet spot.
04715 D*/
04716 
04717 
04718 /*F*/
04719 int gpioCfgDMAchannel(unsigned DMAchannel); /* DEPRECATED */
04720 /*D
04721 Configures pigpio to use the specified DMA channel.
04722 
04723 This function is only effective if called before [*gpioInitialise*].
04724 
04725 . .
04726 DMAchannel: 0-14
04727 . .
04728 
04729 The default setting is to use channel 14.
04730 D*/
04731 
04732 
04733 /*F*/
04734 int gpioCfgDMAchannels(
04735    unsigned primaryChannel, unsigned secondaryChannel);
04736 /*D
04737 Configures pigpio to use the specified DMA channels.
04738 
04739 This function is only effective if called before [*gpioInitialise*].
04740 
04741 . .
04742   primaryChannel: 0-14
04743 secondaryChannel: 0-14
04744 . .
04745 
04746 The default setting is to use channel 14 for the primary channel and
04747 channel 6 for the secondary channel.
04748 
04749 The secondary channel is only used for the transmission of waves.
04750 
04751 If possible use one of channels 0 to 6 for the secondary channel
04752 (a full channel).
04753 
04754 A full channel only requires one DMA control block regardless of the
04755 length of a pulse delay.  Channels 7 to 14 (lite channels) require
04756 one DMA control block for each 16383 microseconds of delay.  I.e.
04757 a 10 second pulse delay requires one control block on a full channel
04758 and 611 control blocks on a lite channel.
04759 D*/
04760 
04761 
04762 /*F*/
04763 int gpioCfgPermissions(uint64_t updateMask);
04764 /*D
04765 Configures pigpio to restrict GPIO updates via the socket or pipe
04766 interfaces to the GPIO specified by the mask.  Programs directly
04767 calling the pigpio library (i.e. linked with -lpigpio are not
04768 affected).  A GPIO update is a write to a GPIO or a GPIO mode
04769 change or any function which would force such an action.
04770 
04771 This function is only effective if called before [*gpioInitialise*].
04772 
04773 . .
04774 updateMask: bit (1<<n) is set for each GPIO n which may be updated
04775 . .
04776 
04777 The default setting depends upon the Pi model. The user GPIO are
04778 added to the mask.
04779 
04780 If the board revision is not recognised then GPIO 2-27 are allowed.
04781 
04782 Unknown board @ PI_DEFAULT_UPDATE_MASK_UNKNOWN @ 0x0FFFFFFC 
04783 Type 1 board  @ PI_DEFAULT_UPDATE_MASK_B1 @ 0x03E6CF93 
04784 Type 2 board  @ PI_DEFAULT_UPDATE_MASK_A_B2 @ 0xFBC6CF9C
04785 Type 3 board  @ PI_DEFAULT_UPDATE_MASK_R3 @ 0x0FFFFFFC
04786 D*/
04787 
04788 
04789 /*F*/
04790 int gpioCfgSocketPort(unsigned port);
04791 /*D
04792 Configures pigpio to use the specified socket port.
04793 
04794 This function is only effective if called before [*gpioInitialise*].
04795 
04796 . .
04797 port: 1024-32000
04798 . .
04799 
04800 The default setting is to use port 8888.
04801 D*/
04802 
04803 
04804 /*F*/
04805 int gpioCfgInterfaces(unsigned ifFlags);
04806 /*D
04807 Configures pigpio support of the fifo and socket interfaces.
04808 
04809 This function is only effective if called before [*gpioInitialise*].
04810 
04811 . .
04812 ifFlags: 0-7
04813 . .
04814 
04815 The default setting (0) is that both interfaces are enabled.
04816 
04817 Or in PI_DISABLE_FIFO_IF to disable the pipe interface.
04818 
04819 Or in PI_DISABLE_SOCK_IF to disable the socket interface.
04820 
04821 Or in PI_LOCALHOST_SOCK_IF to disable remote socket
04822 access (this means that the socket interface is only
04823 usable from the local Pi).
04824 D*/
04825 
04826 
04827 /*F*/
04828 int gpioCfgMemAlloc(unsigned memAllocMode);
04829 /*D
04830 Selects the method of DMA memory allocation.
04831 
04832 This function is only effective if called before [*gpioInitialise*].
04833 
04834 . .
04835 memAllocMode: 0-2
04836 . .
04837 
04838 There are two methods of DMA memory allocation.  The original method
04839 uses the /proc/self/pagemap file to allocate bus memory.  The new
04840 method uses the mailbox property interface to allocate bus memory.
04841 
04842 Auto will use the mailbox method unless a larger than default buffer
04843 size is requested with [*gpioCfgBufferSize*].
04844 D*/
04845 
04846 
04847 /*F*/
04848 int gpioCfgNetAddr(int numSockAddr, uint32_t *sockAddr);
04849 /*D
04850 Sets the network addresses which are allowed to talk over the
04851 socket interface.
04852 
04853 This function is only effective if called before [*gpioInitialise*].
04854 
04855 . .
04856 numSockAddr: 0-256 (0 means all addresses allowed)
04857    sockAddr: an array of permitted network addresses.
04858 . .
04859 D*/
04860 
04861 
04862 /*F*/
04863 int gpioCfgInternals(unsigned cfgWhat, unsigned cfgVal);
04864 /*D
04865 Used to tune internal settings.
04866 
04867 . .
04868 cfgWhat: see source code
04869  cfgVal: see source code
04870 . .
04871 D*/
04872 
04873 
04874 /*F*/
04875 uint32_t gpioCfgGetInternals(void);
04876 /*D
04877 This function returns the current library internal configuration
04878 settings.
04879 D*/
04880 
04881 /*F*/
04882 int gpioCfgSetInternals(uint32_t cfgVal);
04883 /*D
04884 This function sets the current library internal configuration
04885 settings.
04886 
04887 . .
04888 cfgVal: see source code
04889 . .
04890 D*/
04891 
04892 
04893 /*F*/
04894 int gpioCustom1(unsigned arg1, unsigned arg2, char *argx, unsigned argc);
04895 /*D
04896 This function is available for user customisation.
04897 
04898 It returns a single integer value.
04899 
04900 . .
04901 arg1: >=0
04902 arg2: >=0
04903 argx: extra (byte) arguments
04904 argc: number of extra arguments
04905 . .
04906 
04907 Returns >= 0 if OK, less than 0 indicates a user defined error.
04908 D*/
04909 
04910 
04911 /*F*/
04912 int gpioCustom2(unsigned arg1, char *argx, unsigned argc,
04913                 char *retBuf, unsigned retMax);
04914 /*D
04915 This function is available for user customisation.
04916 
04917 It differs from gpioCustom1 in that it returns an array of bytes
04918 rather than just an integer.
04919 
04920 The returned value is an integer indicating the number of returned bytes.
04921 . .
04922   arg1: >=0
04923   argx: extra (byte) arguments
04924   argc: number of extra arguments
04925 retBuf: buffer for returned bytes
04926 retMax: maximum number of bytes to return
04927 . .
04928 
04929 Returns >= 0 if OK, less than 0 indicates a user defined error.
04930 
04931 The number of returned bytes must be retMax or less.
04932 D*/
04933 
04934 
04935 /*F*/
04936 int rawWaveAddSPI(
04937    rawSPI_t *spi,
04938    unsigned offset,
04939    unsigned spiSS,
04940    char *buf,
04941    unsigned spiTxBits,
04942    unsigned spiBitFirst,
04943    unsigned spiBitLast,
04944    unsigned spiBits);
04945 /*D
04946 This function adds a waveform representing SPI data to the
04947 existing waveform (if any).
04948 
04949 . .
04950         spi: a pointer to a spi object
04951      offset: microseconds from the start of the waveform
04952       spiSS: the slave select GPIO
04953         buf: the bits to transmit, most significant bit first
04954   spiTxBits: the number of bits to write
04955 spiBitFirst: the first bit to read
04956  spiBitLast: the last bit to read
04957     spiBits: the number of bits to transfer
04958 . .
04959 
04960 Returns the new total number of pulses in the current waveform if OK,
04961 otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES.
04962 
04963 Not intended for general use.
04964 D*/
04965 
04966 /*F*/
04967 int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses);
04968 /*D
04969 This function adds a number of pulses to the current waveform.
04970 
04971 . .
04972 numPulses: the number of pulses
04973    pulses: the array containing the pulses
04974 . .
04975 
04976 Returns the new total number of pulses in the current waveform if OK,
04977 otherwise PI_TOO_MANY_PULSES.
04978 
04979 The advantage of this function over gpioWaveAddGeneric is that it
04980 allows the setting of the flags field.
04981 
04982 The pulses are interleaved in time order within the existing waveform
04983 (if any).
04984 
04985 Merging allows the waveform to be built in parts, that is the settings
04986 for GPIO#1 can be added, and then GPIO#2 etc.
04987 
04988 If the added waveform is intended to start after or within the existing
04989 waveform then the first pulse should consist of a delay.
04990 
04991 Not intended for general use.
04992 D*/
04993 
04994 /*F*/
04995 unsigned rawWaveCB(void);
04996 /*D
04997 Returns the number of the cb being currently output.
04998 
04999 Not intended for general use.
05000 D*/
05001 
05002 /*F*/
05003 rawCbs_t *rawWaveCBAdr(int cbNum);
05004 /*D
05005 Return the (Linux) address of contol block cbNum.
05006 
05007 . .
05008 cbNum: the cb of interest
05009 . .
05010 
05011 Not intended for general use.
05012 D*/
05013 
05014 /*F*/
05015 uint32_t rawWaveGetOOL(int pos);
05016 /*D
05017 Gets the OOL parameter stored at pos.
05018 
05019 . .
05020 pos: the position of interest.
05021 . .
05022 
05023 Not intended for general use.
05024 D*/
05025 
05026 
05027 /*F*/
05028 void rawWaveSetOOL(int pos, uint32_t lVal);
05029 /*D
05030 Sets the OOL parameter stored at pos to value.
05031 
05032 . .
05033  pos: the position of interest
05034 lVal: the value to write
05035 . .
05036 
05037 Not intended for general use.
05038 D*/
05039 
05040 /*F*/
05041 uint32_t rawWaveGetOut(int pos);
05042 /*D
05043 Gets the wave output parameter stored at pos.
05044 
05045 DEPRECATED: use rawWaveGetOOL instead.
05046 
05047 . .
05048 pos: the position of interest.
05049 . .
05050 
05051 Not intended for general use.
05052 D*/
05053 
05054 
05055 /*F*/
05056 void rawWaveSetOut(int pos, uint32_t lVal);
05057 /*D
05058 Sets the wave output parameter stored at pos to value.
05059 
05060 DEPRECATED: use rawWaveSetOOL instead.
05061 
05062 . .
05063  pos: the position of interest
05064 lVal: the value to write
05065 . .
05066 
05067 Not intended for general use.
05068 D*/
05069 
05070 /*F*/
05071 uint32_t rawWaveGetIn(int pos);
05072 /*D
05073 Gets the wave input value parameter stored at pos.
05074 
05075 DEPRECATED: use rawWaveGetOOL instead.
05076 
05077 . .
05078 pos: the position of interest
05079 . .
05080 
05081 Not intended for general use.
05082 D*/
05083 
05084 
05085 /*F*/
05086 void rawWaveSetIn(int pos, uint32_t lVal);
05087 /*D
05088 Sets the wave input value stored at pos to value.
05089 
05090 DEPRECATED: use rawWaveSetOOL instead.
05091 
05092 . .
05093  pos: the position of interest
05094 lVal: the value to write
05095 . .
05096 
05097 Not intended for general use.
05098 D*/
05099 
05100 /*F*/
05101 rawWaveInfo_t rawWaveInfo(int wave_id);
05102 /*D
05103 Gets details about the wave with id wave_id.
05104 
05105 . .
05106 wave_id: the wave of interest
05107 . .
05108 
05109 Not intended for general use.
05110 D*/
05111 
05112 /*F*/
05113 int getBitInBytes(int bitPos, char *buf, int numBits);
05114 /*D
05115 Returns the value of the bit bitPos bits from the start of buf.  Returns
05116 0 if bitPos is greater than or equal to numBits.
05117 
05118 . .
05119  bitPos: bit index from the start of buf
05120     buf: array of bits
05121 numBits: number of valid bits in buf
05122 . .
05123 
05124 D*/
05125 
05126 /*F*/
05127 void putBitInBytes(int bitPos, char *buf, int bit);
05128 /*D
05129 Sets the bit bitPos bits from the start of buf to bit.
05130 
05131 . .
05132 bitPos: bit index from the start of buf
05133    buf: array of bits
05134    bit: 0-1, value to set
05135 . .
05136 
05137 D*/
05138 
05139 /*F*/
05140 double time_time(void);
05141 /*D
05142 Return the current time in seconds since the Epoch.
05143 D*/
05144 
05145 
05146 /*F*/
05147 void time_sleep(double seconds);
05148 /*D
05149 Delay execution for a given number of seconds
05150 
05151 . .
05152 seconds: the number of seconds to sleep
05153 . .
05154 D*/
05155 
05156 
05157 /*F*/
05158 void rawDumpWave(void);
05159 /*D
05160 Used to print a readable version of the current waveform to stderr.
05161 
05162 Not intended for general use.
05163 D*/
05164 
05165 
05166 /*F*/
05167 void rawDumpScript(unsigned script_id);
05168 /*D
05169 Used to print a readable version of a script to stderr.
05170 
05171 . .
05172 script_id: >=0, a script_id returned by [*gpioStoreScript*]
05173 . .
05174 
05175 Not intended for general use.
05176 D*/
05177 
05178 
05179 #ifdef __cplusplus
05180 }
05181 #endif
05182 
05183 /*PARAMS
05184 
05185 active :: 0-1000000
05186 
05187 The number of microseconds level changes are reported for once
05188 a noise filter has been triggered (by [*steady*] microseconds of
05189 a stable level).
05190 
05191 arg1::
05192 
05193 An unsigned argument passed to a user customised function.  Its
05194 meaning is defined by the customiser.
05195 
05196 arg2::
05197 
05198 An unsigned argument passed to a user customised function.  Its
05199 meaning is defined by the customiser.
05200 
05201 argc::
05202 The count of bytes passed to a user customised function.
05203 
05204 *argx::
05205 A pointer to an array of bytes passed to a user customised function.
05206 Its meaning and content is defined by the customiser.
05207 
05208 baud::
05209 The speed of serial communication (I2C, SPI, serial link, waves) in
05210 bits per second.
05211 
05212 bit::
05213 A value of 0 or 1.
05214 
05215 bitPos::
05216 A bit position within a byte or word.  The least significant bit is
05217 position 0.
05218 
05219 bits::
05220 A value used to select GPIO.  If bit n of bits is set then GPIO n is
05221 selected.
05222 
05223 A convenient way to set bit n is to or in (1<<n).
05224 
05225 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
05226 
05227 *bsc_xfer::
05228 A pointer to a [*bsc_xfer_t*] object used to control a BSC transfer.
05229 
05230 bsc_xfer_t::
05231 
05232 . .
05233 typedef struct
05234 {
05235    uint32_t control;          // Write
05236    int rxCnt;                 // Read only
05237    char rxBuf[BSC_FIFO_SIZE]; // Read only
05238    int txCnt;                 // Write
05239    char txBuf[BSC_FIFO_SIZE]; // Write
05240 } bsc_xfer_t;
05241 . .
05242 
05243 *buf::
05244 
05245 A buffer to hold data being sent or being received.
05246 
05247 bufSize::
05248 
05249 The size in bytes of a buffer.
05250 
05251 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
05252 
05253 An 8-bit byte value.
05254 
05255 cbNum::
05256 
05257 A number identifying a DMA contol block.
05258 
05259 cfgMicros::
05260 
05261 The GPIO sample rate in microseconds.  The default is 5us, or 200 thousand
05262 samples per second.
05263 
05264 cfgMillis:: 100-10000
05265 
05266 The size of the sample buffer in milliseconds.  Generally this should be
05267 left at the default of 120ms.  If you expect intense bursts of signals it
05268 might be necessary to increase the buffer size.
05269 
05270 cfgPeripheral::
05271 
05272 One of the PWM or PCM peripherals used to pace DMA transfers for timing
05273 purposes.
05274 
05275 cfgSource::
05276 
05277 Deprecated.
05278 
05279 cfgVal::
05280 
05281 A number specifying the value of a configuration item.  See [*cfgWhat*].
05282 
05283 cfgWhat::
05284 
05285 A number specifying a configuration item.
05286 
05287 562484977: print enhanced statistics at termination. 
05288 984762879: set the initial debug level.
05289 
05290 char::
05291 
05292 A single character, an 8 bit quantity able to store 0-255.
05293 
05294 clkfreq::4689-250M
05295 
05296 The hardware clock frequency.
05297 
05298 . .
05299 PI_HW_CLK_MIN_FREQ 4689
05300 PI_HW_CLK_MAX_FREQ 250000000
05301 . .
05302 
05303 count::
05304 The number of bytes to be transferred in an I2C, SPI, or Serial
05305 command.
05306 
05307 CS::
05308 The GPIO used for the slave select signal when bit banging SPI.
05309 
05310 data_bits::1-32
05311 
05312 The number of data bits to be used when adding serial data to a
05313 waveform.
05314 
05315 . .
05316 PI_MIN_WAVE_DATABITS 1
05317 PI_MAX_WAVE_DATABITS 32
05318 . .
05319 
05320 DMAchannel::0-14
05321 . .
05322 PI_MIN_DMA_CHANNEL 0
05323 PI_MAX_DMA_CHANNEL 14
05324 . .
05325 
05326 double::
05327 
05328 A floating point number.
05329 
05330 dutycycle::0-range
05331 
05332 A number representing the ratio of on time to off time for PWM.
05333 
05334 The number may vary between 0 and range (default 255) where
05335 0 is off and range is fully on.
05336 
05337 edge::0-2
05338 The type of GPIO edge to generate an interrupt.  See [*gpioSetISRFunc*]
05339 and [*gpioSetISRFuncEx*].
05340 
05341 . .
05342 RISING_EDGE 0
05343 FALLING_EDGE 1
05344 EITHER_EDGE 2
05345 . .
05346 
05347 event::0-31
05348 An event is a signal used to inform one or more consumers
05349 to start an action.
05350 
05351 eventFunc_t::
05352 . .
05353 typedef void (*eventFunc_t) (int event, uint32_t tick);
05354 . .
05355 
05356 eventFuncEx_t::
05357 . .
05358 typedef void (*eventFuncEx_t)
05359    (int event, uint32_t tick, void *userdata);
05360 . .
05361 
05362 f::
05363 
05364 A function.
05365 
05366 *file::
05367 A full file path.  To be accessible the path must match an entry in
05368 /opt/pigpio/access.
05369 
05370 *fpat::
05371 A file path which may contain wildcards.  To be accessible the path
05372 must match an entry in /opt/pigpio/access.
05373 
05374 frequency::>=0
05375 
05376 The number of times a GPIO is swiched on and off per second.  This
05377 can be set per GPIO and may be as little as 5Hz or as much as
05378 40KHz.  The GPIO will be on for a proportion of the time as defined
05379 by its dutycycle.
05380 
05381 gpio::
05382 
05383 A Broadcom numbered GPIO, in the range 0-53.
05384 
05385 There  are 54 General Purpose Input Outputs (GPIO) named GPIO0 through
05386 GPIO53.
05387 
05388 They are split into two  banks.   Bank  1  consists  of  GPIO0  through
05389 GPIO31.  Bank 2 consists of GPIO32 through GPIO53.
05390 
05391 All the GPIO which are safe for the user to read and write are in
05392 bank 1.  Not all GPIO in bank 1 are safe though.  Type 1 boards
05393 have 17  safe GPIO.  Type 2 boards have 21.  Type 3 boards have 26.
05394 
05395 See [*gpioHardwareRevision*].
05396 
05397 The user GPIO are marked with an X in the following table.
05398 
05399 . .
05400           0  1  2  3  4  5  6  7  8  9 10 11 12 13 14 15
05401 Type 1    X  X  -  -  X  -  -  X  X  X  X  X  -  -  X  X
05402 Type 2    -  -  X  X  X  -  -  X  X  X  X  X  -  -  X  X
05403 Type 3          X  X  X  X  X  X  X  X  X  X  X  X  X  X
05404 
05405          16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
05406 Type 1    -  X  X  -  -  X  X  X  X  X  -  -  -  -  -  -
05407 Type 2    -  X  X  -  -  -  X  X  X  X  -  X  X  X  X  X
05408 Type 3    X  X  X  X  X  X  X  X  X  X  X  X  -  -  -  -
05409 . .
05410 
05411 gpioAlertFunc_t::
05412 . .
05413 typedef void (*gpioAlertFunc_t) (int gpio, int level, uint32_t tick);
05414 . .
05415 
05416 gpioAlertFuncEx_t::
05417 . .
05418 typedef void (*eventFuncEx_t)
05419    (int event, int level, uint32_t tick, void *userdata);
05420 . .
05421 
05422 gpioCfg*::
05423 
05424 These functions are only effective if called before [*gpioInitialise*].
05425 
05426 [*gpioCfgBufferSize*] 
05427 [*gpioCfgClock*] 
05428 [*gpioCfgDMAchannel*] 
05429 [*gpioCfgDMAchannels*] 
05430 [*gpioCfgPermissions*] 
05431 [*gpioCfgInterfaces*] 
05432 [*gpioCfgSocketPort*] 
05433 [*gpioCfgMemAlloc*]
05434 
05435 gpioGetSamplesFunc_t::
05436 . .
05437 typedef void (*gpioGetSamplesFunc_t)
05438    (const gpioSample_t *samples, int numSamples);
05439 . .
05440 
05441 gpioGetSamplesFuncEx_t::
05442 . .
05443 typedef void (*gpioGetSamplesFuncEx_t)
05444    (const gpioSample_t *samples, int numSamples, void *userdata);
05445 . .
05446 
05447 gpioISRFunc_t::
05448 . .
05449 typedef void (*gpioISRFunc_t)
05450    (int gpio, int level, uint32_t tick);
05451 . .
05452 
05453 gpioISRFuncEx_t::
05454 . .
05455 typedef void (*gpioISRFuncEx_t)
05456    (int gpio, int level, uint32_t tick, void *userdata);
05457 . .
05458 
05459 gpioPulse_t::
05460 . .
05461 typedef struct
05462 {
05463    uint32_t gpioOn;
05464    uint32_t gpioOff;
05465    uint32_t usDelay;
05466 } gpioPulse_t;
05467 . .
05468 
05469 gpioSample_t::
05470 . .
05471 typedef struct
05472 {
05473    uint32_t tick;
05474    uint32_t level;
05475 } gpioSample_t;
05476 . .
05477 
05478 gpioSignalFunc_t::
05479 . .
05480 typedef void (*gpioSignalFunc_t) (int signum);
05481 . .
05482 
05483 gpioSignalFuncEx_t::
05484 . .
05485 typedef void (*gpioSignalFuncEx_t) (int signum, void *userdata);
05486 . .
05487 
05488 gpioThreadFunc_t::
05489 . .
05490 typedef void *(gpioThreadFunc_t) (void *);
05491 . .
05492 
05493 gpioTimerFunc_t::
05494 . .
05495 typedef void (*gpioTimerFunc_t) (void);
05496 . .
05497 
05498 gpioTimerFuncEx_t::
05499 . .
05500 typedef void (*gpioTimerFuncEx_t) (void *userdata);
05501 . .
05502 
05503 gpioWaveAdd*::
05504 
05505 One of
05506 
05507 [*gpioWaveAddNew*] 
05508 [*gpioWaveAddGeneric*] 
05509 [*gpioWaveAddSerial*]
05510 
05511 handle::>=0
05512 
05513 A number referencing an object opened by one of
05514 
05515 [*fileOpen*] 
05516 [*gpioNotifyOpen*] 
05517 [*i2cOpen*] 
05518 [*serOpen*] 
05519 [*spiOpen*]
05520 
05521 i2cAddr:: 0-0x7F
05522 The address of a device on the I2C bus.
05523 
05524 i2cBus::>=0
05525 
05526 An I2C bus number.
05527 
05528 i2cFlags::0
05529 
05530 Flags which modify an I2C open command.  None are currently defined.
05531 
05532 i2cReg:: 0-255
05533 
05534 A register of an I2C device.
05535 
05536 ifFlags::0-3
05537 . .
05538 PI_DISABLE_FIFO_IF 1
05539 PI_DISABLE_SOCK_IF 2
05540 . .
05541 
05542 *inBuf::
05543 A buffer used to pass data to a function.
05544 
05545 inLen::
05546 The number of bytes of data in a buffer.
05547 
05548 int::
05549 A whole number, negative or positive.
05550 
05551 int32_t::
05552 A 32-bit signed value.
05553 
05554 invert::
05555 A flag used to set normal or inverted bit bang serial data level logic.
05556 
05557 level::
05558 The level of a GPIO.  Low or High.
05559 
05560 . .
05561 PI_OFF 0
05562 PI_ON 1
05563 
05564 PI_CLEAR 0
05565 PI_SET 1
05566 
05567 PI_LOW 0
05568 PI_HIGH 1
05569 . .
05570 
05571 There is one exception.  If a watchdog expires on a GPIO the level will be
05572 reported as PI_TIMEOUT.  See [*gpioSetWatchdog*].
05573 
05574 . .
05575 PI_TIMEOUT 2
05576 . .
05577 
05578 
05579 lVal::0-4294967295 (Hex 0x0-0xFFFFFFFF, Octal 0-37777777777)
05580 
05581 A 32-bit word value.
05582 
05583 memAllocMode:: 0-2
05584 
05585 The DMA memory allocation mode.
05586 
05587 . .
05588 PI_MEM_ALLOC_AUTO    0
05589 PI_MEM_ALLOC_PAGEMAP 1
05590 PI_MEM_ALLOC_MAILBOX 2
05591 . .
05592 
05593 *micros::
05594 
05595 A value representing microseconds.
05596 
05597 micros::
05598 
05599 A value representing microseconds.
05600 
05601 millis::
05602 
05603 A value representing milliseconds.
05604 
05605 MISO::
05606 The GPIO used for the MISO signal when bit banging SPI.
05607 
05608 mode::
05609 
05610 1. The operational mode of a GPIO, normally INPUT or OUTPUT.
05611 
05612 . .
05613 PI_INPUT 0
05614 PI_OUTPUT 1
05615 PI_ALT0 4
05616 PI_ALT1 5
05617 PI_ALT2 6
05618 PI_ALT3 7
05619 PI_ALT4 3
05620 PI_ALT5 2
05621 . .
05622 
05623 2. A file open mode.
05624 
05625 . .
05626 PI_FILE_READ  1
05627 PI_FILE_WRITE 2
05628 PI_FILE_RW    3
05629 . .
05630 
05631 The following values can be or'd into the mode.
05632 
05633 . .
05634 PI_FILE_APPEND 4
05635 PI_FILE_CREATE 8
05636 PI_FILE_TRUNC  16
05637 . .
05638 
05639 MOSI::
05640 The GPIO used for the MOSI signal when bit banging SPI.
05641 
05642 numBits::
05643 
05644 The number of bits stored in a buffer.
05645 
05646 numBytes::
05647 The number of bytes used to store characters in a string.  Depending
05648 on the number of bits per character there may be 1, 2, or 4 bytes
05649 per character.
05650 
05651 numPar:: 0-10
05652 The number of parameters passed to a script.
05653 
05654 numPulses::
05655 The number of pulses to be added to a waveform.
05656 
05657 numSegs::
05658 The number of segments in a combined I2C transaction.
05659 
05660 numSockAddr::
05661 The number of network addresses allowed to use the socket interface.
05662 
05663 0 means all addresses allowed.
05664 
05665 offset::
05666 The associated data starts this number of microseconds from the start of
05667 the waveform.
05668 
05669 *outBuf::
05670 A buffer used to return data from a function.
05671 
05672 outLen::
05673 The size in bytes of an output buffer.
05674 
05675 pad:: 0-2
05676 A set of GPIO which share common drivers.
05677 
05678 Pad @ GPIO
05679 0   @ 0-27
05680 1   @ 28-45
05681 2   @ 46-53
05682 
05683 padStrength:: 1-16
05684 The mA which may be drawn from each GPIO whilst still guaranteeing the
05685 high and low levels.
05686 
05687 *param::
05688 An array of script parameters.
05689 
05690 pi_i2c_msg_t::
05691 . .
05692 typedef struct
05693 {
05694    uint16_t addr;  // slave address
05695    uint16_t flags;
05696    uint16_t len;   // msg length
05697    uint8_t  *buf;  // pointer to msg data
05698 } pi_i2c_msg_t;
05699 . .
05700 
05701 port:: 1024-32000
05702 The port used to bind to the pigpio socket.  Defaults to 8888.
05703 
05704 pos::
05705 The position of an item.
05706 
05707 primaryChannel:: 0-14
05708 The DMA channel used to time the sampling of GPIO and to time servo and
05709 PWM pulses.
05710 
05711 *pth::
05712 
05713 A thread identifier, returned by [*gpioStartThread*].
05714 
05715 pthread_t::
05716 
05717 A thread identifier.
05718 
05719 pud::0-2
05720 
05721 The setting of the pull up/down resistor for a GPIO, which may be off,
05722 pull-up, or pull-down.
05723 
05724 . .
05725 PI_PUD_OFF 0
05726 PI_PUD_DOWN 1
05727 PI_PUD_UP 2
05728 . .
05729 
05730 pulseLen::
05731 
05732 1-100, the length of a trigger pulse in microseconds.
05733 
05734 *pulses::
05735 
05736 An array of pulses to be added to a waveform.
05737 
05738 pulsewidth::0, 500-2500
05739 . .
05740 PI_SERVO_OFF 0
05741 PI_MIN_SERVO_PULSEWIDTH 500
05742 PI_MAX_SERVO_PULSEWIDTH 2500
05743 . .
05744 
05745 PWMduty::0-1000000 (1M)
05746 The hardware PWM dutycycle.
05747 
05748 . .
05749 PI_HW_PWM_RANGE 1000000
05750 . .
05751 
05752 PWMfreq::5-250K
05753 The hardware PWM frequency.
05754 
05755 . .
05756 PI_HW_PWM_MIN_FREQ 1
05757 PI_HW_PWM_MAX_FREQ 125000000
05758 . .
05759 
05760 range::25-40000
05761 . .
05762 PI_MIN_DUTYCYCLE_RANGE 25
05763 PI_MAX_DUTYCYCLE_RANGE 40000
05764 . .
05765 
05766 rawCbs_t::
05767 . .
05768 typedef struct // linux/arch/arm/mach-bcm2708/include/mach/dma.h
05769 {
05770    unsigned long info;
05771    unsigned long src;
05772    unsigned long dst;
05773    unsigned long length;
05774    unsigned long stride;
05775    unsigned long next;
05776    unsigned long pad[2];
05777 } rawCbs_t;
05778 . .
05779 
05780 rawSPI_t::
05781 . .
05782 typedef struct
05783 {
05784    int clk;     // GPIO for clock
05785    int mosi;    // GPIO for MOSI
05786    int miso;    // GPIO for MISO
05787    int ss_pol;  // slave select off state
05788    int ss_us;   // delay after slave select
05789    int clk_pol; // clock off state
05790    int clk_pha; // clock phase
05791    int clk_us;  // clock micros
05792 } rawSPI_t;
05793 . .
05794 
05795 rawWave_t::
05796 . .
05797 typedef struct
05798 {
05799    uint32_t gpioOn;
05800    uint32_t gpioOff;
05801    uint32_t usDelay;
05802    uint32_t flags;
05803 } rawWave_t;
05804 . .
05805 
05806 rawWaveInfo_t::
05807 . .
05808 typedef struct
05809 {
05810    uint16_t botCB;  // first CB used by wave
05811    uint16_t topCB;  // last CB used by wave
05812    uint16_t botOOL; // last OOL used by wave
05813    uint16_t topOOL; // first OOL used by wave
05814    uint16_t deleted;
05815    uint16_t numCB;
05816    uint16_t numBOOL;
05817    uint16_t numTOOL;
05818 } rawWaveInfo_t;
05819 . .
05820 
05821 *retBuf::
05822 
05823 A buffer to hold a number of bytes returned to a used customised function,
05824 
05825 retMax::
05826 
05827 The maximum number of bytes a user customised function should return.
05828 
05829 *rxBuf::
05830 
05831 A pointer to a buffer to receive data.
05832 
05833 SCL::
05834 The user GPIO to use for the clock when bit banging I2C.
05835 
05836 SCLK::
05837 The GPIO used for the SCLK signal when bit banging SPI.
05838 
05839 *script::
05840 A pointer to the text of a script.
05841 
05842 script_id::
05843 An id of a stored script as returned by [*gpioStoreScript*].
05844 
05845 *scriptName::
05846 The name of a [*shell*] script to be executed.  The script must be present in
05847 /opt/pigpio/cgi and must have execute permission.
05848 
05849 *scriptString::
05850 The string to be passed to a [*shell*] script to be executed.
05851 
05852 SDA::
05853 The user GPIO to use for data when bit banging I2C.
05854 
05855 secondaryChannel:: 0-6
05856 
05857 The DMA channel used to time output waveforms.
05858 
05859 *seconds::
05860 
05861 A pointer to a uint32_t to store the second component of
05862 a returned time.
05863 
05864 seconds::
05865 The number of seconds.
05866 
05867 seekFrom::
05868 
05869 . .
05870 PI_FROM_START   0
05871 PI_FROM_CURRENT 1
05872 PI_FROM_END     2
05873 . .
05874 
05875 seekOffset::
05876 The number of bytes to move forward (positive) or backwards (negative)
05877 from the seek position (start, current, or end of file).
05878 
05879 *segs::
05880 An array of segments which make up a combined I2C transaction.
05881 
05882 serFlags::
05883 Flags which modify a serial open command.  None are currently defined.
05884 
05885 *sertty::
05886 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
05887 
05888 setting::
05889 A value used to set a flag, 0 for false, non-zero for true.
05890 
05891 signum::0-63
05892 . .
05893 PI_MIN_SIGNUM 0
05894 PI_MAX_SIGNUM 63
05895 . .
05896 
05897 size_t::
05898 
05899 A standard type used to indicate the size of an object in bytes.
05900 
05901 *sockAddr::
05902 An array of network addresses allowed to use the socket interface encoded
05903 as 32 bit numbers.
05904 
05905 E.g. address 192.168.1.66 would be encoded as 0x4201a8c0.
05906 
05907 *spi::
05908 A pointer to a [*rawSPI_t*] structure.
05909 
05910 spiBitFirst::
05911 GPIO reads are made from spiBitFirst to spiBitLast.
05912 
05913 spiBitLast::
05914 
05915 GPIO reads are made from spiBitFirst to spiBitLast.
05916 
05917 spiBits::
05918 The number of bits to transfer in a raw SPI transaction.
05919 
05920 spiChan::
05921 A SPI channel, 0-2.
05922 
05923 spiFlags::
05924 See [*spiOpen*] and [*bbSPIOpen*].
05925 
05926 spiSS::
05927 The SPI slave select GPIO in a raw SPI transaction.
05928 
05929 spiTxBits::
05930 The number of bits to transfer dring a raw SPI transaction
05931 
05932 steady :: 0-300000
05933 
05934 The number of microseconds level changes must be stable for
05935 before reporting the level changed ([*gpioGlitchFilter*]) or triggering
05936 the active part of a noise filter ([*gpioNoiseFilter*]).
05937 
05938 stop_bits::2-8
05939 The number of (half) stop bits to be used when adding serial data
05940 to a waveform.
05941 
05942 . .
05943 PI_MIN_WAVE_HALFSTOPBITS 2
05944 PI_MAX_WAVE_HALFSTOPBITS 8
05945 . .
05946 
05947 *str::
05948 An array of characters.
05949 
05950 timeout::
05951 A GPIO level change timeout in milliseconds.
05952 
05953 [*gpioSetWatchdog*]
05954 . .
05955 PI_MIN_WDOG_TIMEOUT 0
05956 PI_MAX_WDOG_TIMEOUT 60000
05957 . .
05958 
05959 [*gpioSetISRFunc*] and [*gpioSetISRFuncEx*]
05960 . .
05961 <=0 cancel timeout
05962 >0 timeout after specified milliseconds
05963 . .
05964 
05965 timer::
05966 . .
05967 PI_MIN_TIMER 0
05968 PI_MAX_TIMER 9
05969 . .
05970 
05971 timetype::
05972 . .
05973 PI_TIME_RELATIVE 0
05974 PI_TIME_ABSOLUTE 1
05975 . .
05976 
05977 *txBuf::
05978 
05979 An array of bytes to transmit.
05980 
05981 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
05982 
05983 A 32-bit unsigned value.
05984 
05985 uint64_t::0-(2^64)-1
05986 
05987 A 64-bit unsigned value.
05988 
05989 unsigned::
05990 
05991 A whole number >= 0.
05992 
05993 updateMask::
05994 
05995 A 64 bit mask indicating which GPIO may be written to by the user.
05996 
05997 If GPIO#n may be written then bit (1<<n) is set.
05998 
05999 user_gpio::
06000 
06001 0-31, a Broadcom numbered GPIO.
06002 
06003 See [*gpio*].
06004 
06005 *userdata::
06006 A pointer to arbitrary user data.  This may be used to identify the instance.
06007 
06008 You must ensure that the pointer is in scope at the time it is processed.  If
06009 it is a pointer to a global this is automatic.  Do not pass the address of a
06010 local variable.  If you want to pass a transient object then use the
06011 following technique.
06012 
06013 In the calling function:
06014 
06015 . .
06016 user_type *userdata; 
06017 user_type my_userdata;
06018 
06019 userdata = malloc(sizeof(user_type)); 
06020 *userdata = my_userdata;
06021 . .
06022 
06023 In the receiving function:
06024 
06025 . .
06026 user_type my_userdata = *(user_type*)userdata;
06027 
06028 free(userdata);
06029 . .
06030 
06031 void::
06032 
06033 Denoting no parameter is required
06034 
06035 wave_id::
06036 
06037 A number identifying a waveform created by [*gpioWaveCreate*].
06038 
06039 wave_mode::
06040 
06041 The mode determines if the waveform is sent once or cycles
06042 repeatedly.  The SYNC variants wait for the current waveform
06043 to reach the end of a cycle or finish before starting the new
06044 waveform.
06045 
06046 . .
06047 PI_WAVE_MODE_ONE_SHOT      0
06048 PI_WAVE_MODE_REPEAT        1
06049 PI_WAVE_MODE_ONE_SHOT_SYNC 2
06050 PI_WAVE_MODE_REPEAT_SYNC   3
06051 . .
06052 
06053 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
06054 
06055 A 16-bit word value.
06056 
06057 PARAMS*/
06058 
06059 /*DEF_S Socket Command Codes*/
06060 
06061 #define PI_CMD_MODES  0
06062 #define PI_CMD_MODEG  1
06063 #define PI_CMD_PUD    2
06064 #define PI_CMD_READ   3
06065 #define PI_CMD_WRITE  4
06066 #define PI_CMD_PWM    5
06067 #define PI_CMD_PRS    6
06068 #define PI_CMD_PFS    7
06069 #define PI_CMD_SERVO  8
06070 #define PI_CMD_WDOG   9
06071 #define PI_CMD_BR1   10
06072 #define PI_CMD_BR2   11
06073 #define PI_CMD_BC1   12
06074 #define PI_CMD_BC2   13
06075 #define PI_CMD_BS1   14
06076 #define PI_CMD_BS2   15
06077 #define PI_CMD_TICK  16
06078 #define PI_CMD_HWVER 17
06079 #define PI_CMD_NO    18
06080 #define PI_CMD_NB    19
06081 #define PI_CMD_NP    20
06082 #define PI_CMD_NC    21
06083 #define PI_CMD_PRG   22
06084 #define PI_CMD_PFG   23
06085 #define PI_CMD_PRRG  24
06086 #define PI_CMD_HELP  25
06087 #define PI_CMD_PIGPV 26
06088 #define PI_CMD_WVCLR 27
06089 #define PI_CMD_WVAG  28
06090 #define PI_CMD_WVAS  29
06091 #define PI_CMD_WVGO  30
06092 #define PI_CMD_WVGOR 31
06093 #define PI_CMD_WVBSY 32
06094 #define PI_CMD_WVHLT 33
06095 #define PI_CMD_WVSM  34
06096 #define PI_CMD_WVSP  35
06097 #define PI_CMD_WVSC  36
06098 #define PI_CMD_TRIG  37
06099 #define PI_CMD_PROC  38
06100 #define PI_CMD_PROCD 39
06101 #define PI_CMD_PROCR 40
06102 #define PI_CMD_PROCS 41
06103 #define PI_CMD_SLRO  42
06104 #define PI_CMD_SLR   43
06105 #define PI_CMD_SLRC  44
06106 #define PI_CMD_PROCP 45
06107 #define PI_CMD_MICS  46
06108 #define PI_CMD_MILS  47
06109 #define PI_CMD_PARSE 48
06110 #define PI_CMD_WVCRE 49
06111 #define PI_CMD_WVDEL 50
06112 #define PI_CMD_WVTX  51
06113 #define PI_CMD_WVTXR 52
06114 #define PI_CMD_WVNEW 53
06115 
06116 #define PI_CMD_I2CO  54
06117 #define PI_CMD_I2CC  55
06118 #define PI_CMD_I2CRD 56
06119 #define PI_CMD_I2CWD 57
06120 #define PI_CMD_I2CWQ 58
06121 #define PI_CMD_I2CRS 59
06122 #define PI_CMD_I2CWS 60
06123 #define PI_CMD_I2CRB 61
06124 #define PI_CMD_I2CWB 62
06125 #define PI_CMD_I2CRW 63
06126 #define PI_CMD_I2CWW 64
06127 #define PI_CMD_I2CRK 65
06128 #define PI_CMD_I2CWK 66
06129 #define PI_CMD_I2CRI 67
06130 #define PI_CMD_I2CWI 68
06131 #define PI_CMD_I2CPC 69
06132 #define PI_CMD_I2CPK 70
06133 
06134 #define PI_CMD_SPIO  71
06135 #define PI_CMD_SPIC  72
06136 #define PI_CMD_SPIR  73
06137 #define PI_CMD_SPIW  74
06138 #define PI_CMD_SPIX  75
06139 
06140 #define PI_CMD_SERO  76
06141 #define PI_CMD_SERC  77
06142 #define PI_CMD_SERRB 78
06143 #define PI_CMD_SERWB 79
06144 #define PI_CMD_SERR  80
06145 #define PI_CMD_SERW  81
06146 #define PI_CMD_SERDA 82
06147 
06148 #define PI_CMD_GDC   83
06149 #define PI_CMD_GPW   84
06150 
06151 #define PI_CMD_HC    85
06152 #define PI_CMD_HP    86
06153 
06154 #define PI_CMD_CF1   87
06155 #define PI_CMD_CF2   88
06156 
06157 #define PI_CMD_BI2CC 89
06158 #define PI_CMD_BI2CO 90
06159 #define PI_CMD_BI2CZ 91
06160 
06161 #define PI_CMD_I2CZ  92
06162 
06163 #define PI_CMD_WVCHA 93
06164 
06165 #define PI_CMD_SLRI  94
06166 
06167 #define PI_CMD_CGI   95
06168 #define PI_CMD_CSI   96
06169 
06170 #define PI_CMD_FG    97
06171 #define PI_CMD_FN    98
06172 
06173 #define PI_CMD_NOIB  99
06174 
06175 #define PI_CMD_WVTXM 100
06176 #define PI_CMD_WVTAT 101
06177 
06178 #define PI_CMD_PADS  102
06179 #define PI_CMD_PADG  103
06180 
06181 #define PI_CMD_FO    104
06182 #define PI_CMD_FC    105
06183 #define PI_CMD_FR    106
06184 #define PI_CMD_FW    107
06185 #define PI_CMD_FS    108
06186 #define PI_CMD_FL    109
06187 
06188 #define PI_CMD_SHELL 110
06189 
06190 #define PI_CMD_BSPIC 111
06191 #define PI_CMD_BSPIO 112
06192 #define PI_CMD_BSPIX 113
06193 
06194 #define PI_CMD_BSCX  114
06195 
06196 #define PI_CMD_EVM   115
06197 #define PI_CMD_EVT   116
06198 
06199 #define PI_CMD_PROCU 117
06200 
06201 /*DEF_E*/
06202 
06203 /*
06204 PI CMD_NOIB only works on the socket interface.
06205 It returns a spare notification handle.  Notifications for
06206 that handle will be sent to the socket (rather than a
06207 /dev/pigpiox pipe).
06208 
06209 The socket should be dedicated to receiving notifications
06210 after this command is issued.
06211 */
06212 
06213 /* pseudo commands */
06214 
06215 #define PI_CMD_SCRIPT 800
06216 
06217 #define PI_CMD_ADD   800
06218 #define PI_CMD_AND   801
06219 #define PI_CMD_CALL  802
06220 #define PI_CMD_CMDR  803
06221 #define PI_CMD_CMDW  804
06222 #define PI_CMD_CMP   805
06223 #define PI_CMD_DCR   806
06224 #define PI_CMD_DCRA  807
06225 #define PI_CMD_DIV   808
06226 #define PI_CMD_HALT  809
06227 #define PI_CMD_INR   810
06228 #define PI_CMD_INRA  811
06229 #define PI_CMD_JM    812
06230 #define PI_CMD_JMP   813
06231 #define PI_CMD_JNZ   814
06232 #define PI_CMD_JP    815
06233 #define PI_CMD_JZ    816
06234 #define PI_CMD_TAG   817
06235 #define PI_CMD_LD    818
06236 #define PI_CMD_LDA   819
06237 #define PI_CMD_LDAB  820
06238 #define PI_CMD_MLT   821
06239 #define PI_CMD_MOD   822
06240 #define PI_CMD_NOP   823
06241 #define PI_CMD_OR    824
06242 #define PI_CMD_POP   825
06243 #define PI_CMD_POPA  826
06244 #define PI_CMD_PUSH  827
06245 #define PI_CMD_PUSHA 828
06246 #define PI_CMD_RET   829
06247 #define PI_CMD_RL    830
06248 #define PI_CMD_RLA   831
06249 #define PI_CMD_RR    832
06250 #define PI_CMD_RRA   833
06251 #define PI_CMD_STA   834
06252 #define PI_CMD_STAB  835
06253 #define PI_CMD_SUB   836
06254 #define PI_CMD_SYS   837
06255 #define PI_CMD_WAIT  838
06256 #define PI_CMD_X     839
06257 #define PI_CMD_XA    840
06258 #define PI_CMD_XOR   841
06259 #define PI_CMD_EVTWT 842
06260 
06261 /*DEF_S Error Codes*/
06262 
06263 #define PI_INIT_FAILED       -1 // gpioInitialise failed
06264 #define PI_BAD_USER_GPIO     -2 // GPIO not 0-31
06265 #define PI_BAD_GPIO          -3 // GPIO not 0-53
06266 #define PI_BAD_MODE          -4 // mode not 0-7
06267 #define PI_BAD_LEVEL         -5 // level not 0-1
06268 #define PI_BAD_PUD           -6 // pud not 0-2
06269 #define PI_BAD_PULSEWIDTH    -7 // pulsewidth not 0 or 500-2500
06270 #define PI_BAD_DUTYCYCLE     -8 // dutycycle outside set range
06271 #define PI_BAD_TIMER         -9 // timer not 0-9
06272 #define PI_BAD_MS           -10 // ms not 10-60000
06273 #define PI_BAD_TIMETYPE     -11 // timetype not 0-1
06274 #define PI_BAD_SECONDS      -12 // seconds < 0
06275 #define PI_BAD_MICROS       -13 // micros not 0-999999
06276 #define PI_TIMER_FAILED     -14 // gpioSetTimerFunc failed
06277 #define PI_BAD_WDOG_TIMEOUT -15 // timeout not 0-60000
06278 #define PI_NO_ALERT_FUNC    -16 // DEPRECATED
06279 #define PI_BAD_CLK_PERIPH   -17 // clock peripheral not 0-1
06280 #define PI_BAD_CLK_SOURCE   -18 // DEPRECATED
06281 #define PI_BAD_CLK_MICROS   -19 // clock micros not 1, 2, 4, 5, 8, or 10
06282 #define PI_BAD_BUF_MILLIS   -20 // buf millis not 100-10000
06283 #define PI_BAD_DUTYRANGE    -21 // dutycycle range not 25-40000
06284 #define PI_BAD_DUTY_RANGE   -21 // DEPRECATED (use PI_BAD_DUTYRANGE)
06285 #define PI_BAD_SIGNUM       -22 // signum not 0-63
06286 #define PI_BAD_PATHNAME     -23 // can't open pathname
06287 #define PI_NO_HANDLE        -24 // no handle available
06288 #define PI_BAD_HANDLE       -25 // unknown handle
06289 #define PI_BAD_IF_FLAGS     -26 // ifFlags > 4
06290 #define PI_BAD_CHANNEL      -27 // DMA channel not 0-14
06291 #define PI_BAD_PRIM_CHANNEL -27 // DMA primary channel not 0-14
06292 #define PI_BAD_SOCKET_PORT  -28 // socket port not 1024-32000
06293 #define PI_BAD_FIFO_COMMAND -29 // unrecognized fifo command
06294 #define PI_BAD_SECO_CHANNEL -30 // DMA secondary channel not 0-6
06295 #define PI_NOT_INITIALISED  -31 // function called before gpioInitialise
06296 #define PI_INITIALISED      -32 // function called after gpioInitialise
06297 #define PI_BAD_WAVE_MODE    -33 // waveform mode not 0-3
06298 #define PI_BAD_CFG_INTERNAL -34 // bad parameter in gpioCfgInternals call
06299 #define PI_BAD_WAVE_BAUD    -35 // baud rate not 50-250K(RX)/50-1M(TX)
06300 #define PI_TOO_MANY_PULSES  -36 // waveform has too many pulses
06301 #define PI_TOO_MANY_CHARS   -37 // waveform has too many chars
06302 #define PI_NOT_SERIAL_GPIO  -38 // no bit bang serial read on GPIO
06303 #define PI_BAD_SERIAL_STRUC -39 // bad (null) serial structure parameter
06304 #define PI_BAD_SERIAL_BUF   -40 // bad (null) serial buf parameter
06305 #define PI_NOT_PERMITTED    -41 // GPIO operation not permitted
06306 #define PI_SOME_PERMITTED   -42 // one or more GPIO not permitted
06307 #define PI_BAD_WVSC_COMMND  -43 // bad WVSC subcommand
06308 #define PI_BAD_WVSM_COMMND  -44 // bad WVSM subcommand
06309 #define PI_BAD_WVSP_COMMND  -45 // bad WVSP subcommand
06310 #define PI_BAD_PULSELEN     -46 // trigger pulse length not 1-100
06311 #define PI_BAD_SCRIPT       -47 // invalid script
06312 #define PI_BAD_SCRIPT_ID    -48 // unknown script id
06313 #define PI_BAD_SER_OFFSET   -49 // add serial data offset > 30 minutes
06314 #define PI_GPIO_IN_USE      -50 // GPIO already in use
06315 #define PI_BAD_SERIAL_COUNT -51 // must read at least a byte at a time
06316 #define PI_BAD_PARAM_NUM    -52 // script parameter id not 0-9
06317 #define PI_DUP_TAG          -53 // script has duplicate tag
06318 #define PI_TOO_MANY_TAGS    -54 // script has too many tags
06319 #define PI_BAD_SCRIPT_CMD   -55 // illegal script command
06320 #define PI_BAD_VAR_NUM      -56 // script variable id not 0-149
06321 #define PI_NO_SCRIPT_ROOM   -57 // no more room for scripts
06322 #define PI_NO_MEMORY        -58 // can't allocate temporary memory
06323 #define PI_SOCK_READ_FAILED -59 // socket read failed
06324 #define PI_SOCK_WRIT_FAILED -60 // socket write failed
06325 #define PI_TOO_MANY_PARAM   -61 // too many script parameters (> 10)
06326 #define PI_NOT_HALTED       -62 // DEPRECATED
06327 #define PI_SCRIPT_NOT_READY -62 // script initialising
06328 #define PI_BAD_TAG          -63 // script has unresolved tag
06329 #define PI_BAD_MICS_DELAY   -64 // bad MICS delay (too large)
06330 #define PI_BAD_MILS_DELAY   -65 // bad MILS delay (too large)
06331 #define PI_BAD_WAVE_ID      -66 // non existent wave id
06332 #define PI_TOO_MANY_CBS     -67 // No more CBs for waveform
06333 #define PI_TOO_MANY_OOL     -68 // No more OOL for waveform
06334 #define PI_EMPTY_WAVEFORM   -69 // attempt to create an empty waveform
06335 #define PI_NO_WAVEFORM_ID   -70 // no more waveforms
06336 #define PI_I2C_OPEN_FAILED  -71 // can't open I2C device
06337 #define PI_SER_OPEN_FAILED  -72 // can't open serial device
06338 #define PI_SPI_OPEN_FAILED  -73 // can't open SPI device
06339 #define PI_BAD_I2C_BUS      -74 // bad I2C bus
06340 #define PI_BAD_I2C_ADDR     -75 // bad I2C address
06341 #define PI_BAD_SPI_CHANNEL  -76 // bad SPI channel
06342 #define PI_BAD_FLAGS        -77 // bad i2c/spi/ser open flags
06343 #define PI_BAD_SPI_SPEED    -78 // bad SPI speed
06344 #define PI_BAD_SER_DEVICE   -79 // bad serial device name
06345 #define PI_BAD_SER_SPEED    -80 // bad serial baud rate
06346 #define PI_BAD_PARAM        -81 // bad i2c/spi/ser parameter
06347 #define PI_I2C_WRITE_FAILED -82 // i2c write failed
06348 #define PI_I2C_READ_FAILED  -83 // i2c read failed
06349 #define PI_BAD_SPI_COUNT    -84 // bad SPI count
06350 #define PI_SER_WRITE_FAILED -85 // ser write failed
06351 #define PI_SER_READ_FAILED  -86 // ser read failed
06352 #define PI_SER_READ_NO_DATA -87 // ser read no data available
06353 #define PI_UNKNOWN_COMMAND  -88 // unknown command
06354 #define PI_SPI_XFER_FAILED  -89 // spi xfer/read/write failed
06355 #define PI_BAD_POINTER      -90 // bad (NULL) pointer
06356 #define PI_NO_AUX_SPI       -91 // no auxiliary SPI on Pi A or B
06357 #define PI_NOT_PWM_GPIO     -92 // GPIO is not in use for PWM
06358 #define PI_NOT_SERVO_GPIO   -93 // GPIO is not in use for servo pulses
06359 #define PI_NOT_HCLK_GPIO    -94 // GPIO has no hardware clock
06360 #define PI_NOT_HPWM_GPIO    -95 // GPIO has no hardware PWM
06361 #define PI_BAD_HPWM_FREQ    -96 // hardware PWM frequency not 1-125M
06362 #define PI_BAD_HPWM_DUTY    -97 // hardware PWM dutycycle not 0-1M
06363 #define PI_BAD_HCLK_FREQ    -98 // hardware clock frequency not 4689-250M
06364 #define PI_BAD_HCLK_PASS    -99 // need password to use hardware clock 1
06365 #define PI_HPWM_ILLEGAL    -100 // illegal, PWM in use for main clock
06366 #define PI_BAD_DATABITS    -101 // serial data bits not 1-32
06367 #define PI_BAD_STOPBITS    -102 // serial (half) stop bits not 2-8
06368 #define PI_MSG_TOOBIG      -103 // socket/pipe message too big
06369 #define PI_BAD_MALLOC_MODE -104 // bad memory allocation mode
06370 #define PI_TOO_MANY_SEGS   -105 // too many I2C transaction segments
06371 #define PI_BAD_I2C_SEG     -106 // an I2C transaction segment failed
06372 #define PI_BAD_SMBUS_CMD   -107 // SMBus command not supported by driver
06373 #define PI_NOT_I2C_GPIO    -108 // no bit bang I2C in progress on GPIO
06374 #define PI_BAD_I2C_WLEN    -109 // bad I2C write length
06375 #define PI_BAD_I2C_RLEN    -110 // bad I2C read length
06376 #define PI_BAD_I2C_CMD     -111 // bad I2C command
06377 #define PI_BAD_I2C_BAUD    -112 // bad I2C baud rate, not 50-500k
06378 #define PI_CHAIN_LOOP_CNT  -113 // bad chain loop count
06379 #define PI_BAD_CHAIN_LOOP  -114 // empty chain loop
06380 #define PI_CHAIN_COUNTER   -115 // too many chain counters
06381 #define PI_BAD_CHAIN_CMD   -116 // bad chain command
06382 #define PI_BAD_CHAIN_DELAY -117 // bad chain delay micros
06383 #define PI_CHAIN_NESTING   -118 // chain counters nested too deeply
06384 #define PI_CHAIN_TOO_BIG   -119 // chain is too long
06385 #define PI_DEPRECATED      -120 // deprecated function removed
06386 #define PI_BAD_SER_INVERT  -121 // bit bang serial invert not 0 or 1
06387 #define PI_BAD_EDGE        -122 // bad ISR edge value, not 0-2
06388 #define PI_BAD_ISR_INIT    -123 // bad ISR initialisation
06389 #define PI_BAD_FOREVER     -124 // loop forever must be last command
06390 #define PI_BAD_FILTER      -125 // bad filter parameter
06391 #define PI_BAD_PAD         -126 // bad pad number
06392 #define PI_BAD_STRENGTH    -127 // bad pad drive strength
06393 #define PI_FIL_OPEN_FAILED -128 // file open failed
06394 #define PI_BAD_FILE_MODE   -129 // bad file mode
06395 #define PI_BAD_FILE_FLAG   -130 // bad file flag
06396 #define PI_BAD_FILE_READ   -131 // bad file read
06397 #define PI_BAD_FILE_WRITE  -132 // bad file write
06398 #define PI_FILE_NOT_ROPEN  -133 // file not open for read
06399 #define PI_FILE_NOT_WOPEN  -134 // file not open for write
06400 #define PI_BAD_FILE_SEEK   -135 // bad file seek
06401 #define PI_NO_FILE_MATCH   -136 // no files match pattern
06402 #define PI_NO_FILE_ACCESS  -137 // no permission to access file
06403 #define PI_FILE_IS_A_DIR   -138 // file is a directory
06404 #define PI_BAD_SHELL_STATUS -139 // bad shell return status
06405 #define PI_BAD_SCRIPT_NAME -140 // bad script name
06406 #define PI_BAD_SPI_BAUD    -141 // bad SPI baud rate, not 50-500k
06407 #define PI_NOT_SPI_GPIO    -142 // no bit bang SPI in progress on GPIO
06408 #define PI_BAD_EVENT_ID    -143 // bad event id
06409 #define PI_CMD_INTERRUPTED -144 // Used by Python
06410 
06411 #define PI_PIGIF_ERR_0    -2000
06412 #define PI_PIGIF_ERR_99   -2099
06413 
06414 #define PI_CUSTOM_ERR_0   -3000
06415 #define PI_CUSTOM_ERR_999 -3999
06416 
06417 /*DEF_E*/
06418 
06419 /*DEF_S Defaults*/
06420 
06421 #define PI_DEFAULT_BUFFER_MILLIS           120
06422 #define PI_DEFAULT_CLK_MICROS              5
06423 #define PI_DEFAULT_CLK_PERIPHERAL          PI_CLOCK_PCM
06424 #define PI_DEFAULT_IF_FLAGS                0
06425 #define PI_DEFAULT_FOREGROUND              0
06426 #define PI_DEFAULT_DMA_CHANNEL             14
06427 #define PI_DEFAULT_DMA_PRIMARY_CHANNEL     14
06428 #define PI_DEFAULT_DMA_SECONDARY_CHANNEL   6
06429 #define PI_DEFAULT_SOCKET_PORT             8888
06430 #define PI_DEFAULT_SOCKET_PORT_STR         "8888"
06431 #define PI_DEFAULT_SOCKET_ADDR_STR         "127.0.0.1"
06432 #define PI_DEFAULT_UPDATE_MASK_UNKNOWN     0x0000000FFFFFFCLL
06433 #define PI_DEFAULT_UPDATE_MASK_B1          0x03E7CF93
06434 #define PI_DEFAULT_UPDATE_MASK_A_B2        0xFBC7CF9C
06435 #define PI_DEFAULT_UPDATE_MASK_APLUS_BPLUS 0x0080480FFFFFFCLL
06436 #define PI_DEFAULT_UPDATE_MASK_ZERO        0x0080000FFFFFFCLL
06437 #define PI_DEFAULT_UPDATE_MASK_PI2B        0x0080480FFFFFFCLL
06438 #define PI_DEFAULT_UPDATE_MASK_PI3B        0x0000000FFFFFFCLL
06439 #define PI_DEFAULT_UPDATE_MASK_COMPUTE     0x00FFFFFFFFFFFFLL
06440 #define PI_DEFAULT_MEM_ALLOC_MODE          PI_MEM_ALLOC_AUTO
06441 
06442 #define PI_DEFAULT_CFG_INTERNALS           0
06443 
06444 /*DEF_E*/
06445 
06446 #endif
06447 


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