pigpiod_if2.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 PIGPIOD_IF2_H
00029 #define PIGPIOD_IF2_H
00030 
00031 #include "pigpio.h"
00032 
00033 #define PIGPIOD_IF2_VERSION 13
00034 
00035 /*TEXT
00036 
00037 pigpiod_if2 is a C library for the Raspberry which allows control
00038 of the GPIO via the socket interface to the pigpio daemon. 
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 on the pigpio daemon
00065 
00066 *GPIO*
00067 
00068 ALL GPIO are identified by their Broadcom number.
00069 
00070 *Notes*
00071 
00072 The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals.
00073 
00074 *Usage*
00075 
00076 Include <pigpiod_if2.h> in your source files.
00077 
00078 Assuming your source is in prog.c use the following command to build
00079 
00080 . .
00081 gcc -Wall -pthread -o prog prog.c -lpigpiod_if2 -lrt
00082 . .
00083 
00084 to run make sure the pigpio daemon is running
00085 
00086 . .
00087 sudo pigpiod
00088 
00089  ./prog # sudo is not required to run programs linked to pigpiod_if2
00090 . .
00091 
00092 For examples see x_pigpiod_if2.c within the pigpio archive file.
00093 
00094 *Notes*
00095 
00096 All the functions which return an int return < 0 on error
00097 
00098 TEXT*/
00099 
00100 /*OVERVIEW
00101 
00102 ESSENTIAL
00103 
00104 pigpio_start               Connects to a pigpio daemon
00105 pigpio_stop                Disconnects from a pigpio daemon
00106 
00107 BEGINNER
00108 
00109 set_mode                   Set a GPIO mode
00110 get_mode                   Get a GPIO mode
00111 
00112 set_pull_up_down           Set/clear GPIO pull up/down resistor
00113 
00114 gpio_read                  Read a GPIO
00115 gpio_write                 Write a GPIO
00116 
00117 set_PWM_dutycycle          Start/stop PWM pulses on a GPIO
00118 get_PWM_dutycycle          Get the PWM dutycycle in use on a GPIO
00119 
00120 set_servo_pulsewidth       Start/stop servo pulses on a GPIO
00121 get_servo_pulsewidth       Get the servo pulsewidth in use on a GPIO
00122 
00123 callback                   Create GPIO level change callback
00124 callback_ex                Create GPIO level change callback, extended
00125 callback_cancel            Cancel a callback
00126 wait_for_edge              Wait for GPIO level change
00127 
00128 INTERMEDIATE
00129 
00130 gpio_trigger               Send a trigger pulse to a GPIO.
00131 
00132 set_watchdog               Set a watchdog on a GPIO.
00133 
00134 set_PWM_range              Configure PWM range for a GPIO
00135 get_PWM_range              Get configured PWM range for a GPIO
00136 
00137 set_PWM_frequency          Configure PWM frequency for a GPIO
00138 get_PWM_frequency          Get configured PWM frequency for a GPIO
00139 
00140 read_bank_1                Read all GPIO in bank 1
00141 read_bank_2                Read all GPIO in bank 2
00142 
00143 clear_bank_1               Clear selected GPIO in bank 1
00144 clear_bank_2               Clear selected GPIO in bank 2
00145 
00146 set_bank_1                 Set selected GPIO in bank 1
00147 set_bank_2                 Set selected GPIO in bank 2
00148 
00149 start_thread               Start a new thread
00150 stop_thread                Stop a previously started thread
00151 
00152 ADVANCED
00153 
00154 get_PWM_real_range         Get underlying PWM range for a GPIO
00155 
00156 notify_open                Request a notification handle
00157 notify_begin               Start notifications for selected GPIO
00158 notify_pause               Pause notifications
00159 notify_close               Close a notification
00160 
00161 bb_serial_read_open        Opens a GPIO for bit bang serial reads
00162 bb_serial_read             Reads bit bang serial data from a GPIO
00163 bb_serial_read_close       Closes a GPIO for bit bang serial reads
00164 bb_serial_invert           Invert serial logic (1 invert, 0 normal)
00165 
00166 hardware_clock             Start hardware clock on supported GPIO
00167 hardware_PWM               Start hardware PWM on supported GPIO
00168 
00169 set_glitch_filter          Set a glitch filter on a GPIO
00170 set_noise_filter           Set a noise filter on a GPIO
00171 
00172 get_pad_strength           Gets a pads drive strength
00173 set_pad_strength           Sets a pads drive strength
00174 
00175 shell_                     Executes a shell command
00176 
00177 SCRIPTS
00178 
00179 store_script               Store a script
00180 run_script                 Run a stored script
00181 update_script              Set a scripts parameters
00182 script_status              Get script status and parameters
00183 stop_script                Stop a running script
00184 delete_script              Delete a stored script
00185 
00186 WAVES
00187 
00188 wave_clear                 Deletes all waveforms
00189 
00190 wave_add_new               Starts a new waveform
00191 wave_add_generic           Adds a series of pulses to the waveform
00192 wave_add_serial            Adds serial data to the waveform
00193 
00194 wave_create                Creates a waveform from added data
00195 wave_delete                Deletes one or more waveforms
00196 
00197 wave_send_once             Transmits a waveform once
00198 wave_send_repeat           Transmits a waveform repeatedly
00199 wave_send_using_mode       Transmits a waveform in the chosen mode
00200 
00201 wave_chain                 Transmits a chain of waveforms
00202 
00203 wave_tx_at                 Returns the current transmitting waveform
00204 wave_tx_busy               Checks to see if the waveform has ended
00205 wave_tx_stop               Aborts the current waveform
00206 
00207 wave_get_micros            Length in microseconds of the current waveform
00208 wave_get_high_micros       Length of longest waveform so far
00209 wave_get_max_micros        Absolute maximum allowed micros
00210 
00211 wave_get_pulses            Length in pulses of the current waveform
00212 wave_get_high_pulses       Length of longest waveform so far
00213 wave_get_max_pulses        Absolute maximum allowed pulses
00214 
00215 wave_get_cbs               Length in cbs of the current waveform
00216 wave_get_high_cbs          Length of longest waveform so far
00217 wave_get_max_cbs           Absolute maximum allowed cbs
00218 
00219 I2C
00220 
00221 i2c_open                   Opens an I2C device
00222 i2c_close                  Closes an I2C device
00223 
00224 i2c_write_quick            smbus write quick
00225 i2c_write_byte             smbus write byte
00226 i2c_read_byte              smbus read byte
00227 i2c_write_byte_data        smbus write byte data
00228 i2c_write_word_data        smbus write word data
00229 i2c_read_byte_data         smbus read byte data
00230 i2c_read_word_data         smbus read word data
00231 i2c_process_call           smbus process call
00232 i2c_write_block_data       smbus write block data
00233 i2c_read_block_data        smbus read block data
00234 i2c_block_process_call     smbus block process call
00235 
00236 i2c_write_i2c_block_data   smbus write I2C block data
00237 i2c_read_i2c_block_data    smbus read I2C block data
00238 
00239 i2c_read_device            Reads the raw I2C device
00240 i2c_write_device           Writes the raw I2C device
00241 
00242 i2c_zip                    Performs multiple I2C transactions
00243 
00244 bb_i2c_open                Opens GPIO for bit banging I2C
00245 bb_i2c_close               Closes GPIO for bit banging I2C
00246 bb_i2c_zip                 Performs multiple bit banged I2C transactions
00247 
00248 SPI
00249 
00250 spi_open                   Opens a SPI device
00251 spi_close                  Closes a SPI device
00252 
00253 spi_read                   Reads bytes from a SPI device
00254 spi_write                  Writes bytes to a SPI device
00255 spi_xfer                   Transfers bytes with a SPI device
00256 
00257 bb_spi_open                Opens GPIO for bit banging SPI
00258 bb_spi_close               Closes GPIO for bit banging SPI
00259 bb_spi_xfer                Transfers bytes with bit banging SPI
00260 
00261 I2C/SPI_SLAVE
00262 
00263 bsc_xfer                   I2C/SPI as slave transfer
00264 bsc_i2c                    I2C as slave transfer
00265 
00266 SERIAL
00267 
00268 serial_open                Opens a serial device
00269 serial_close               Closes a serial device
00270 
00271 serial_write_byte          Writes a byte to a serial device
00272 serial_read_byte           Reads a byte from a serial device
00273 serial_write               Writes bytes to a serial device
00274 serial_read                Reads bytes from a serial device
00275 
00276 serial_data_available      Returns number of bytes ready to be read
00277 
00278 FILES
00279 
00280 file_open                  Opens a file
00281 file_close                 Closes a file
00282 file_read                  Reads bytes from a file
00283 file_write                 Writes bytes to a file
00284 file_seek                  Seeks to a position within a file
00285 file_list                  List files which match a pattern
00286 
00287 EVENTS
00288 
00289 event_callback            Sets a callback for an event
00290 event_callback_ex         Sets a callback for an event, extended
00291 event_callback_cancel     Cancel an event callback
00292 event_trigger             Triggers an event
00293 wait_for_event            Wait for an event
00294 
00295 CUSTOM
00296 
00297 custom_1                   User custom function 1
00298 custom_2                   User custom function 2
00299 
00300 UTILITIES
00301 
00302 get_current_tick           Get current tick (microseconds)
00303 
00304 get_hardware_revision      Get hardware revision
00305 get_pigpio_version         Get the pigpio version
00306 pigpiod_if_version         Get the pigpiod_if2 version
00307 
00308 pigpio_error               Get a text description of an error code.
00309 
00310 time_sleep                 Sleeps for a float number of seconds
00311 time_time                  Float number of seconds since the epoch
00312 
00313 OVERVIEW*/
00314 
00315 #ifdef __cplusplus
00316 extern "C" {
00317 #endif
00318 
00319 typedef void (*CBFunc_t)
00320    (int pi, unsigned user_gpio, unsigned level, uint32_t tick);
00321 
00322 typedef void (*CBFuncEx_t)
00323    (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *userdata);
00324 
00325 typedef struct callback_s callback_t;
00326 
00327 typedef void (*evtCBFunc_t)
00328    (int pi, unsigned event, uint32_t tick);
00329 
00330 typedef void (*evtCBFuncEx_t)
00331    (int pi, unsigned event, uint32_t tick, void *userdata);
00332 
00333 typedef struct evtCallback_s evtCallback_t;
00334 
00335 /*F*/
00336 double time_time(void);
00337 /*D
00338 Return the current time in seconds since the Epoch.
00339 D*/
00340 
00341 /*F*/
00342 void time_sleep(double seconds);
00343 /*D
00344 Delay execution for a given number of seconds.
00345 
00346 . .
00347 seconds: the number of seconds to delay.
00348 . .
00349 D*/
00350 
00351 /*F*/
00352 char *pigpio_error(int errnum);
00353 /*D
00354 Return a text description for an error code.
00355 
00356 . .
00357 errnum: the error code.
00358 . .
00359 D*/
00360 
00361 /*F*/
00362 unsigned pigpiod_if_version(void);
00363 /*D
00364 Return the pigpiod_if2 version.
00365 D*/
00366 
00367 /*F*/
00368 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata);
00369 /*D
00370 Starts a new thread of execution with thread_func as the main routine.
00371 
00372 . .
00373 thread_func: the main function for the new thread.
00374    userdata: a pointer to an arbitrary argument.
00375 . .
00376 
00377 Returns a pointer to pthread_t if OK, otherwise NULL.
00378 
00379 The function is passed the single argument userdata.
00380 
00381 The thread can be cancelled by passing the pointer to pthread_t to
00382 [*stop_thread*].
00383 D*/
00384 
00385 /*F*/
00386 void stop_thread(pthread_t *pth);
00387 /*D
00388 Cancels the thread pointed at by pth.
00389 
00390 . .
00391 pth: the thread to be stopped.
00392 . .
00393 
00394 No value is returned.
00395 
00396 The thread to be stopped should have been started with [*start_thread*].
00397 D*/
00398 
00399 /*F*/
00400 int pigpio_start(char *addrStr, char *portStr);
00401 /*D
00402 Connect to the pigpio daemon.  Reserving command and
00403 notification streams.
00404 
00405 . .
00406 addrStr: specifies the host or IP address of the Pi running the
00407          pigpio daemon.  It may be NULL in which case localhost
00408          is used unless overridden by the PIGPIO_ADDR environment
00409          variable.
00410 
00411 portStr: specifies the port address used by the Pi running the
00412          pigpio daemon.  It may be NULL in which case "8888"
00413          is used unless overridden by the PIGPIO_PORT environment
00414          variable.
00415 . .
00416 
00417 Returns an integer value greater than or equal to zero if OK.
00418 
00419 This value is passed to the GPIO routines to specify the Pi
00420 to be operated on.
00421 D*/
00422 
00423 /*F*/
00424 void pigpio_stop(int pi);
00425 /*D
00426 Terminates the connection to a pigpio daemon and releases
00427 resources used by the library.
00428 
00429 . .
00430 pi: >=0 (as returned by [*pigpio_start*]).
00431 . .
00432 D*/
00433 
00434 /*F*/
00435 int set_mode(int pi, unsigned gpio, unsigned mode);
00436 /*D
00437 Set the GPIO mode.
00438 
00439 . .
00440   pi: >=0 (as returned by [*pigpio_start*]).
00441 gpio: 0-53.
00442 mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1,
00443       PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5.
00444 . .
00445 
00446 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE,
00447 or PI_NOT_PERMITTED.
00448 D*/
00449 
00450 /*F*/
00451 int get_mode(int pi, unsigned gpio);
00452 /*D
00453 Get the GPIO mode.
00454 
00455 . .
00456   pi: >=0 (as returned by [*pigpio_start*]).
00457 gpio: 0-53.
00458 . .
00459 
00460 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
00461 D*/
00462 
00463 /*F*/
00464 int set_pull_up_down(int pi, unsigned gpio, unsigned pud);
00465 /*D
00466 Set or clear the GPIO pull-up/down resistor.
00467 
00468 . .
00469   pi: >=0 (as returned by [*pigpio_start*]).
00470 gpio: 0-53.
00471  pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF.
00472 . .
00473 
00474 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD,
00475 or PI_NOT_PERMITTED.
00476 D*/
00477 
00478 /*F*/
00479 int gpio_read(int pi, unsigned gpio);
00480 /*D
00481 Read the GPIO level.
00482 
00483 . .
00484   pi: >=0 (as returned by [*pigpio_start*]).
00485 gpio:0-53.
00486 . .
00487 
00488 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
00489 D*/
00490 
00491 /*F*/
00492 int gpio_write(int pi, unsigned gpio, unsigned level);
00493 /*D
00494 Write the GPIO level.
00495 
00496 . .
00497    pi: >=0 (as returned by [*pigpio_start*]).
00498  gpio: 0-53.
00499 level: 0, 1.
00500 . .
00501 
00502 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL,
00503 or PI_NOT_PERMITTED.
00504 
00505 Notes
00506 
00507 If PWM or servo pulses are active on the GPIO they are switched off.
00508 D*/
00509 
00510 /*F*/
00511 int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle);
00512 /*D
00513 Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO.
00514 
00515 . .
00516        pi: >=0 (as returned by [*pigpio_start*]).
00517 user_gpio: 0-31.
00518 dutycycle: 0-range (range defaults to 255).
00519 . .
00520 
00521 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE,
00522 or PI_NOT_PERMITTED.
00523 Notes
00524 
00525 The [*set_PWM_range*] function may be used to change the
00526 default range of 255.
00527 D*/
00528 
00529 /*F*/
00530 int get_PWM_dutycycle(int pi, unsigned user_gpio);
00531 /*D
00532 Return the PWM dutycycle in use on a GPIO.
00533 
00534 . .
00535        pi: >=0 (as returned by [*pigpio_start*]).
00536 user_gpio: 0-31.
00537 . .
00538 
00539 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
00540 
00541 For normal PWM the dutycycle will be out of the defined range
00542 for the GPIO (see [*get_PWM_range*]).
00543 
00544 If a hardware clock is active on the GPIO the reported dutycycle
00545 will be 500000 (500k) out of 1000000 (1M).
00546 
00547 If hardware PWM is active on the GPIO the reported dutycycle
00548 will be out of a 1000000 (1M).
00549 D*/
00550 
00551 /*F*/
00552 int set_PWM_range(int pi, unsigned user_gpio, unsigned range);
00553 /*D
00554 Set the range of PWM values to be used on the GPIO.
00555 
00556 . .
00557        pi: >=0 (as returned by [*pigpio_start*]).
00558 user_gpio: 0-31.
00559     range: 25-40000.
00560 . .
00561 
00562 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE,
00563 or PI_NOT_PERMITTED.
00564 
00565 Notes
00566 
00567 If PWM is currently active on the GPIO its dutycycle will be
00568 scaled to reflect the new range.
00569 
00570 The real range, the number of steps between fully off and fully on
00571 for each of the 18 available GPIO frequencies is
00572 
00573 . .
00574   25(#1),    50(#2),   100(#3),   125(#4),    200(#5),    250(#6),
00575  400(#7),   500(#8),   625(#9),   800(#10),  1000(#11),  1250(#12),
00576 2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18)
00577 . .
00578 
00579 The real value set by set_PWM_range is (dutycycle * real range) / range.
00580 D*/
00581 
00582 /*F*/
00583 int get_PWM_range(int pi, unsigned user_gpio);
00584 /*D
00585 Get the range of PWM values being used on the GPIO.
00586 
00587 . .
00588        pi: >=0 (as returned by [*pigpio_start*]).
00589 user_gpio: 0-31.
00590 . .
00591 
00592 Returns the dutycycle range used for the GPIO if OK,
00593 otherwise PI_BAD_USER_GPIO.
00594 
00595 If a hardware clock or hardware PWM is active on the GPIO the
00596 reported range will be 1000000 (1M).
00597 D*/
00598 
00599 /*F*/
00600 int get_PWM_real_range(int pi, unsigned user_gpio);
00601 /*D
00602 Get the real underlying range of PWM values being used on the GPIO.
00603 
00604 . .
00605        pi: >=0 (as returned by [*pigpio_start*]).
00606 user_gpio: 0-31.
00607 . .
00608 
00609 Returns the real range used for the GPIO if OK,
00610 otherwise PI_BAD_USER_GPIO.
00611 
00612 If a hardware clock is active on the GPIO the reported
00613 real range will be 1000000 (1M).
00614 
00615 If hardware PWM is active on the GPIO the reported real range
00616 will be approximately 250M divided by the set PWM frequency.
00617 
00618 D*/
00619 
00620 /*F*/
00621 int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency);
00622 /*D
00623 Set the frequency (in Hz) of the PWM to be used on the GPIO.
00624 
00625 . .
00626        pi: >=0 (as returned by [*pigpio_start*]).
00627 user_gpio: 0-31.
00628 frequency: >=0 (Hz).
00629 . .
00630 
00631 Returns the numerically closest frequency if OK, otherwise
00632 PI_BAD_USER_GPIO or PI_NOT_PERMITTED.
00633 
00634 If PWM is currently active on the GPIO it will be switched
00635 off and then back on at the new frequency.
00636 
00637 Each GPIO can be independently set to one of 18 different
00638 PWM frequencies.
00639 
00640 The selectable frequencies depend upon the sample rate which
00641 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5).  The
00642 sample rate is set when the pigpio daemon is started.
00643 
00644 The frequencies for each sample rate are:
00645 
00646 . .
00647                        Hertz
00648 
00649        1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
00650            1250  1000   800  500  400  250  200  100   50
00651 
00652        2: 20000 10000  5000 4000 2500 2000 1250 1000  800
00653             625   500   400  250  200  125  100   50   25
00654 
00655        4: 10000  5000  2500 2000 1250 1000  625  500  400
00656             313   250   200  125  100   63   50   25   13
00657 sample
00658  rate
00659  (us)  5:  8000  4000  2000 1600 1000  800  500  400  320
00660             250   200   160  100   80   50   40   20   10
00661 
00662        8:  5000  2500  1250 1000  625  500  313  250  200
00663             156   125   100   63   50   31   25   13    6
00664 
00665       10:  4000  2000  1000  800  500  400  250  200  160
00666             125   100    80   50   40   25   20   10    5
00667 . .
00668 D*/
00669 
00670 /*F*/
00671 int get_PWM_frequency(int pi, unsigned user_gpio);
00672 /*D
00673 Get the frequency of PWM being used on the GPIO.
00674 
00675 . .
00676        pi: >=0 (as returned by [*pigpio_start*]).
00677 user_gpio: 0-31.
00678 . .
00679 
00680 For normal PWM the frequency will be that defined for the GPIO by
00681 [*set_PWM_frequency*].
00682 
00683 If a hardware clock is active on the GPIO the reported frequency
00684 will be that set by [*hardware_clock*].
00685 
00686 If hardware PWM is active on the GPIO the reported frequency
00687 will be that set by [*hardware_PWM*].
00688 
00689 Returns the frequency (in hertz) used for the GPIO if OK,
00690 otherwise PI_BAD_USER_GPIO.
00691 D*/
00692 
00693 /*F*/
00694 int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth);
00695 /*D
00696 Start (500-2500) or stop (0) servo pulses on the GPIO.
00697 
00698 . .
00699         pi: >=0 (as returned by [*pigpio_start*]).
00700  user_gpio: 0-31.
00701 pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise).
00702 . .
00703 
00704 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or
00705 PI_NOT_PERMITTED.
00706 
00707 The selected pulsewidth will continue to be transmitted until
00708 changed by a subsequent call to set_servo_pulsewidth.
00709 
00710 The pulsewidths supported by servos varies and should probably be
00711 determined by experiment. A value of 1500 should always be safe and
00712 represents the mid-point of rotation.
00713 
00714 You can DAMAGE a servo if you command it to move beyond its limits.
00715 
00716 OTHER UPDATE RATES:
00717 
00718 This function updates servos at 50Hz.  If you wish to use a different
00719 update frequency you will have to use the PWM functions.
00720 
00721 . .
00722 Update Rate (Hz)     50   100  200  400  500
00723 1E6/Hz            20000 10000 5000 2500 2000
00724 . .
00725 
00726 Firstly set the desired PWM frequency using [*set_PWM_frequency*].
00727 
00728 Then set the PWM range using [*set_PWM_range*] to 1E6/Hz.
00729 Doing this allows you to use units of microseconds when setting
00730 the servo pulsewidth.
00731 
00732 E.g. If you want to update a servo connected to GPIO 25 at 400Hz
00733 
00734 . .
00735 set_PWM_frequency(25, 400);
00736 set_PWM_range(25, 2500);
00737 . .
00738 
00739 Thereafter use the [*set_PWM_dutycycle*] function to move the servo,
00740 e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. 
00741 D*/
00742 
00743 /*F*/
00744 int get_servo_pulsewidth(int pi, unsigned user_gpio);
00745 /*D
00746 Return the servo pulsewidth in use on a GPIO.
00747 
00748 . .
00749        pi: >=0 (as returned by [*pigpio_start*]).
00750 user_gpio: 0-31.
00751 . .
00752 
00753 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
00754 D*/
00755 
00756 /*F*/
00757 int notify_open(int pi);
00758 /*D
00759 Get a free notification handle.
00760 
00761 . .
00762 pi: >=0 (as returned by [*pigpio_start*]).
00763 . .
00764 
00765 Returns a handle greater than or equal to zero if OK,
00766 otherwise PI_NO_HANDLE.
00767 
00768 A notification is a method for being notified of GPIO state
00769 changes via a pipe.
00770 
00771 Pipes are only accessible from the local machine so this function
00772 serves no purpose if you are using the library from a remote machine.
00773 The in-built (socket) notifications provided by [*callback*]
00774 should be used instead.
00775 
00776 Notifications for handle x will be available at the pipe
00777 named /dev/pigpiox (where x is the handle number).
00778 E.g. if the function returns 15 then the notifications must be
00779 read from /dev/pigpio15.
00780 D*/
00781 
00782 /*F*/
00783 int notify_begin(int pi, unsigned handle, uint32_t bits);
00784 /*D
00785 Start notifications on a previously opened handle.
00786 
00787 . .
00788     pi: >=0 (as returned by [*pigpio_start*]).
00789 handle: 0-31 (as returned by [*notify_open*])
00790   bits: a mask indicating the GPIO to be notified.
00791 . .
00792 
00793 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00794 
00795 The notification sends state changes for each GPIO whose
00796 corresponding bit in bits is set.
00797 
00798 Each notification occupies 12 bytes in the fifo as follows:
00799 
00800 . .
00801 typedef struct
00802 {
00803    uint16_t seqno;
00804    uint16_t flags;
00805    uint32_t tick;
00806    uint32_t level;
00807 } gpioReport_t;
00808 . .
00809 
00810 seqno: starts at 0 each time the handle is opened and then increments
00811 by one for each report.
00812 
00813 flags: three flags are defined, PI_NTFY_FLAGS_WDOG,
00814 PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT.
00815 
00816 If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags
00817 indicate a GPIO which has had a watchdog timeout.
00818 
00819 If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive
00820 signal on the pipe/socket and is sent once a minute in the absence
00821 of other notification activity.
00822 
00823 If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags
00824 indicate an event which has been triggered.
00825 
00826 tick: the number of microseconds since system boot.  It wraps around
00827 after 1h12m.
00828 
00829 level: indicates the level of each GPIO.  If bit 1<<x is set then
00830 GPIO x is high.
00831 D*/
00832 
00833 /*F*/
00834 int notify_pause(int pi, unsigned handle);
00835 /*D
00836 Pause notifications on a previously opened handle.
00837 
00838 . .
00839     pi: >=0 (as returned by [*pigpio_start*]).
00840 handle: 0-31 (as returned by [*notify_open*])
00841 . .
00842 
00843 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00844 
00845 Notifications for the handle are suspended until
00846 [*notify_begin*] is called again.
00847 D*/
00848 
00849 /*F*/
00850 int notify_close(int pi, unsigned handle);
00851 /*D
00852 Stop notifications on a previously opened handle and
00853 release the handle for reuse.
00854 
00855 . .
00856     pi: >=0 (as returned by [*pigpio_start*]).
00857 handle: 0-31 (as returned by [*notify_open*])
00858 . .
00859 
00860 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00861 D*/
00862 
00863 /*F*/
00864 int set_watchdog(int pi, unsigned user_gpio, unsigned timeout);
00865 /*D
00866 Sets a watchdog for a GPIO.
00867 
00868 . .
00869        pi: >=0 (as returned by [*pigpio_start*]).
00870 user_gpio: 0-31.
00871   timeout: 0-60000.
00872 . .
00873 
00874 Returns 0 if OK, otherwise PI_BAD_USER_GPIO
00875 or PI_BAD_WDOG_TIMEOUT.
00876 
00877 The watchdog is nominally in milliseconds.
00878 
00879 Only one watchdog may be registered per GPIO.
00880 
00881 The watchdog may be cancelled by setting timeout to 0.
00882 
00883 Once a watchdog has been started callbacks for the GPIO will be
00884 triggered every timeout interval after the last GPIO activity.
00885 
00886 The callback will receive the special level PI_TIMEOUT.
00887 D*/
00888 
00889 /*F*/
00890 int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady);
00891 /*D
00892 Sets a glitch filter on a GPIO.
00893 
00894 Level changes on the GPIO are not reported unless the level
00895 has been stable for at least [*steady*] microseconds.  The
00896 level is then reported.  Level changes of less than
00897 [*steady*] microseconds are ignored.
00898 
00899 . .
00900        pi: >=0 (as returned by [*pigpio_start*]).
00901 user_gpio: 0-31
00902    steady: 0-300000
00903 . .
00904 
00905 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
00906 
00907 This filter affects the GPIO samples returned to callbacks set up
00908 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
00909 
00910 It does not affect levels read by [*gpio_read*],
00911 [*read_bank_1*], or [*read_bank_2*].
00912 
00913 Each (stable) edge will be timestamped [*steady*] microseconds
00914 after it was first detected.
00915 D*/
00916 
00917 /*F*/
00918 int set_noise_filter(
00919    int pi, unsigned user_gpio, unsigned steady, unsigned active);
00920 /*D
00921 Sets a noise filter on a GPIO.
00922 
00923 Level changes on the GPIO are ignored until a level which has
00924 been stable for [*steady*] microseconds is detected.  Level changes
00925 on the GPIO are then reported for [*active*] microseconds after
00926 which the process repeats.
00927 
00928 . .
00929        pi: >=0 (as returned by [*pigpio_start*]).
00930 user_gpio: 0-31
00931    steady: 0-300000
00932    active: 0-1000000
00933 . .
00934 
00935 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
00936 
00937 This filter affects the GPIO samples returned to callbacks set up
00938 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
00939 
00940 It does not affect levels read by [*gpio_read*],
00941 [*read_bank_1*], or [*read_bank_2*].
00942 
00943 Level changes before and after the active period may
00944 be reported.  Your software must be designed to cope with
00945 such reports.
00946 D*/
00947 
00948 /*F*/
00949 uint32_t read_bank_1(int pi);
00950 /*D
00951 Read the levels of the bank 1 GPIO (GPIO 0-31).
00952 
00953 . .
00954 pi: >=0 (as returned by [*pigpio_start*]).
00955 . .
00956 
00957 The returned 32 bit integer has a bit set if the corresponding
00958 GPIO is logic 1.  GPIO n has bit value (1<<n).
00959 D*/
00960 
00961 /*F*/
00962 uint32_t read_bank_2(int pi);
00963 /*D
00964 Read the levels of the bank 2 GPIO (GPIO 32-53).
00965 
00966 . .
00967 pi: >=0 (as returned by [*pigpio_start*]).
00968 . .
00969 
00970 The returned 32 bit integer has a bit set if the corresponding
00971 GPIO is logic 1.  GPIO n has bit value (1<<(n-32)).
00972 D*/
00973 
00974 /*F*/
00975 int clear_bank_1(int pi, uint32_t bits);
00976 /*D
00977 Clears GPIO 0-31 if the corresponding bit in bits is set.
00978 
00979 . .
00980   pi: >=0 (as returned by [*pigpio_start*]).
00981 bits: a bit mask with 1 set if the corresponding GPIO is
00982       to be cleared.
00983 . .
00984 
00985 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
00986 
00987 A status of PI_SOME_PERMITTED indicates that the user is not
00988 allowed to write to one or more of the GPIO.
00989 D*/
00990 
00991 /*F*/
00992 int clear_bank_2(int pi, uint32_t bits);
00993 /*D
00994 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
00995 
00996 . .
00997   pi: >=0 (as returned by [*pigpio_start*]).
00998 bits: a bit mask with 1 set if the corresponding GPIO is
00999       to be cleared.
01000 . .
01001 
01002 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
01003 
01004 A status of PI_SOME_PERMITTED indicates that the user is not
01005 allowed to write to one or more of the GPIO.
01006 D*/
01007 
01008 /*F*/
01009 int set_bank_1(int pi, uint32_t bits);
01010 /*D
01011 Sets GPIO 0-31 if the corresponding bit in bits is set.
01012 
01013 . .
01014   pi: >=0 (as returned by [*pigpio_start*]).
01015 bits: a bit mask with 1 set if the corresponding GPIO is
01016       to be set.
01017 . .
01018 
01019 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
01020 
01021 A status of PI_SOME_PERMITTED indicates that the user is not
01022 allowed to write to one or more of the GPIO.
01023 D*/
01024 
01025 /*F*/
01026 int set_bank_2(int pi, uint32_t bits);
01027 /*D
01028 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
01029 
01030 . .
01031   pi: >=0 (as returned by [*pigpio_start*]).
01032 bits: a bit mask with 1 set if the corresponding GPIO is
01033       to be set.
01034 . .
01035 
01036 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
01037 
01038 A status of PI_SOME_PERMITTED indicates that the user is not
01039 allowed to write to one or more of the GPIO.
01040 D*/
01041 
01042 
01043 /*F*/
01044 int hardware_clock(int pi, unsigned gpio, unsigned clkfreq);
01045 /*D
01046 Starts a hardware clock on a GPIO at the specified frequency.
01047 Frequencies above 30MHz are unlikely to work.
01048 
01049 . .
01050        pi: >=0 (as returned by [*pigpio_start*]).
01051      gpio: see description
01052 frequency: 0 (off) or 4689-250000000 (250M)
01053 . .
01054 
01055 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
01056 PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
01057 
01058 The same clock is available on multiple GPIO.  The latest
01059 frequency setting will be used by all GPIO which share a clock.
01060 
01061 The GPIO must be one of the following.
01062 
01063 . .
01064 4   clock 0  All models
01065 5   clock 1  All models but A and B (reserved for system use)
01066 6   clock 2  All models but A and B
01067 20  clock 0  All models but A and B
01068 21  clock 1  All models but A and Rev.2 B (reserved for system use)
01069 
01070 32  clock 0  Compute module only
01071 34  clock 0  Compute module only
01072 42  clock 1  Compute module only (reserved for system use)
01073 43  clock 2  Compute module only
01074 44  clock 1  Compute module only (reserved for system use)
01075 . .
01076 
01077 Access to clock 1 is protected by a password as its use will likely
01078 crash the Pi.  The password is given by or'ing 0x5A000000 with the
01079 GPIO number.
01080 D*/
01081 
01082 
01083 /*F*/
01084 int hardware_PWM(int pi, unsigned gpio, unsigned PWMfreq, uint32_t PWMduty);
01085 /*D
01086 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
01087 Frequencies above 30MHz are unlikely to work.
01088 
01089 NOTE: Any waveform started by [*wave_send_**] or [*wave_chain*]
01090 will be cancelled.
01091 
01092 This function is only valid if the pigpio main clock is PCM.  The
01093 main clock defaults to PCM but may be overridden when the pigpio
01094 daemon is started (option -t).
01095 
01096 . .
01097      pi: >=0 (as returned by [*pigpio_start*]).
01098    gpio: see descripton
01099 PWMfreq: 0 (off) or 1-125000000 (125M)
01100 PWMduty: 0 (off) to 1000000 (1M)(fully on)
01101 . .
01102 
01103 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
01104 PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ,
01105 or PI_HPWM_ILLEGAL.
01106 
01107 The same PWM channel is available on multiple GPIO.  The latest
01108 frequency and dutycycle setting will be used by all GPIO which
01109 share a PWM channel.
01110 
01111 The GPIO must be one of the following.
01112 
01113 . .
01114 12  PWM channel 0  All models but A and B
01115 13  PWM channel 1  All models but A and B
01116 18  PWM channel 0  All models
01117 19  PWM channel 1  All models but A and B
01118 
01119 40  PWM channel 0  Compute module only
01120 41  PWM channel 1  Compute module only
01121 45  PWM channel 1  Compute module only
01122 52  PWM channel 0  Compute module only
01123 53  PWM channel 1  Compute module only
01124 . .
01125 
01126 The actual number of steps beween off and fully on is the
01127 integral part of 250 million divided by PWMfreq.
01128 
01129 The actual frequency set is 250 million / steps.
01130 
01131 There will only be a million steps for a PWMfreq of 250.
01132 Lower frequencies will have more steps and higher
01133 frequencies will have fewer steps.  PWMduty is
01134 automatically scaled to take this into account.
01135 D*/
01136 
01137 
01138 /*F*/
01139 uint32_t get_current_tick(int pi);
01140 /*D
01141 Gets the current system tick.
01142 
01143 . .
01144 pi: >=0 (as returned by [*pigpio_start*]).
01145 . .
01146 
01147 Tick is the number of microseconds since system boot.
01148 
01149 As tick is an unsigned 32 bit quantity it wraps around after
01150 2**32 microseconds, which is approximately 1 hour 12 minutes.
01151 
01152 D*/
01153 
01154 /*F*/
01155 uint32_t get_hardware_revision(int pi);
01156 /*D
01157 Get the Pi's hardware revision number.
01158 
01159 . .
01160 pi: >=0 (as returned by [*pigpio_start*]).
01161 . .
01162 
01163 The hardware revision is the last few characters on the Revision line
01164 of /proc/cpuinfo.
01165 
01166 If the hardware revision can not be found or is not a valid
01167 hexadecimal number the function returns 0.
01168 
01169 The revision number can be used to determine the assignment of GPIO
01170 to pins (see [*gpio*]).
01171 
01172 There are at least three types of board.
01173 
01174 Type 1 boards have hardware revision numbers of 2 and 3.
01175 
01176 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
01177 
01178 Type 3 boards have hardware revision numbers of 16 or greater.
01179 D*/
01180 
01181 /*F*/
01182 uint32_t get_pigpio_version(int pi);
01183 /*D
01184 Returns the pigpio version.
01185 
01186 . .
01187 pi: >=0 (as returned by [*pigpio_start*]).
01188 . .
01189 D*/
01190 
01191 
01192 /*F*/
01193 int wave_clear(int pi);
01194 /*D
01195 This function clears all waveforms and any data added by calls to the
01196 [*wave_add_**] functions.
01197 
01198 . .
01199 pi: >=0 (as returned by [*pigpio_start*]).
01200 . .
01201 
01202 Returns 0 if OK.
01203 D*/
01204 
01205 /*F*/
01206 int wave_add_new(int pi);
01207 /*D
01208 This function starts a new empty waveform.  You wouldn't normally need
01209 to call this function as it is automatically called after a waveform is
01210 created with the [*wave_create*] function.
01211 
01212 . .
01213 pi: >=0 (as returned by [*pigpio_start*]).
01214 . .
01215 
01216 Returns 0 if OK.
01217 D*/
01218 
01219 /*F*/
01220 int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses);
01221 /*D
01222 This function adds a number of pulses to the current waveform.
01223 
01224 . .
01225        pi: >=0 (as returned by [*pigpio_start*]).
01226 numPulses: the number of pulses.
01227    pulses: an array of pulses.
01228 . .
01229 
01230 Returns the new total number of pulses in the current waveform if OK,
01231 otherwise PI_TOO_MANY_PULSES.
01232 
01233 The pulses are interleaved in time order within the existing waveform
01234 (if any).
01235 
01236 Merging allows the waveform to be built in parts, that is the settings
01237 for GPIO#1 can be added, and then GPIO#2 etc.
01238 
01239 If the added waveform is intended to start after or within the existing
01240 waveform then the first pulse should consist solely of a delay.
01241 D*/
01242 
01243 /*F*/
01244 int wave_add_serial
01245    (int pi, unsigned user_gpio, unsigned baud, unsigned data_bits,
01246     unsigned stop_bits, unsigned offset, unsigned numBytes, char *str);
01247 /*D
01248 This function adds a waveform representing serial data to the
01249 existing waveform (if any).  The serial data starts offset
01250 microseconds from the start of the waveform.
01251 
01252 . .
01253        pi: >=0 (as returned by [*pigpio_start*]).
01254 user_gpio: 0-31.
01255      baud: 50-1000000
01256 data_bits: number of data bits (1-32)
01257 stop_bits: number of stop half bits (2-8)
01258    offset: >=0
01259  numBytes: >=1
01260       str: an array of chars.
01261 . .
01262 
01263 Returns the new total number of pulses in the current waveform if OK,
01264 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
01265 PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
01266 or PI_TOO_MANY_PULSES.
01267 
01268 NOTES:
01269 
01270 The serial data is formatted as one start bit, [*data_bits*] data bits,
01271 and [*stop_bits*]/2 stop bits.
01272 
01273 It is legal to add serial data streams with different baud rates to
01274 the same waveform.
01275 
01276 [*numBytes*] is the number of bytes of data in str.
01277 
01278 The bytes required for each character depend upon [*data_bits*].
01279 
01280 For [*data_bits*] 1-8 there will be one byte per character. 
01281 For [*data_bits*] 9-16 there will be two bytes per character. 
01282 For [*data_bits*] 17-32 there will be four bytes per character.
01283 D*/
01284 
01285 /*F*/
01286 int wave_create(int pi);
01287 /*D
01288 This function creates a waveform from the data provided by the prior
01289 calls to the [*wave_add_**] functions.  Upon success a wave id
01290 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
01291 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
01292 
01293 . .
01294 pi: >=0 (as returned by [*pigpio_start*]).
01295 . .
01296 
01297 The data provided by the [*wave_add_**] functions is consumed by this
01298 function.
01299 
01300 As many waveforms may be created as there is space available.  The
01301 wave id is passed to [*wave_send_**] to specify the waveform to transmit.
01302 
01303 Normal usage would be
01304 
01305 Step 1. [*wave_clear*] to clear all waveforms and added data.
01306 
01307 Step 2. [*wave_add_**] calls to supply the waveform data.
01308 
01309 Step 3. [*wave_create*] to create the waveform and get a unique id
01310 
01311 Repeat steps 2 and 3 as needed.
01312 
01313 Step 4. [*wave_send_**] with the id of the waveform to transmit.
01314 
01315 A waveform comprises one or more pulses.  Each pulse consists of a
01316 [*gpioPulse_t*] structure.
01317 
01318 . .
01319 typedef struct
01320 {
01321    uint32_t gpioOn;
01322    uint32_t gpioOff;
01323    uint32_t usDelay;
01324 } gpioPulse_t;
01325 . .
01326 
01327 The fields specify
01328 
01329 1) the GPIO to be switched on at the start of the pulse. 
01330 2) the GPIO to be switched off at the start of the pulse. 
01331 3) the delay in microseconds before the next pulse. 
01332 
01333 Any or all the fields can be zero.  It doesn't make any sense to
01334 set all the fields to zero (the pulse will be ignored).
01335 
01336 When a waveform is started each pulse is executed in order with the
01337 specified delay between the pulse and the next.
01338 
01339 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
01340 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
01341 D*/
01342 
01343 
01344 /*F*/
01345 int wave_delete(int pi, unsigned wave_id);
01346 /*D
01347 This function deletes the waveform with id wave_id.
01348 
01349 . .
01350      pi: >=0 (as returned by [*pigpio_start*]).
01351 wave_id: >=0, as returned by [*wave_create*].
01352 . .
01353 
01354 Wave ids are allocated in order, 0, 1, 2, etc.
01355 
01356 The wave is flagged for deletion.  The resources used by the wave
01357 will only be reused when either of the following apply.
01358 
01359 - all waves with higher numbered wave ids have been deleted or have
01360 been flagged for deletion.
01361 
01362 - a new wave is created which uses exactly the same resources as
01363 the current wave (see the C source for gpioWaveCreate for details).
01364 
01365 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
01366 D*/
01367 
01368 
01369 /*F*/
01370 int wave_send_once(int pi, unsigned wave_id);
01371 /*D
01372 This function transmits the waveform with id wave_id.  The waveform
01373 is sent once.
01374 
01375 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01376 
01377 . .
01378      pi: >=0 (as returned by [*pigpio_start*]).
01379 wave_id: >=0, as returned by [*wave_create*].
01380 . .
01381 
01382 Returns the number of DMA control blocks in the waveform if OK,
01383 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
01384 D*/
01385 
01386 
01387 /*F*/
01388 int wave_send_repeat(int pi, unsigned wave_id);
01389 /*D
01390 This function transmits the waveform with id wave_id.  The waveform
01391 cycles until cancelled (either by the sending of a new waveform or
01392 by [*wave_tx_stop*]).
01393 
01394 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01395 
01396 . .
01397      pi: >=0 (as returned by [*pigpio_start*]).
01398 wave_id: >=0, as returned by [*wave_create*].
01399 . .
01400 
01401 Returns the number of DMA control blocks in the waveform if OK,
01402 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
01403 D*/
01404 
01405 
01406 /*F*/
01407 int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode);
01408 /*D
01409 Transmits the waveform with id wave_id using mode mode.
01410 
01411 . .
01412      pi: >=0 (as returned by [*pigpio_start*]).
01413 wave_id: >=0, as returned by [*wave_create*].
01414    mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT,
01415          PI_WAVE_MODE_ONE_SHOT_SYNC, or PI_WAVE_MODE_REPEAT_SYNC.
01416 . .
01417 
01418 PI_WAVE_MODE_ONE_SHOT: same as [*wave_send_once*].
01419 
01420 PI_WAVE_MODE_REPEAT same as [*wave_send_repeat*].
01421 
01422 PI_WAVE_MODE_ONE_SHOT_SYNC same as [*wave_send_once*] but tries
01423 to sync with the previous waveform.
01424 
01425 PI_WAVE_MODE_REPEAT_SYNC same as [*wave_send_repeat*] but tries
01426 to sync with the previous waveform.
01427 
01428 WARNING: bad things may happen if you delete the previous
01429 waveform before it has been synced to the new waveform.
01430 
01431 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01432 
01433 Returns the number of DMA control blocks in the waveform if OK,
01434 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
01435 D*/
01436 
01437 /*F*/
01438 int wave_chain(int pi, char *buf, unsigned bufSize);
01439 /*D
01440 This function transmits a chain of waveforms.
01441 
01442 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01443 
01444 The waves to be transmitted are specified by the contents of buf
01445 which contains an ordered list of [*wave_id*]s and optional command
01446 codes and related data.
01447 
01448 . .
01449      pi: >=0 (as returned by [*pigpio_start*]).
01450     buf: pointer to the wave_ids and optional command codes
01451 bufSize: the number of bytes in buf
01452 . .
01453 
01454 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
01455 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
01456 
01457 Each wave is transmitted in the order specified.  A wave may
01458 occur multiple times per chain.
01459 
01460 A blocks of waves may be transmitted multiple times by using
01461 the loop commands. The block is bracketed by loop start and
01462 end commands.  Loops may be nested.
01463 
01464 Delays between waves may be added with the delay command.
01465 
01466 The following command codes are supported:
01467 
01468 Name         @ Cmd & Data @ Meaning
01469 Loop Start   @ 255 0      @ Identify start of a wave block
01470 Loop Repeat  @ 255 1 x y  @ loop x + y*256 times
01471 Delay        @ 255 2 x y  @ delay x + y*256 microseconds
01472 Loop Forever @ 255 3      @ loop forever
01473 
01474 If present Loop Forever must be the last entry in the chain.
01475 
01476 The code is currently dimensioned to support a chain with roughly
01477 600 entries and 20 loop counters.
01478 
01479 ...
01480 #include <stdio.h>
01481 #include <pigpiod_if2.h>
01482 
01483 #define WAVES 5
01484 #define GPIO 4
01485 
01486 int main(int argc, char *argv[])
01487 {
01488    int i, pi, wid[WAVES];
01489 
01490    pi = pigpio_start(0, 0);
01491    if (pi<0) return -1;
01492 
01493    set_mode(pi, GPIO, PI_OUTPUT);
01494 
01495    for (i=0; i<WAVES; i++)
01496    {
01497       wave_add_generic(pi, 2, (gpioPulse_t[])
01498          {{1<<GPIO, 0,        20},
01499           {0, 1<<GPIO, (i+1)*200}});
01500 
01501       wid[i] = wave_create(pi);
01502    }
01503 
01504    wave_chain(pi, (char []) {
01505       wid[4], wid[3], wid[2],       // transmit waves 4+3+2
01506       255, 0,                       // loop start
01507          wid[0], wid[0], wid[0],    // transmit waves 0+0+0
01508          255, 0,                    // loop start
01509             wid[0], wid[1],         // transmit waves 0+1
01510             255, 2, 0x88, 0x13,     // delay 5000us
01511          255, 1, 30, 0,             // loop end (repeat 30 times)
01512          255, 0,                    // loop start
01513             wid[2], wid[3], wid[0], // transmit waves 2+3+0
01514             wid[3], wid[1], wid[2], // transmit waves 3+1+2
01515          255, 1, 10, 0,             // loop end (repeat 10 times)
01516       255, 1, 5, 0,                 // loop end (repeat 5 times)
01517       wid[4], wid[4], wid[4],       // transmit waves 4+4+4
01518       255, 2, 0x20, 0x4E,           // delay 20000us
01519       wid[0], wid[0], wid[0],       // transmit waves 0+0+0
01520 
01521       }, 46);
01522 
01523    while (wave_tx_busy(pi)) time_sleep(0.1);
01524 
01525    for (i=0; i<WAVES; i++) wave_delete(pi, wid[i]);
01526 
01527    pigpio_stop(pi);
01528 }
01529 ...
01530 D*/
01531 
01532 
01533 /*F*/
01534 int wave_tx_at(int pi);
01535 /*D
01536 This function returns the id of the waveform currently being
01537 transmitted.
01538 
01539 . .
01540 pi: >=0 (as returned by [*pigpio_start*]).
01541 . .
01542 
01543 Returns the waveform id or one of the following special values:
01544 
01545 PI_WAVE_NOT_FOUND (9998) - transmitted wave not found. 
01546 PI_NO_TX_WAVE (9999) - no wave being transmitted.
01547 D*/
01548 
01549 /*F*/
01550 int wave_tx_busy(int pi);
01551 /*D
01552 This function checks to see if a waveform is currently being
01553 transmitted.
01554 
01555 . .
01556 pi: >=0 (as returned by [*pigpio_start*]).
01557 . .
01558 
01559 Returns 1 if a waveform is currently being transmitted, otherwise 0.
01560 D*/
01561 
01562 /*F*/
01563 int wave_tx_stop(int pi);
01564 /*D
01565 This function stops the transmission of the current waveform.
01566 
01567 . .
01568 pi: >=0 (as returned by [*pigpio_start*]).
01569 . .
01570 
01571 Returns 0 if OK.
01572 
01573 This function is intended to stop a waveform started with the repeat mode.
01574 D*/
01575 
01576 /*F*/
01577 int wave_get_micros(int pi);
01578 /*D
01579 This function returns the length in microseconds of the current
01580 waveform.
01581 
01582 . .
01583 pi: >=0 (as returned by [*pigpio_start*]).
01584 . .
01585 D*/
01586 
01587 /*F*/
01588 int wave_get_high_micros(int pi);
01589 /*D
01590 This function returns the length in microseconds of the longest waveform
01591 created since the pigpio daemon was started.
01592 
01593 . .
01594 pi: >=0 (as returned by [*pigpio_start*]).
01595 . .
01596 D*/
01597 
01598 /*F*/
01599 int wave_get_max_micros(int pi);
01600 /*D
01601 This function returns the maximum possible size of a waveform in 
01602 microseconds.
01603 
01604 . .
01605 pi: >=0 (as returned by [*pigpio_start*]).
01606 . .
01607 D*/
01608 
01609 /*F*/
01610 int wave_get_pulses(int pi);
01611 /*D
01612 This function returns the length in pulses of the current waveform.
01613 
01614 . .
01615 pi: >=0 (as returned by [*pigpio_start*]).
01616 . .
01617 D*/
01618 
01619 /*F*/
01620 int wave_get_high_pulses(int pi);
01621 /*D
01622 This function returns the length in pulses of the longest waveform
01623 created since the pigpio daemon was started.
01624 
01625 . .
01626 pi: >=0 (as returned by [*pigpio_start*]).
01627 . .
01628 D*/
01629 
01630 /*F*/
01631 int wave_get_max_pulses(int pi);
01632 /*D
01633 This function returns the maximum possible size of a waveform in pulses.
01634 
01635 . .
01636 pi: >=0 (as returned by [*pigpio_start*]).
01637 . .
01638 D*/
01639 
01640 /*F*/
01641 int wave_get_cbs(int pi);
01642 /*D
01643 This function returns the length in DMA control blocks of the current
01644 waveform.
01645 
01646 . .
01647 pi: >=0 (as returned by [*pigpio_start*]).
01648 . .
01649 D*/
01650 
01651 /*F*/
01652 int wave_get_high_cbs(int pi);
01653 /*D
01654 This function returns the length in DMA control blocks of the longest
01655 waveform created since the pigpio daemon was started.
01656 
01657 . .
01658 pi: >=0 (as returned by [*pigpio_start*]).
01659 . .
01660 D*/
01661 
01662 /*F*/
01663 int wave_get_max_cbs(int pi);
01664 /*D
01665 This function returns the maximum possible size of a waveform in DMA
01666 control blocks.
01667 
01668 . .
01669 pi: >=0 (as returned by [*pigpio_start*]).
01670 . .
01671 D*/
01672 
01673 /*F*/
01674 int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, unsigned level);
01675 /*D
01676 This function sends a trigger pulse to a GPIO.  The GPIO is set to
01677 level for pulseLen microseconds and then reset to not level.
01678 
01679 . .
01680        pi: >=0 (as returned by [*pigpio_start*]).
01681 user_gpio: 0-31.
01682  pulseLen: 1-100.
01683     level: 0,1.
01684 . .
01685 
01686 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
01687 PI_BAD_PULSELEN, or PI_NOT_PERMITTED.
01688 D*/
01689 
01690 /*F*/
01691 int store_script(int pi, char *script);
01692 /*D
01693 This function stores a script for later execution.
01694 
01695 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
01696 
01697 . .
01698     pi: >=0 (as returned by [*pigpio_start*]).
01699 script: the text of the script.
01700 . .
01701 
01702 The function returns a script id if the script is valid,
01703 otherwise PI_BAD_SCRIPT.
01704 D*/
01705 
01706 /*F*/
01707 int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param);
01708 /*D
01709 This function runs a stored script.
01710 
01711 . .
01712        pi: >=0 (as returned by [*pigpio_start*]).
01713 script_id: >=0, as returned by [*store_script*].
01714    numPar: 0-10, the number of parameters.
01715     param: an array of parameters.
01716 . .
01717 
01718 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
01719 PI_TOO_MANY_PARAM
01720 
01721 param is an array of up to 10 parameters which may be referenced in
01722 the script as p0 to p9.
01723 D*/
01724 
01725 /*F*/
01726 int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param);
01727 /*D
01728 This function sets the parameters of a script.  The script may or
01729 may not be running.  The first numPar parameters of the script are
01730 overwritten with the new values.
01731 
01732 . .
01733        pi: >=0 (as returned by [*pigpio_start*]).
01734 script_id: >=0, as returned by [*store_script*].
01735    numPar: 0-10, the number of parameters.
01736     param: an array of parameters.
01737 . .
01738 
01739 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
01740 PI_TOO_MANY_PARAM.
01741 
01742 param is an array of up to 10 parameters which may be referenced in
01743 the script as p0 to p9.
01744 D*/
01745 
01746 /*F*/
01747 int script_status(int pi, unsigned script_id, uint32_t *param);
01748 /*D
01749 This function returns the run status of a stored script as well
01750 as the current values of parameters 0 to 9.
01751 
01752 . .
01753        pi: >=0 (as returned by [*pigpio_start*]).
01754 script_id: >=0, as returned by [*store_script*].
01755     param: an array to hold the returned 10 parameters.
01756 . .
01757 
01758 The function returns greater than or equal to 0 if OK,
01759 otherwise PI_BAD_SCRIPT_ID.
01760 
01761 The run status may be
01762 
01763 . .
01764 PI_SCRIPT_INITING
01765 PI_SCRIPT_HALTED
01766 PI_SCRIPT_RUNNING
01767 PI_SCRIPT_WAITING
01768 PI_SCRIPT_FAILED
01769 . .
01770 
01771 The current value of script parameters 0 to 9 are returned in param.
01772 D*/
01773 
01774 /*F*/
01775 int stop_script(int pi, unsigned script_id);
01776 /*D
01777 This function stops a running script.
01778 
01779 . .
01780        pi: >=0 (as returned by [*pigpio_start*]).
01781 script_id: >=0, as returned by [*store_script*].
01782 . .
01783 
01784 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
01785 D*/
01786 
01787 /*F*/
01788 int delete_script(int pi, unsigned script_id);
01789 /*D
01790 This function deletes a stored script.
01791 
01792 . .
01793        pi: >=0 (as returned by [*pigpio_start*]).
01794 script_id: >=0, as returned by [*store_script*].
01795 . .
01796 
01797 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
01798 D*/
01799 
01800 /*F*/
01801 int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits);
01802 /*D
01803 This function opens a GPIO for bit bang reading of serial data.
01804 
01805 . .
01806        pi: >=0 (as returned by [*pigpio_start*]).
01807 user_gpio: 0-31.
01808      baud: 50-250000
01809 data_bits: 1-32
01810 . .
01811 
01812 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
01813 or PI_GPIO_IN_USE.
01814 
01815 The serial data is returned in a cyclic buffer and is read using
01816 bb_serial_read.
01817 
01818 It is the caller's responsibility to read data from the cyclic buffer
01819 in a timely fashion.
01820 D*/
01821 
01822 /*F*/
01823 int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize);
01824 /*D
01825 This function copies up to bufSize bytes of data read from the
01826 bit bang serial cyclic buffer to the buffer starting at buf.
01827 
01828 . .
01829        pi: >=0 (as returned by [*pigpio_start*]).
01830 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01831       buf: an array to receive the read bytes.
01832   bufSize: >=0
01833 . .
01834 
01835 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
01836 or PI_NOT_SERIAL_GPIO.
01837 
01838 The bytes returned for each character depend upon the number of
01839 data bits [*data_bits*] specified in the [*bb_serial_read_open*] command.
01840 
01841 For [*data_bits*] 1-8 there will be one byte per character. 
01842 For [*data_bits*] 9-16 there will be two bytes per character. 
01843 For [*data_bits*] 17-32 there will be four bytes per character.
01844 D*/
01845 
01846 /*F*/
01847 int bb_serial_read_close(int pi, unsigned user_gpio);
01848 /*D
01849 This function closes a GPIO for bit bang reading of serial data.
01850 
01851 . .
01852        pi: >=0 (as returned by [*pigpio_start*]).
01853 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01854 . .
01855 
01856 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
01857 D*/
01858 
01859 /*F*/
01860 int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert);
01861 /*D
01862 This function inverts serial logic for big bang serial reads.
01863 
01864 . .
01865        pi: >=0 (as returned by [*pigpio_start*]).
01866 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01867    invert: 0-1, 1 invert, 0 normal.
01868 . .
01869 
01870 Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT.
01871 D*/
01872 
01873 /*F*/
01874 int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags);
01875 /*D
01876 This returns a handle for the device at address i2c_addr on bus i2c_bus.
01877 
01878 . .
01879        pi: >=0 (as returned by [*pigpio_start*]).
01880   i2c_bus: >=0.
01881  i2c_addr: 0-0x7F.
01882 i2c_flags: 0.
01883 . .
01884 
01885 No flags are currently defined.  This parameter should be set to zero.
01886 
01887 Physically buses 0 and 1 are available on the Pi.  Higher numbered buses
01888 will be available if a kernel supported bus multiplexor is being used.
01889 
01890 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
01891 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
01892 
01893 For the SMBus commands the low level transactions are shown at the end
01894 of the function description.  The following abbreviations are used.
01895 
01896 . .
01897 S       (1 bit) : Start bit
01898 P       (1 bit) : Stop bit
01899 Rd/Wr   (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
01900 A, NA   (1 bit) : Accept and not accept bit. 
01901 Addr    (7 bits): I2C 7 bit address.
01902 i2c_reg (8 bits): A byte which often selects a register.
01903 Data    (8 bits): A data byte.
01904 Count   (8 bits): A byte defining the length of a block operation.
01905 
01906 [..]: Data sent by the device.
01907 . .
01908 D*/
01909 
01910 /*F*/
01911 int i2c_close(int pi, unsigned handle);
01912 /*D
01913 This closes the I2C device associated with the handle.
01914 
01915 . .
01916     pi: >=0 (as returned by [*pigpio_start*]).
01917 handle: >=0, as returned by a call to [*i2c_open*].
01918 . .
01919 
01920 Returns 0 if OK, otherwise PI_BAD_HANDLE.
01921 D*/
01922 
01923 /*F*/
01924 int i2c_write_quick(int pi, unsigned handle, unsigned bit);
01925 /*D
01926 This sends a single bit (in the Rd/Wr bit) to the device associated
01927 with handle.
01928 
01929 . .
01930     pi: >=0 (as returned by [*pigpio_start*]).
01931 handle: >=0, as returned by a call to [*i2c_open*].
01932    bit: 0-1, the value to write.
01933 . .
01934 
01935 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01936 PI_I2C_WRITE_FAILED.
01937 
01938 Quick command. SMBus 2.0 5.5.1
01939 . .
01940 S Addr bit [A] P
01941 . .
01942 D*/
01943 
01944 /*F*/
01945 int i2c_write_byte(int pi, unsigned handle, unsigned bVal);
01946 /*D
01947 This sends a single byte to the device associated with handle.
01948 
01949 . .
01950     pi: >=0 (as returned by [*pigpio_start*]).
01951 handle: >=0, as returned by a call to [*i2c_open*].
01952   bVal: 0-0xFF, the value to write.
01953 . .
01954 
01955 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01956 PI_I2C_WRITE_FAILED.
01957 
01958 Send byte. SMBus 2.0 5.5.2
01959 . .
01960 S Addr Wr [A] bVal [A] P
01961 . .
01962 D*/
01963 
01964 /*F*/
01965 int i2c_read_byte(int pi, unsigned handle);
01966 /*D
01967 This reads a single byte from the device associated with handle.
01968 
01969 . .
01970     pi: >=0 (as returned by [*pigpio_start*]).
01971 handle: >=0, as returned by a call to [*i2c_open*].
01972 . .
01973 
01974 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
01975 or PI_I2C_READ_FAILED.
01976 
01977 Receive byte. SMBus 2.0 5.5.3
01978 . .
01979 S Addr Rd [A] [Data] NA P
01980 . .
01981 D*/
01982 
01983 /*F*/
01984 int i2c_write_byte_data(
01985    int pi, unsigned handle, unsigned i2c_reg, unsigned bVal);
01986 /*D
01987 This writes a single byte to the specified register of the device
01988 associated with handle.
01989 
01990 . .
01991      pi: >=0 (as returned by [*pigpio_start*]).
01992  handle: >=0, as returned by a call to [*i2c_open*].
01993 i2c_reg: 0-255, the register to write.
01994    bVal: 0-0xFF, the value to write.
01995 . .
01996 
01997 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01998 PI_I2C_WRITE_FAILED.
01999 
02000 Write byte. SMBus 2.0 5.5.4
02001 . .
02002 S Addr Wr [A] i2c_reg [A] bVal [A] P
02003 . .
02004 D*/
02005 
02006 /*F*/
02007 int i2c_write_word_data(
02008    int pi, unsigned handle, unsigned i2c_reg, unsigned wVal);
02009 /*D
02010 This writes a single 16 bit word to the specified register of the device
02011 associated with handle.
02012 
02013 . .
02014      pi: >=0 (as returned by [*pigpio_start*]).
02015  handle: >=0, as returned by a call to [*i2c_open*].
02016 i2c_reg: 0-255, the register to write.
02017    wVal: 0-0xFFFF, the value to write.
02018 . .
02019 
02020 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02021 PI_I2C_WRITE_FAILED.
02022 
02023 Write word. SMBus 2.0 5.5.4
02024 . .
02025 S Addr Wr [A] i2c_reg [A] wval_Low [A] wVal_High [A] P
02026 . .
02027 D*/
02028 
02029 /*F*/
02030 int i2c_read_byte_data(int pi, unsigned handle, unsigned i2c_reg);
02031 /*D
02032 This reads a single byte from the specified register of the device
02033 associated with handle.
02034 
02035 . .
02036      pi: >=0 (as returned by [*pigpio_start*]).
02037  handle: >=0, as returned by a call to [*i2c_open*].
02038 i2c_reg: 0-255, the register to read.
02039 . .
02040 
02041 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
02042 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02043 
02044 Read byte. SMBus 2.0 5.5.5
02045 . .
02046 S Addr Wr [A] i2c_reg [A] S Addr Rd [A] [Data] NA P
02047 . .
02048 D*/
02049 
02050 /*F*/
02051 int i2c_read_word_data(int pi, unsigned handle, unsigned i2c_reg);
02052 /*D
02053 This reads a single 16 bit word from the specified register of the device
02054 associated with handle.
02055 
02056 . .
02057      pi: >=0 (as returned by [*pigpio_start*]).
02058  handle: >=0, as returned by a call to [*i2c_open*].
02059 i2c_reg: 0-255, the register to read.
02060 . .
02061 
02062 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
02063 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02064 
02065 Read word. SMBus 2.0 5.5.5
02066 . .
02067 S Addr Wr [A] i2c_reg [A]
02068    S Addr Rd [A] [DataLow] A [DataHigh] NA P
02069 . .
02070 D*/
02071 
02072 /*F*/
02073 int i2c_process_call(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal);
02074 /*D
02075 This writes 16 bits of data to the specified register of the device
02076 associated with handle and and reads 16 bits of data in return.
02077 
02078 . .
02079      pi: >=0 (as returned by [*pigpio_start*]).
02080  handle: >=0, as returned by a call to [*i2c_open*].
02081 i2c_reg: 0-255, the register to write/read.
02082    wVal: 0-0xFFFF, the value to write.
02083 . .
02084 
02085 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
02086 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02087 
02088 Process call. SMBus 2.0 5.5.6
02089 . .
02090 S Addr Wr [A] i2c_reg [A] wVal_Low [A] wVal_High [A]
02091    S Addr Rd [A] [DataLow] A [DataHigh] NA P
02092 . .
02093 D*/
02094 
02095 /*F*/
02096 int i2c_write_block_data(
02097    int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
02098 /*D
02099 This writes up to 32 bytes to the specified register of the device
02100 associated with handle.
02101 
02102 . .
02103      pi: >=0 (as returned by [*pigpio_start*]).
02104  handle: >=0, as returned by a call to [*i2c_open*].
02105 i2c_reg: 0-255, the register to write.
02106     buf: an array with the data to send.
02107   count: 1-32, the number of bytes to write.
02108 . .
02109 
02110 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02111 PI_I2C_WRITE_FAILED.
02112 
02113 Block write. SMBus 2.0 5.5.7
02114 . .
02115 S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] buf1 [A] ...
02116    [A] bufn [A] P
02117 . .
02118 D*/
02119 
02120 /*F*/
02121 int i2c_read_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf);
02122 /*D
02123 This reads a block of up to 32 bytes from the specified register of
02124 the device associated with handle.
02125 
02126 . .
02127      pi: >=0 (as returned by [*pigpio_start*]).
02128  handle: >=0, as returned by a call to [*i2c_open*].
02129 i2c_reg: 0-255, the register to read.
02130     buf: an array to receive the read data.
02131 . .
02132 
02133 The amount of returned data is set by the device.
02134 
02135 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
02136 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02137 
02138 Block read. SMBus 2.0 5.5.7
02139 . .
02140 S Addr Wr [A] i2c_reg [A]
02141    S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P
02142 . .
02143 D*/
02144 
02145 /*F*/
02146 int i2c_block_process_call(
02147    int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
02148 /*D
02149 This writes data bytes to the specified register of the device
02150 associated with handle and reads a device specified number
02151 of bytes of data in return.
02152 
02153 . .
02154      pi: >=0 (as returned by [*pigpio_start*]).
02155  handle: >=0, as returned by a call to [*i2c_open*].
02156 i2c_reg: 0-255, the register to write/read.
02157     buf: an array with the data to send and to receive the read data.
02158   count: 1-32, the number of bytes to write.
02159 . .
02160 
02161 
02162 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
02163 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02164 
02165 The smbus 2.0 documentation states that a minimum of 1 byte may be
02166 sent and a minimum of 1 byte may be received.  The total number of
02167 bytes sent/received must be 32 or less.
02168 
02169 Block write-block read. SMBus 2.0 5.5.8
02170 . .
02171 S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] ...
02172    S Addr Rd [A] [Count] A [Data] ... A P
02173 . .
02174 D*/
02175 
02176 /*F*/
02177 int i2c_read_i2c_block_data(
02178    int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
02179 /*D
02180 This reads count bytes from the specified register of the device
02181 associated with handle .  The count may be 1-32.
02182 
02183 . .
02184      pi: >=0 (as returned by [*pigpio_start*]).
02185  handle: >=0, as returned by a call to [*i2c_open*].
02186 i2c_reg: 0-255, the register to read.
02187     buf: an array to receive the read data.
02188   count: 1-32, the number of bytes to read.
02189 . .
02190 
02191 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
02192 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
02193 
02194 . .
02195 S Addr Wr [A] i2c_reg [A]
02196    S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
02197 . .
02198 D*/
02199 
02200 
02201 /*F*/
02202 int i2c_write_i2c_block_data(
02203    int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
02204 /*D
02205 This writes 1 to 32 bytes to the specified register of the device
02206 associated with handle.
02207 
02208 . .
02209      pi: >=0 (as returned by [*pigpio_start*]).
02210  handle: >=0, as returned by a call to [*i2c_open*].
02211 i2c_reg: 0-255, the register to write.
02212     buf: the data to write.
02213   count: 1-32, the number of bytes to write.
02214 . .
02215 
02216 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02217 PI_I2C_WRITE_FAILED.
02218 
02219 . .
02220 S Addr Wr [A] i2c_reg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
02221 . .
02222 D*/
02223 
02224 /*F*/
02225 int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count);
02226 /*D
02227 This reads count bytes from the raw device into buf.
02228 
02229 . .
02230     pi: >=0 (as returned by [*pigpio_start*]).
02231 handle: >=0, as returned by a call to [*i2c_open*].
02232    buf: an array to receive the read data bytes.
02233  count: >0, the number of bytes to read.
02234 . .
02235 
02236 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02237 PI_I2C_READ_FAILED.
02238 
02239 . .
02240 S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
02241 . .
02242 D*/
02243 
02244 /*F*/
02245 int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count);
02246 /*D
02247 This writes count bytes from buf to the raw device.
02248 
02249 . .
02250     pi: >=0 (as returned by [*pigpio_start*]).
02251 handle: >=0, as returned by a call to [*i2c_open*].
02252    buf: an array containing the data bytes to write.
02253  count: >0, the number of bytes to write.
02254 . .
02255 
02256 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02257 PI_I2C_WRITE_FAILED.
02258 
02259 . .
02260 S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
02261 . .
02262 D*/
02263 
02264 /*F*/
02265 int i2c_zip(
02266    int pi,
02267    unsigned handle,
02268    char    *inBuf,
02269    unsigned inLen,
02270    char    *outBuf,
02271    unsigned outLen);
02272 /*D
02273 This function executes a sequence of I2C operations.  The
02274 operations to be performed are specified by the contents of inBuf
02275 which contains the concatenated command codes and associated data.
02276 
02277 . .
02278     pi: >=0 (as returned by [*pigpio_start*]).
02279 handle: >=0, as returned by a call to [*i2cOpen*]
02280  inBuf: pointer to the concatenated I2C commands, see below
02281  inLen: size of command buffer
02282 outBuf: pointer to buffer to hold returned data
02283 outLen: size of output buffer
02284 . .
02285 
02286 Returns >= 0 if OK (the number of bytes read), otherwise
02287 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
02288 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
02289 
02290 The following command codes are supported:
02291 
02292 Name    @ Cmd & Data @ Meaning
02293 End     @ 0          @ No more commands
02294 Escape  @ 1          @ Next P is two bytes
02295 On      @ 2          @ Switch combined flag on
02296 Off     @ 3          @ Switch combined flag off
02297 Address @ 4 P        @ Set I2C address to P
02298 Flags   @ 5 lsb msb  @ Set I2C flags to lsb + (msb << 8)
02299 Read    @ 6 P        @ Read P bytes of data
02300 Write   @ 7 P ...    @ Write P bytes of data
02301 
02302 The address, read, and write commands take a parameter P.
02303 Normally P is one byte (0-255).  If the command is preceded by
02304 the Escape command then P is two bytes (0-65535, least significant
02305 byte first).
02306 
02307 The address defaults to that associated with the handle.
02308 The flags default to 0.  The address and flags maintain their
02309 previous value until updated.
02310 
02311 The returned I2C data is stored in consecutive locations of outBuf.
02312 
02313 ...
02314 Set address 0x53, write 0x32, read 6 bytes
02315 Set address 0x1E, write 0x03, read 6 bytes
02316 Set address 0x68, write 0x1B, read 8 bytes
02317 End
02318 
02319 0x04 0x53   0x07 0x01 0x32   0x06 0x06
02320 0x04 0x1E   0x07 0x01 0x03   0x06 0x06
02321 0x04 0x68   0x07 0x01 0x1B   0x06 0x08
02322 0x00
02323 ...
02324 
02325 D*/
02326 
02327 /*F*/
02328 int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud);
02329 /*D
02330 This function selects a pair of GPIO for bit banging I2C at a
02331 specified baud rate.
02332 
02333 Bit banging I2C allows for certain operations which are not possible
02334 with the standard I2C driver.
02335 
02336 o baud rates as low as 50 
02337 o repeated starts 
02338 o clock stretching 
02339 o I2C on any pair of spare GPIO
02340 
02341 . .
02342   pi: >=0 (as returned by [*pigpio_start*]).
02343  SDA: 0-31
02344  SCL: 0-31
02345 baud: 50-500000
02346 . .
02347 
02348 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
02349 PI_GPIO_IN_USE.
02350 
02351 NOTE:
02352 
02353 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected.  As
02354 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
02355 D*/
02356 
02357 /*F*/
02358 int bb_i2c_close(int pi, unsigned SDA);
02359 /*D
02360 This function stops bit banging I2C on a pair of GPIO previously
02361 opened with [*bb_i2c_open*].
02362 
02363 . .
02364  pi: >=0 (as returned by [*pigpio_start*]).
02365 SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*]
02366 . .
02367 
02368 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
02369 D*/
02370 
02371 /*F*/
02372 int bb_i2c_zip(
02373    int pi,
02374    unsigned SDA,
02375    char    *inBuf,
02376    unsigned inLen,
02377    char    *outBuf,
02378    unsigned outLen);
02379 /*D
02380 This function executes a sequence of bit banged I2C operations.  The
02381 operations to be performed are specified by the contents of inBuf
02382 which contains the concatenated command codes and associated data.
02383 
02384 . .
02385     pi: >=0 (as returned by [*pigpio_start*]).
02386    SDA: 0-31 (as used in a prior call to [*bb_i2c_open*])
02387  inBuf: pointer to the concatenated I2C commands, see below
02388  inLen: size of command buffer
02389 outBuf: pointer to buffer to hold returned data
02390 outLen: size of output buffer
02391 . .
02392 
02393 Returns >= 0 if OK (the number of bytes read), otherwise
02394 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
02395 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
02396 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
02397 
02398 The following command codes are supported:
02399 
02400 Name    @ Cmd & Data   @ Meaning
02401 End     @ 0            @ No more commands
02402 Escape  @ 1            @ Next P is two bytes
02403 Start   @ 2            @ Start condition
02404 Stop    @ 3            @ Stop condition
02405 Address @ 4 P          @ Set I2C address to P
02406 Flags   @ 5 lsb msb    @ Set I2C flags to lsb + (msb << 8)
02407 Read    @ 6 P          @ Read P bytes of data
02408 Write   @ 7 P ...      @ Write P bytes of data
02409 
02410 The address, read, and write commands take a parameter P.
02411 Normally P is one byte (0-255).  If the command is preceded by
02412 the Escape command then P is two bytes (0-65535, least significant
02413 byte first).
02414 
02415 The address and flags default to 0.  The address and flags maintain
02416 their previous value until updated.
02417 
02418 No flags are currently defined.
02419 
02420 The returned I2C data is stored in consecutive locations of outBuf.
02421 
02422 ...
02423 Set address 0x53
02424 start, write 0x32, (re)start, read 6 bytes, stop
02425 Set address 0x1E
02426 start, write 0x03, (re)start, read 6 bytes, stop
02427 Set address 0x68
02428 start, write 0x1B, (re)start, read 8 bytes, stop
02429 End
02430 
02431 0x04 0x53
02432 0x02 0x07 0x01 0x32   0x02 0x06 0x06 0x03
02433 
02434 0x04 0x1E
02435 0x02 0x07 0x01 0x03   0x02 0x06 0x06 0x03
02436 
02437 0x04 0x68
02438 0x02 0x07 0x01 0x1B   0x02 0x06 0x08 0x03
02439 
02440 0x00
02441 ...
02442 D*/
02443 
02444 /*F*/
02445 int bb_spi_open(
02446    int pi,
02447    unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK,
02448    unsigned baud, unsigned spi_flags);
02449 /*D
02450 This function selects a set of GPIO for bit banging SPI at a
02451 specified baud rate.
02452 
02453 . .
02454        pi: >=0 (as returned by [*pigpio_start*]).
02455        CS: 0-31
02456      MISO: 0-31
02457      MOSI: 0-31
02458      SCLK: 0-31
02459      baud: 50-250000
02460 spi_flags: see below
02461 . .
02462 
02463 spi_flags consists of the least significant 22 bits.
02464 
02465 . .
02466 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
02467  0  0  0  0  0  0  R  T  0  0  0  0  0  0  0  0  0  0  0  p  m  m
02468 . .
02469 
02470 mm defines the SPI mode, defaults to 0
02471 
02472 . .
02473 Mode CPOL CPHA
02474  0    0    0
02475  1    0    1
02476  2    1    0
02477  3    1    1
02478 . .
02479 
02480 p is 0 if CS is active low (default) and 1 for active high.
02481 
02482 T is 1 if the least significant bit is transmitted on MOSI first, the
02483 default (0) shifts the most significant bit out first.
02484 
02485 R is 1 if the least significant bit is received on MISO first, the
02486 default (0) receives the most significant bit first.
02487 
02488 The other bits in flags should be set to zero.
02489 
02490 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or
02491 PI_GPIO_IN_USE.
02492 
02493 If more than one device is connected to the SPI bus (defined by
02494 SCLK, MOSI, and MISO) each must have its own CS.
02495 
02496 ...
02497 bb_spi_open(pi,10, MISO, MOSI, SCLK, 10000, 0); // device 1
02498 bb_spi_open(pi,11, MISO, MOSI, SCLK, 20000, 3); // device 2
02499 ...
02500 D*/
02501 
02502 /*F*/
02503 int bb_spi_close(int pi, unsigned CS);
02504 /*D
02505 This function stops bit banging SPI on a set of GPIO
02506 opened with [*bbSPIOpen*].
02507 
02508 . .
02509 pi: >=0 (as returned by [*pigpio_start*]).
02510 CS: 0-31, the CS GPIO used in a prior call to [*bb_spi_open*]
02511 . .
02512 
02513 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO.
02514 D*/
02515 
02516 /*F*/
02517 int bb_spi_xfer(
02518    int pi,
02519    unsigned CS,
02520    char    *txBuf,
02521    char    *rxBuf,
02522    unsigned count);
02523 /*D
02524 This function executes a bit banged SPI transfer.
02525 
02526 . .
02527    pi: >=0 (as returned by [*pigpio_start*]).
02528    CS: 0-31 (as used in a prior call to [*bb_spi_open*])
02529 txBuf: pointer to buffer to hold data to be sent
02530 rxBuf: pointer to buffer to hold returned data
02531 count: size of data transfer
02532 . .
02533 
02534 Returns >= 0 if OK (the number of bytes read), otherwise
02535 PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER.
02536 
02537 ...
02538 // gcc -Wall -pthread -o bb_spi_x_test bb_spi_x_test.c -lpigpiod_if2
02539 // ./bb_spi_x_test
02540 
02541 #include <stdio.h>
02542 
02543 #include "pigpiod_if2.h"
02544 
02545 #define CE0 5
02546 #define CE1 6
02547 #define MISO 13
02548 #define MOSI 19
02549 #define SCLK 12
02550 
02551 int main(int argc, char *argv[])
02552 {
02553    int i, pi, count, set_val, read_val;
02554    unsigned char inBuf[3];
02555    char cmd1[] = {0, 0};
02556    char cmd2[] = {12, 0};
02557    char cmd3[] = {1, 128, 0};
02558 
02559    if ((pi = pigpio_start(0, 0)) < 0)
02560    {
02561       fprintf(stderr, "pigpio initialisation failed (%d).\n", pi);
02562       return 1;
02563    }
02564 
02565    bb_spi_open(pi, CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC
02566    bb_spi_open(pi, CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC
02567 
02568    for (i=0; i<256; i++)
02569    {
02570       cmd1[1] = i;
02571 
02572       count = bb_spi_xfer(pi, CE0, cmd1, (char *)inBuf, 2); // > DAC
02573 
02574       if (count == 2)
02575       {
02576          count = bb_spi_xfer(pi, CE0, cmd2, (char *)inBuf, 2); // < DAC
02577 
02578          if (count == 2)
02579          {
02580             set_val = inBuf[1];
02581 
02582             count = bb_spi_xfer(pi, CE1, cmd3, (char *)inBuf, 3); // < ADC
02583 
02584             if (count == 3)
02585             {
02586                read_val = ((inBuf[1]&3)<<8) | inBuf[2];
02587                printf("%d %d\n", set_val, read_val);
02588             }
02589          }
02590       }
02591    }
02592 
02593    bb_spi_close(pi, CE0);
02594    bb_spi_close(pi, CE1);
02595 
02596    pigpio_stop(pi);
02597 }
02598 ...
02599 D*/
02600 
02601 /*F*/
02602 int spi_open(int pi, unsigned spi_channel, unsigned baud, unsigned spi_flags);
02603 /*D
02604 This function returns a handle for the SPI device on channel.
02605 Data will be transferred at baud bits per second.  The flags may
02606 be used to modify the default behaviour of 4-wire operation, mode 0,
02607 active low chip select.
02608 
02609 An auxiliary SPI device is available on all models but the
02610 A and B and may be selected by setting the A bit in the
02611 flags.  The auxiliary device has 3 chip selects and a
02612 selectable word size in bits.
02613 
02614 . .
02615          pi: >=0 (as returned by [*pigpio_start*]).
02616 spi_channel: 0-1 (0-2 for the auxiliary device).
02617        baud: 32K-125M (values above 30M are unlikely to work).
02618   spi_flags: see below.
02619 . .
02620 
02621 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
02622 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
02623 
02624 spi_flags consists of the least significant 22 bits.
02625 
02626 . .
02627 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
02628  b  b  b  b  b  b  R  T  n  n  n  n  W  A u2 u1 u0 p2 p1 p0  m  m
02629 . .
02630 
02631 mm defines the SPI mode.
02632 
02633 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
02634 
02635 . .
02636 Mode POL PHA
02637  0    0   0
02638  1    0   1
02639  2    1   0
02640  3    1   1
02641 . .
02642 
02643 px is 0 if CEx is active low (default) and 1 for active high.
02644 
02645 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
02646 
02647 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
02648 
02649 W is 0 if the device is not 3-wire, 1 if the device is 3-wire.  Standard
02650 SPI device only.
02651 
02652 nnnn defines the number of bytes (0-15) to write before switching
02653 the MOSI line to MISO to read data.  This field is ignored
02654 if W is not set.  Standard SPI device only.
02655 
02656 T is 1 if the least significant bit is transmitted on MOSI first, the
02657 default (0) shifts the most significant bit out first.  Auxiliary SPI
02658 device only.
02659 
02660 R is 1 if the least significant bit is received on MISO first, the
02661 default (0) receives the most significant bit first.  Auxiliary SPI
02662 device only.
02663 
02664 bbbbbb defines the word size in bits (0-32).  The default (0)
02665 sets 8 bits per word.  Auxiliary SPI device only.
02666 
02667 The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions
02668 transfer data packed into 1, 2, or 4 bytes according to
02669 the word size in bits.
02670 
02671 For bits 1-8 there will be one byte per character. 
02672 For bits 9-16 there will be two bytes per character. 
02673 For bits 17-32 there will be four bytes per character.
02674 
02675 Multi-byte transfers are made in least significant byte first order.
02676 
02677 E.g. to transfer 32 11-bit words buf should contain 64 bytes
02678 and count should be 64.
02679 
02680 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
02681 by 0x1A.
02682 
02683 The other bits in flags should be set to zero.
02684 D*/
02685 
02686 /*F*/
02687 int spi_close(int pi, unsigned handle);
02688 /*D
02689 This functions closes the SPI device identified by the handle.
02690 
02691 . .
02692     pi: >=0 (as returned by [*pigpio_start*]).
02693 handle: >=0, as returned by a call to [*spi_open*].
02694 . .
02695 
02696 Returns 0 if OK, otherwise PI_BAD_HANDLE.
02697 D*/
02698 
02699 /*F*/
02700 int spi_read(int pi, unsigned handle, char *buf, unsigned count);
02701 /*D
02702 This function reads count bytes of data from the SPI
02703 device associated with the handle.
02704 
02705 . .
02706     pi: >=0 (as returned by [*pigpio_start*]).
02707 handle: >=0, as returned by a call to [*spi_open*].
02708    buf: an array to receive the read data bytes.
02709  count: the number of bytes to read.
02710 . .
02711 
02712 Returns the number of bytes transferred if OK, otherwise
02713 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02714 D*/
02715 
02716 /*F*/
02717 int spi_write(int pi, unsigned handle, char *buf, unsigned count);
02718 /*D
02719 This function writes count bytes of data from buf to the SPI
02720 device associated with the handle.
02721 
02722 . .
02723     pi: >=0 (as returned by [*pigpio_start*]).
02724 handle: >=0, as returned by a call to [*spi_open*].
02725    buf: the data bytes to write.
02726  count: the number of bytes to write.
02727 . .
02728 
02729 Returns the number of bytes transferred if OK, otherwise
02730 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02731 D*/
02732 
02733 /*F*/
02734 int spi_xfer(
02735    int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count);
02736 /*D
02737 This function transfers count bytes of data from txBuf to the SPI
02738 device associated with the handle.  Simultaneously count bytes of
02739 data are read from the device and placed in rxBuf.
02740 
02741 . .
02742     pi: >=0 (as returned by [*pigpio_start*]).
02743 handle: >=0, as returned by a call to [*spi_open*].
02744  txBuf: the data bytes to write.
02745  rxBuf: the received data bytes.
02746  count: the number of bytes to transfer.
02747 . .
02748 
02749 Returns the number of bytes transferred if OK, otherwise
02750 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02751 D*/
02752 
02753 /*F*/
02754 int serial_open(int pi, char *ser_tty, unsigned baud, unsigned ser_flags);
02755 /*D
02756 This function opens a serial device at a specified baud rate
02757 with specified flags.  The device name must start with
02758 /dev/tty or /dev/serial.
02759 
02760 
02761 . .
02762        pi: >=0 (as returned by [*pigpio_start*]).
02763   ser_tty: the serial device to open.
02764      baud: the baud rate in bits per second, see below.
02765 ser_flags: 0.
02766 . .
02767 
02768 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
02769 PI_SER_OPEN_FAILED.
02770 
02771 The baud rate must be one of 50, 75, 110, 134, 150,
02772 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
02773 38400, 57600, 115200, or 230400.
02774 
02775 No flags are currently defined.  This parameter should be set to zero.
02776 D*/
02777 
02778 /*F*/
02779 int serial_close(int pi, unsigned handle);
02780 /*D
02781 This function closes the serial device associated with handle.
02782 
02783 . .
02784     pi: >=0 (as returned by [*pigpio_start*]).
02785 handle: >=0, as returned by a call to [*serial_open*].
02786 . .
02787 
02788 Returns 0 if OK, otherwise PI_BAD_HANDLE.
02789 D*/
02790 
02791 /*F*/
02792 int serial_write_byte(int pi, unsigned handle, unsigned bVal);
02793 /*D
02794 This function writes bVal to the serial port associated with handle.
02795 
02796 . .
02797     pi: >=0 (as returned by [*pigpio_start*]).
02798 handle: >=0, as returned by a call to [*serial_open*].
02799 . .
02800 
02801 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02802 PI_SER_WRITE_FAILED.
02803 D*/
02804 
02805 /*F*/
02806 int serial_read_byte(int pi, unsigned handle);
02807 /*D
02808 This function reads a byte from the serial port associated with handle.
02809 
02810 . .
02811     pi: >=0 (as returned by [*pigpio_start*]).
02812 handle: >=0, as returned by a call to [*serial_open*].
02813 . .
02814 
02815 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
02816 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
02817 
02818 If no data is ready PI_SER_READ_NO_DATA is returned.
02819 D*/
02820 
02821 /*F*/
02822 int serial_write(int pi, unsigned handle, char *buf, unsigned count);
02823 /*D
02824 This function writes count bytes from buf to the the serial port
02825 associated with handle.
02826 
02827 . .
02828     pi: >=0 (as returned by [*pigpio_start*]).
02829 handle: >=0, as returned by a call to [*serial_open*].
02830    buf: the array of bytes to write.
02831  count: the number of bytes to write.
02832 . .
02833 
02834 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02835 PI_SER_WRITE_FAILED.
02836 D*/
02837 
02838 /*F*/
02839 int serial_read(int pi, unsigned handle, char *buf, unsigned count);
02840 /*D
02841 This function reads up to count bytes from the the serial port
02842 associated with handle and writes them to buf.
02843 
02844 . .
02845     pi: >=0 (as returned by [*pigpio_start*]).
02846 handle: >=0, as returned by a call to [*serial_open*].
02847    buf: an array to receive the read data.
02848  count: the maximum number of bytes to read.
02849 . .
02850 
02851 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
02852 PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED.
02853 
02854 If no data is ready zero is returned.
02855 D*/
02856 
02857 /*F*/
02858 int serial_data_available(int pi, unsigned handle);
02859 /*D
02860 Returns the number of bytes available to be read from the
02861 device associated with handle.
02862 
02863 . .
02864     pi: >=0 (as returned by [*pigpio_start*]).
02865 handle: >=0, as returned by a call to [*serial_open*].
02866 . .
02867 
02868 Returns the number of bytes of data available (>=0) if OK,
02869 otherwise PI_BAD_HANDLE.
02870 D*/
02871 
02872 /*F*/
02873 int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned argc);
02874 /*D
02875 This function is available for user customisation.
02876 
02877 It returns a single integer value.
02878 
02879 . .
02880   pi: >=0 (as returned by [*pigpio_start*]).
02881 arg1: >=0
02882 arg2: >=0
02883 argx: extra (byte) arguments
02884 argc: number of extra arguments
02885 . .
02886 
02887 Returns >= 0 if OK, less than 0 indicates a user defined error.
02888 D*/
02889 
02890 
02891 /*F*/
02892 int custom_2(int pi, unsigned arg1, char *argx, unsigned argc,
02893              char *retBuf, unsigned retMax);
02894 /*D
02895 This function is available for user customisation.
02896 
02897 It differs from custom_1 in that it returns an array of bytes
02898 rather than just an integer.
02899 
02900 The return value is an integer indicating the number of returned bytes.
02901 . .
02902     pi: >=0 (as returned by [*pigpio_start*]).
02903   arg1: >=0
02904   argc: extra (byte) arguments
02905  count: number of extra arguments
02906 retBuf: buffer for returned data
02907 retMax: maximum number of bytes to return
02908 . .
02909 
02910 Returns >= 0 if OK, less than 0 indicates a user defined error.
02911 
02912 Note, the number of returned bytes will be retMax or less.
02913 D*/
02914 
02915 /*F*/
02916 int get_pad_strength(int pi, unsigned pad);
02917 /*D
02918 This function returns the pad drive strength in mA.
02919 
02920 . .
02921  pi: >=0 (as returned by [*pigpio_start*]).
02922 pad: 0-2, the pad to get.
02923 . .
02924 
02925 Returns the pad drive strength if OK, otherwise PI_BAD_PAD.
02926 
02927 Pad @ GPIO
02928 0   @ 0-27
02929 1   @ 28-45
02930 2   @ 46-53
02931 
02932 ...
02933 strength = get_pad_strength(pi, 0); //  get pad 0 strength
02934 ...
02935 D*/
02936 
02937 
02938 /*F*/
02939 int set_pad_strength(int pi, unsigned pad, unsigned padStrength);
02940 /*D
02941 This function sets the pad drive strength in mA.
02942 
02943 . .
02944          pi: >=0 (as returned by [*pigpio_start*]).
02945         pad: 0-2, the pad to set.
02946 padStrength: 1-16 mA.
02947 . .
02948 
02949 Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH.
02950 
02951 Pad @ GPIO
02952 0   @ 0-27
02953 1   @ 28-45
02954 2   @ 46-53
02955 
02956 ...
02957 set_pad_strength(pi, 0, 10); // set pad 0 strength to 10 mA
02958 ...
02959 D*/
02960 
02961 
02962 /*F*/
02963 int shell_(int pi, char *scriptName, char *scriptString);
02964 /*D
02965 This function uses the system call to execute a shell script
02966 with the given string as its parameter.
02967 
02968 . .
02969           pi: >=0 (as returned by [*pigpio_start*]).
02970   scriptName: the name of the script, only alphanumeric characters,
02971               '-' and '_' are allowed in the name.
02972 scriptString: the string to pass to the script.
02973 . .
02974 
02975 The exit status of the system call is returned if OK, otherwise
02976 PI_BAD_SHELL_STATUS.
02977 
02978 scriptName must exist in /opt/pigpio/cgi and must be executable.
02979 
02980 The returned exit status is normally 256 times that set by the
02981 shell script exit function.  If the script can't be found 32512 will
02982 be returned.
02983 
02984 The following table gives some example returned statuses.
02985 
02986 Script exit status @ Returned system call status
02987 1                  @ 256
02988 5                  @ 1280
02989 10                 @ 2560
02990 200                @ 51200
02991 script not found   @ 32512
02992 
02993 ...
02994 // pass two parameters, hello and world
02995 status = shell_(pi, "scr1", "hello world");
02996 
02997 // pass three parameters, hello, string with spaces, and world
02998 status = shell_(pi, "scr1", "hello 'string with spaces' world");
02999 
03000 // pass one parameter, hello string with spaces world
03001 status = shell_(pi, "scr1", "\"hello string with spaces world\"");
03002 ...
03003 D*/
03004 
03005 #pragma GCC diagnostic push
03006 
03007 #pragma GCC diagnostic ignored "-Wcomment"
03008 
03009 /*F*/
03010 int file_open(int pi, char *file, unsigned mode);
03011 /*D
03012 This function returns a handle to a file opened in a specified mode.
03013 
03014 . .
03015   pi: >=0 (as returned by [*pigpio_start*]).
03016 file: the file to open.
03017 mode: the file open mode.
03018 . .
03019 
03020 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS,
03021 PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR.
03022 
03023 File
03024 
03025 A file may only be opened if permission is granted by an entry in
03026 /opt/pigpio/access.  This is intended to allow remote access to files
03027 in a more or less controlled manner.
03028 
03029 Each entry in /opt/pigpio/access takes the form of a file path
03030 which may contain wildcards followed by a single letter permission.
03031 The permission may be R for read, W for write, U for read/write,
03032 and N for no access.
03033 
03034 Where more than one entry matches a file the most specific rule
03035 applies.  If no entry matches a file then access is denied.
03036 
03037 Suppose /opt/pigpio/access contains the following entries
03038 
03039 . .
03040 /home/* n
03041 /home/pi/shared/dir_1/* w
03042 /home/pi/shared/dir_2/* r
03043 /home/pi/shared/dir_3/* u
03044 /home/pi/shared/dir_1/file.txt n
03045 . .
03046 
03047 Files may be written in directory dir_1 with the exception
03048 of file.txt.
03049 
03050 Files may be read in directory dir_2.
03051 
03052 Files may be read and written in directory dir_3.
03053 
03054 If a directory allows read, write, or read/write access then files may
03055 be created in that directory.
03056 
03057 In an attempt to prevent risky permissions the following paths are
03058 ignored in /opt/pigpio/access.
03059 
03060 . .
03061 a path containing ..
03062 a path containing only wildcards (*?)
03063 a path containing less than two non-wildcard parts
03064 . .
03065 
03066 Mode
03067 
03068 The mode may have the following values.
03069 
03070 Macro         @ Value @ Meaning
03071 PI_FILE_READ  @   1   @ open file for reading
03072 PI_FILE_WRITE @   2   @ open file for writing
03073 PI_FILE_RW    @   3   @ open file for reading and writing
03074 
03075 The following values may be or'd into the mode.
03076 
03077 Macro          @ Value @ Meaning
03078 PI_FILE_APPEND @ 4     @ Writes append data to the end of the file
03079 PI_FILE_CREATE @ 8     @ The file is created if it doesn't exist
03080 PI_FILE_TRUNC  @ 16    @ The file is truncated
03081 
03082 Newly created files are owned by root with permissions owner read and write.
03083 
03084 ...
03085 #include <stdio.h>
03086 #include <pigpiod_if2.h>
03087 
03088 int main(int argc, char *argv[])
03089 {
03090    int pi, handle, c;
03091    char buf[60000];
03092 
03093    pi = pigpio_start(NULL, NULL);
03094 
03095    if (pi < 0) return 1;
03096 
03097    // assumes /opt/pigpio/access contains the following line
03098    // /ram/*.c r
03099 
03100    handle = file_open(pi, "/ram/pigpio.c", PI_FILE_READ);
03101 
03102    if (handle >= 0)
03103    {
03104       while ((c=file_read(pi, handle, buf, sizeof(buf)-1)))
03105       {
03106          buf[c] = 0;
03107          printf("%s", buf);
03108       }
03109 
03110       file_close(pi, handle);
03111    }
03112 
03113    pigpio_stop(pi);
03114 }
03115 ...
03116 D*/
03117 
03118 #pragma GCC diagnostic pop
03119 
03120 /*F*/
03121 int file_close(int pi, unsigned handle);
03122 /*D
03123 This function closes the file associated with handle.
03124 
03125 . .
03126     pi: >=0 (as returned by [*pigpio_start*]).
03127 handle: >=0 (as returned by [*file_open*]).
03128 . .
03129 
03130 Returns 0 if OK, otherwise PI_BAD_HANDLE.
03131 
03132 ...
03133 file_close(pi, handle);
03134 ...
03135 D*/
03136 
03137 
03138 /*F*/
03139 int file_write(int pi, unsigned handle, char *buf, unsigned count);
03140 /*D
03141 This function writes count bytes from buf to the the file
03142 associated with handle.
03143 
03144 . .
03145     pi: >=0 (as returned by [*pigpio_start*]).
03146 handle: >=0 (as returned by [*file_open*]).
03147    buf: the array of bytes to write.
03148  count: the number of bytes to write.
03149 . .
03150 
03151 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM,
03152 PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE.
03153 
03154 ...
03155 if (file_write(pi, handle, buf, 100) == 0)
03156 {
03157    // file written okay
03158 }
03159 else
03160 {
03161    // error
03162 }
03163 ...
03164 D*/
03165 
03166 
03167 /*F*/
03168 int file_read(int pi, unsigned handle, char *buf, unsigned count);
03169 /*D
03170 This function reads up to count bytes from the the file
03171 associated with handle and writes them to buf.
03172 
03173 . .
03174     pi: >=0 (as returned by [*pigpio_start*]).
03175 handle: >=0 (as returned by [*file_open*]).
03176    buf: an array to receive the read data.
03177  count: the maximum number of bytes to read.
03178 . .
03179 
03180 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.
03181 
03182 ...
03183    bytes = file_read(pi, handle, buf, sizeof(buf));
03184 
03185    if (bytes >= 0)
03186    {
03187       // process read data
03188    }
03189 ...
03190 D*/
03191 
03192 
03193 /*F*/
03194 int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom);
03195 /*D
03196 This function seeks to a position within the file associated
03197 with handle.
03198 
03199 . .
03200         pi: >=0 (as returned by [*pigpio_start*]).
03201     handle: >=0 (as returned by [*file_open*]).
03202 seekOffset: the number of bytes to move.  Positive offsets
03203             move forward, negative offsets backwards.
03204   seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1),
03205             or PI_FROM_END (2).
03206 . .
03207 
03208 Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK.
03209 
03210 ...
03211 file_seek(pi, handle, 123, PI_FROM_START); // Start plus 123
03212 
03213 size = file_seek(pi, handle, 0, PI_FROM_END); // End, return size
03214 
03215 pos = file_seek(pi, handle, 0, PI_FROM_CURRENT); // Current position
03216 ...
03217 D*/
03218 
03219 #pragma GCC diagnostic push
03220 
03221 #pragma GCC diagnostic ignored "-Wcomment"
03222 
03223 /*F*/
03224 int file_list(int pi, char *fpat,  char *buf, unsigned count);
03225 /*D
03226 This function returns a list of files which match a pattern.
03227 
03228 . .
03229    pi: >=0 (as returned by [*pigpio_start*]).
03230  fpat: file pattern to match.
03231   buf: an array to receive the matching file names.
03232 count: the maximum number of bytes to read.
03233 . .
03234 
03235 Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS,
03236 or PI_NO_FILE_MATCH.
03237 
03238 The pattern must match an entry in /opt/pigpio/access.  The pattern
03239 may contain wildcards.  See [*file_open*].
03240 
03241 NOTE
03242 
03243 The returned value is not the number of files, it is the number
03244 of bytes in the buffer.  The file names are separated by newline
03245 characters.
03246 
03247 ...
03248 #include <stdio.h>
03249 #include <pigpiod_if2.h>
03250 
03251 int main(int argc, char *argv[])
03252 {
03253    int pi, handle, c;
03254    char buf[60000];
03255 
03256    pi = pigpio_start(NULL, NULL);
03257 
03258    if (pi < 0) return 1;
03259 
03260    // assumes /opt/pigpio/access contains the following line
03261    // /ram/*.c r
03262 
03263    c = file_list(pi, "/ram/p*.c", buf, sizeof(buf));
03264 
03265    if (c >= 0)
03266    {
03267       buf[c] = 0;
03268       printf("%s", buf);
03269    }
03270 
03271    pigpio_stop(pi);
03272 }
03273 ...
03274 D*/
03275 
03276 #pragma GCC diagnostic pop
03277 
03278 
03279 /*F*/
03280 int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f);
03281 /*D
03282 This function initialises a new callback.
03283 
03284 . .
03285        pi: >=0 (as returned by [*pigpio_start*]).
03286 user_gpio: 0-31.
03287      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
03288         f: the callback function.
03289 . .
03290 
03291 The function returns a callback id if OK, otherwise pigif_bad_malloc,
03292 pigif_duplicate_callback, or pigif_bad_callback.
03293 
03294 The callback is called with the GPIO, edge, and tick, whenever the
03295 GPIO has the identified edge.
03296 
03297 . .
03298 Parameter   Value    Meaning
03299 
03300 GPIO        0-31     The GPIO which has changed state
03301 
03302 edge        0-2      0 = change to low (a falling edge)
03303                      1 = change to high (a rising edge)
03304                      2 = no level change (a watchdog timeout)
03305 
03306 tick        32 bit   The number of microseconds since boot
03307                      WARNING: this wraps around from
03308                      4294967295 to 0 roughly every 72 minutes
03309 . .
03310 D*/
03311 
03312 /*F*/
03313 int callback_ex
03314    (int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata);
03315 /*D
03316 This function initialises a new callback.
03317 
03318 . .
03319        pi: >=0 (as returned by [*pigpio_start*]).
03320 user_gpio: 0-31.
03321      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
03322         f: the callback function.
03323  userdata: a pointer to arbitrary user data.
03324 . .
03325 
03326 The function returns a callback id if OK, otherwise pigif_bad_malloc,
03327 pigif_duplicate_callback, or pigif_bad_callback.
03328 
03329 The callback is called with the GPIO, edge, tick, and the userdata
03330 pointer, whenever the GPIO has the identified edge.
03331 
03332 . .
03333 Parameter   Value    Meaning
03334 
03335 GPIO        0-31     The GPIO which has changed state
03336 
03337 edge        0-2      0 = change to low (a falling edge)
03338                      1 = change to high (a rising edge)
03339                      2 = no level change (a watchdog timeout)
03340 
03341 tick        32 bit   The number of microseconds since boot
03342                      WARNING: this wraps around from
03343                      4294967295 to 0 roughly every 72 minutes
03344 
03345 userdata    pointer  Pointer to an arbitrary object
03346 . .
03347 D*/
03348 
03349 /*F*/
03350 int callback_cancel(unsigned callback_id);
03351 /*D
03352 This function cancels a callback identified by its id.
03353 
03354 . .
03355 callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*].
03356 . .
03357 
03358 The function returns 0 if OK, otherwise pigif_callback_not_found.
03359 D*/
03360 
03361 /*F*/
03362 int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout);
03363 /*D
03364 This function waits for an edge on the GPIO for up to timeout
03365 seconds.
03366 
03367 . .
03368        pi: >=0 (as returned by [*pigpio_start*]).
03369 user_gpio: 0-31.
03370      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
03371   timeout: >=0.
03372 . .
03373 
03374 The function returns when the edge occurs or after the timeout.
03375 
03376 Do not use this function for precise timing purposes,
03377 the edge is only checked 20 times a second. Whenever
03378 you need to know the accurate time of GPIO events use
03379 a [*callback*] function.
03380 
03381 The function returns 1 if the edge occurred, otherwise 0.
03382 D*/
03383 
03384 /*F*/
03385 int bsc_xfer(int pi, bsc_xfer_t *bscxfer);
03386 /*D
03387 This function provides a low-level interface to the
03388 SPI/I2C Slave peripheral.  This peripheral allows the
03389 Pi to act as a slave device on an I2C or SPI bus.
03390 
03391 I can't get SPI to work properly.  I tried with a
03392 control word of 0x303 and swapped MISO and MOSI.
03393 
03394 The function sets the BSC mode, writes any data in
03395 the transmit buffer to the BSC transmit FIFO, and
03396 copies any data in the BSC receive FIFO to the
03397 receive buffer.
03398 
03399 . .
03400      pi: >=0 (as returned by [*pigpio_start*]).
03401 bscxfer: a structure defining the transfer.
03402 
03403 typedef struct
03404 {
03405    uint32_t control;          // Write
03406    int rxCnt;                 // Read only
03407    char rxBuf[BSC_FIFO_SIZE]; // Read only
03408    int txCnt;                 // Write
03409    char txBuf[BSC_FIFO_SIZE]; // Write
03410 } bsc_xfer_t;
03411 . .
03412 
03413 To start a transfer set control (see below) and copy the bytes to
03414 be sent (if any) to txBuf and set the byte count in txCnt.
03415 
03416 Upon return rxCnt will be set to the number of received bytes placed
03417 in rxBuf.
03418 
03419 The returned function value is the status of the transfer (see below).
03420 
03421 If there was an error the status will be less than zero
03422 (and will contain the error code).
03423 
03424 The most significant word of the returned status contains the number
03425 of bytes actually copied from txBuf to the BSC transmit FIFO (may be
03426 less than requested if the FIFO already contained untransmitted data).
03427 
03428 Note that the control word sets the BSC mode.  The BSC will stay in
03429 that mode until a different control word is sent.
03430 
03431 The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode
03432 and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode.  You
03433 need to swap MISO/MOSI between master and slave.
03434 
03435 When a zero control word is received GPIO 18-21 will be reset
03436 to INPUT mode.
03437 
03438 control consists of the following bits.
03439 
03440 . .
03441 22 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
03442  a  a  a  a  a  a  a  -  - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN
03443 . .
03444 
03445 Bits 0-13 are copied unchanged to the BSC CR register.  See
03446 pages 163-165 of the Broadcom peripherals document for full
03447 details.
03448 
03449 aaaaaaa @ defines the I2C slave address (only relevant in I2C mode)
03450 IT      @ invert transmit status flags
03451 HC      @ enable host control
03452 TF      @ enable test FIFO
03453 IR      @ invert receive status flags
03454 RE      @ enable receive
03455 TE      @ enable transmit
03456 BK      @ abort operation and clear FIFOs
03457 EC      @ send control register as first I2C byte
03458 ES      @ send status register as first I2C byte
03459 PL      @ set SPI polarity high
03460 PH      @ set SPI phase high
03461 I2      @ enable I2C mode
03462 SP      @ enable SPI mode
03463 EN      @ enable BSC peripheral
03464 
03465 The returned status has the following format
03466 
03467 . .
03468 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
03469  S  S  S  S  S  R  R  R  R  R  T  T  T  T  T RB TE RF TF RE TB
03470 . .
03471 
03472 Bits 0-15 are copied unchanged from the BSC FR register.  See
03473 pages 165-166 of the Broadcom peripherals document for full
03474 details.
03475 
03476 SSSSS @ number of bytes successfully copied to transmit FIFO
03477 RRRRR @ number of bytes in receieve FIFO
03478 TTTTT @ number of bytes in transmit FIFO
03479 RB    @ receive busy
03480 TE    @ transmit FIFO empty
03481 RF    @ receive FIFO full
03482 TF    @ transmit FIFO full
03483 RE    @ receive FIFO empty
03484 TB    @ transmit busy
03485 
03486 The following example shows how to configure the BSC peripheral as
03487 an I2C slave with address 0x13 and send four bytes.
03488 
03489 ...
03490 bsc_xfer_t xfer;
03491 
03492 xfer.control = (0x13<<16) | 0x305;
03493 
03494 memcpy(xfer.txBuf, "ABCD", 4);
03495 xfer.txCnt = 4;
03496 
03497 status = bsc_xfer(pi, &xfer);
03498 
03499 if (status >= 0)
03500 {
03501    // process transfer
03502 }
03503 ...
03504 D*/
03505 
03506 /*F*/
03507 int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer);
03508 /*D
03509 This function allows the Pi to act as a slave I2C device.
03510 
03511 The data bytes (if any) are written to the BSC transmit
03512 FIFO and the bytes in the BSC receive FIFO are returned.
03513 
03514 . .
03515       pi: >=0 (as returned by [*pigpio_start*]).
03516 i2c_addr: 0-0x7F.
03517  bscxfer: a structure defining the transfer.
03518 
03519 typedef struct
03520 {
03521    uint32_t control;          // N/A
03522    int rxCnt;                 // Read only
03523    char rxBuf[BSC_FIFO_SIZE]; // Read only
03524    int txCnt;                 // Write
03525    char txBuf[BSC_FIFO_SIZE]; // Write
03526 } bsc_xfer_t;
03527 . .
03528 
03529 txCnt is set to the number of bytes to be transmitted, possibly
03530 zero. The data itself should be copied to txBuf.
03531 
03532 Any received data will be written to rxBuf with rxCnt set.
03533 
03534 See [*bsc_xfer*] for details of the returned status value.
03535 
03536 If there was an error the status will be less than zero
03537 (and will contain the error code).
03538 
03539 Note that an i2c_address of 0 may be used to close
03540 the BSC device and reassign the used GPIO (18/19)
03541 as inputs.
03542 D*/
03543 
03544 /*F*/
03545 int event_callback(int pi, unsigned event, evtCBFunc_t f);
03546 /*D
03547 This function initialises an event callback.
03548 
03549 . .
03550    pi: >=0 (as returned by [*pigpio_start*]).
03551 event: 0-31.
03552     f: the callback function.
03553 . .
03554 
03555 The function returns a callback id if OK, otherwise pigif_bad_malloc,
03556 pigif_duplicate_callback, or pigif_bad_callback.
03557 
03558 The callback is called with the event id, and tick, whenever the
03559 event occurs.
03560 D*/
03561 
03562 /*F*/
03563 int event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *userdata);
03564 /*D
03565 This function initialises an event callback.
03566 
03567 . .
03568       pi: >=0 (as returned by [*pigpio_start*]).
03569    event: 0-31.
03570        f: the callback function.
03571 userdata: a pointer to arbitrary user data.
03572 . .
03573 
03574 The function returns a callback id if OK, otherwise pigif_bad_malloc,
03575 pigif_duplicate_callback, or pigif_bad_callback.
03576 
03577 The callback is called with the event id, the tick, and the userdata
03578 pointer whenever the event occurs.
03579 D*/
03580 
03581 /*F*/
03582 int event_callback_cancel(unsigned callback_id);
03583 /*D
03584 This function cancels an event callback identified by its id.
03585 
03586 . .
03587 callback_id: >=0, as returned by a call to [*event_callback*] or
03588 [*event_callback_ex*].
03589 . .
03590 
03591 The function returns 0 if OK, otherwise pigif_callback_not_found.
03592 D*/
03593 
03594 /*F*/
03595 int wait_for_event(int pi, unsigned event, double timeout);
03596 /*D
03597 This function waits for an event for up to timeout seconds.
03598 
03599 . .
03600      pi: >=0 (as returned by [*pigpio_start*]).
03601   event: 0-31.
03602 timeout: >=0.
03603 . .
03604 
03605 The function returns when the event occurs or after the timeout.
03606 
03607 The function returns 1 if the event occurred, otherwise 0.
03608 D*/
03609 
03610 /*F*/
03611 int event_trigger(int pi, unsigned event);
03612 /*D
03613 This function signals the occurrence of an event.
03614 
03615 . .
03616    pi: >=0 (as returned by [*pigpio_start*]).
03617 event: 0-31.
03618 . .
03619 
03620 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
03621 
03622 An event is a signal used to inform one or more consumers
03623 to start an action.  Each consumer which has registered an interest
03624 in the event (e.g. by calling [*event_callback*]) will be informed by
03625 a callback.
03626 
03627 One event, PI_EVENT_BSC (31) is predefined.  This event is
03628 auto generated on BSC slave activity.
03629 
03630 The meaning of other events is arbitrary.
03631 
03632 Note that other than its id and its tick there is no data associated
03633 with an event.
03634 D*/
03635 
03636 /*PARAMS
03637 
03638 active :: 0-1000000
03639 
03640 The number of microseconds level changes are reported for once
03641 a noise filter has been triggered (by [*steady*] microseconds of
03642 a stable level).
03643 
03644 *addrStr::
03645 A string specifying the host or IP address of the Pi running
03646 the pigpio daemon.  It may be NULL in which case localhost
03647 is used unless overridden by the PIGPIO_ADDR environment
03648 variable.
03649 
03650 arg1::
03651 An unsigned argument passed to a user customised function.  Its
03652 meaning is defined by the customiser.
03653 
03654 arg2::
03655 An unsigned argument passed to a user customised function.  Its
03656 meaning is defined by the customiser.
03657 
03658 argc::
03659 The count of bytes passed to a user customised function.
03660 
03661 *argx::
03662 A pointer to an array of bytes passed to a user customised function.
03663 Its meaning and content is defined by the customiser.
03664 
03665 baud::
03666 The speed of serial communication (I2C, SPI, serial link, waves) in
03667 bits per second.
03668 
03669 bit::
03670 A value of 0 or 1.
03671 
03672 bits::
03673 A value used to select GPIO.  If bit n of bits is set then GPIO n is
03674 selected.
03675 
03676 A convenient way to set bit n is to or in (1<<n).
03677 
03678 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
03679 
03680 bsc_xfer_t::
03681 
03682 . .
03683 typedef struct
03684 {
03685    uint32_t control;          // Write
03686    int rxCnt;                 // Read only
03687    char rxBuf[BSC_FIFO_SIZE]; // Read only
03688    int txCnt;                 // Write
03689    char txBuf[BSC_FIFO_SIZE]; // Write
03690 } bsc_xfer_t;
03691 . .
03692 
03693 *bscxfer::
03694 A pointer to a [*bsc_xfer_t*] object used to control a BSC transfer.
03695 
03696 *buf::
03697 A buffer to hold data being sent or being received.
03698 
03699 bufSize::
03700 The size in bytes of a buffer.
03701 
03702 
03703 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
03704 An 8-bit byte value.
03705 
03706 callback_id::
03707 A value >=0, as returned by a call to a callback function, one of
03708 
03709 [*callback*] 
03710 [*callback_ex*] 
03711 [*event_callback*] 
03712 [*event_callback_ex*]
03713 
03714 The id is passed to [*callback_cancel*] or [*event_callback_cancel*]
03715 to cancel the callback.
03716 
03717 CBFunc_t::
03718 . .
03719 typedef void (*CBFunc_t)
03720    (int pi, unsigned user_gpio, unsigned level, uint32_t tick);
03721 . .
03722 
03723 CBFuncEx_t::
03724 . .
03725 typedef void (*CBFuncEx_t)
03726    (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void * userdata);
03727 . .
03728 
03729 char::
03730 A single character, an 8 bit quantity able to store 0-255.
03731 
03732 clkfreq::4689-250000000 (250M)
03733 The hardware clock frequency.
03734 
03735 count::
03736 The number of bytes to be transferred in a file, I2C, SPI, or serial
03737 command.
03738 
03739 CS::
03740 The GPIO used for the slave select signal when bit banging SPI.
03741 
03742 data_bits::1-32
03743 The number of data bits in each character of serial data.
03744 
03745 . .
03746 #define PI_MIN_WAVE_DATABITS 1
03747 #define PI_MAX_WAVE_DATABITS 32
03748 . .
03749 
03750 double::
03751 A floating point number.
03752 
03753 dutycycle::0-range
03754 A number representing the ratio of on time to off time for PWM.
03755 
03756 The number may vary between 0 and range (default 255) where
03757 0 is off and range is fully on.
03758 
03759 edge::
03760 Used to identify a GPIO level transition of interest.  A rising edge is
03761 a level change from 0 to 1.  A falling edge is a level change from 1 to 0.
03762 
03763 . .
03764 RISING_EDGE  0
03765 FALLING_EDGE 1
03766 EITHER_EDGE. 2
03767 . .
03768 
03769 errnum::
03770 A negative number indicating a function call failed and the nature
03771 of the error.
03772 
03773 event::0-31
03774 An event is a signal used to inform one or more consumers
03775 to start an action.
03776 
03777 evtCBFunc_t::
03778 
03779 . .
03780 typedef void (*evtCBFunc_t)
03781    (int pi, unsigned event, uint32_t tick);
03782 . .
03783 
03784 evtCBFuncEx_t::
03785 
03786 . .
03787 typedef void (*evtCBFuncEx_t)
03788    (int pi, unsigned event, uint32_t tick, void *userdata);
03789 . .
03790 
03791 f::
03792 A function.
03793 
03794 *file::
03795 A full file path.  To be accessible the path must match an entry in
03796 /opt/pigpio/access.
03797 
03798 *fpat::
03799 A file path which may contain wildcards.  To be accessible the path
03800 must match an entry in /opt/pigpio/access.
03801 
03802 frequency::>=0
03803 The number of times a GPIO is swiched on and off per second.  This
03804 can be set per GPIO and may be as little as 5Hz or as much as
03805 40KHz.  The GPIO will be on for a proportion of the time as defined
03806 by its dutycycle.
03807 
03808 gpio::
03809 A Broadcom numbered GPIO, in the range 0-53.
03810 
03811 There  are 54 General Purpose Input Outputs (GPIO) named GPIO0 through
03812 GPIO53.
03813 
03814 They are split into two  banks.   Bank  1  consists  of  GPIO0  through
03815 GPIO31.  Bank 2 consists of GPIO32 through GPIO53.
03816 
03817 All the GPIO which are safe for the user to read and write are in
03818 bank 1.  Not all GPIO in bank 1 are safe though.  Type 1 boards
03819 have 17  safe GPIO.  Type 2 boards have 21.  Type 3 boards have 26.
03820 
03821 See [*get_hardware_revision*].
03822 
03823 The user GPIO are marked with an X in the following table.
03824 
03825 . .
03826           0  1  2  3  4  5  6  7  8  9 10 11 12 13 14 15
03827 Type 1    X  X  -  -  X  -  -  X  X  X  X  X  -  -  X  X
03828 Type 2    -  -  X  X  X  -  -  X  X  X  X  X  -  -  X  X
03829 Type 3          X  X  X  X  X  X  X  X  X  X  X  X  X  X
03830 
03831          16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
03832 Type 1    -  X  X  -  -  X  X  X  X  X  -  -  -  -  -  -
03833 Type 2    -  X  X  -  -  -  X  X  X  X  -  X  X  X  X  X
03834 Type 3    X  X  X  X  X  X  X  X  X  X  X  X  -  -  -  -
03835 . .
03836 
03837 gpioPulse_t::
03838 . .
03839 typedef struct
03840 {
03841    uint32_t gpioOn;
03842    uint32_t gpioOff;
03843    uint32_t usDelay;
03844 } gpioPulse_t;
03845 . .
03846 
03847 gpioThreadFunc_t::
03848 . .
03849 typedef void *(gpioThreadFunc_t) (void *);
03850 . .
03851 
03852 handle::>=0
03853 A number referencing an object opened by one of
03854 
03855 [*file_open*] 
03856 [*i2c_open*] 
03857 [*notify_open*] 
03858 [*serial_open*] 
03859 [*spi_open*]
03860 
03861 i2c_addr::0-0x7F
03862 The address of a device on the I2C bus.
03863 
03864 i2c_bus::>=0
03865 An I2C bus number.
03866 
03867 i2c_flags::0
03868 Flags which modify an I2C open command.  None are currently defined.
03869 
03870 i2c_reg:: 0-255
03871 A register of an I2C device.
03872 
03873 *inBuf::
03874 A buffer used to pass data to a function.
03875 
03876 inLen::
03877 The number of bytes of data in a buffer.
03878 
03879 int::
03880 A whole number, negative or positive.
03881 
03882 int32_t::
03883 A 32-bit signed value.
03884 
03885 invert::
03886 A flag used to set normal or inverted bit bang serial data level logic.
03887 
03888 level::
03889 The level of a GPIO.  Low or High.
03890 
03891 . .
03892 PI_OFF 0
03893 PI_ON 1
03894 
03895 PI_CLEAR 0
03896 PI_SET 1
03897 
03898 PI_LOW 0
03899 PI_HIGH 1
03900 . .
03901 
03902 There is one exception.  If a watchdog expires on a GPIO the level will be
03903 reported as PI_TIMEOUT.  See [*set_watchdog*].
03904 
03905 . .
03906 PI_TIMEOUT 2
03907 . .
03908 
03909 MISO::
03910 The GPIO used for the MISO signal when bit banging SPI.
03911 
03912 mode::
03913 1. The operational mode of a GPIO, normally INPUT or OUTPUT.
03914 
03915 . .
03916 PI_INPUT 0
03917 PI_OUTPUT 1
03918 PI_ALT0 4
03919 PI_ALT1 5
03920 PI_ALT2 6
03921 PI_ALT3 7
03922 PI_ALT4 3
03923 PI_ALT5 2
03924 . .
03925 
03926 2. The mode of waveform transmission.
03927 
03928 . .
03929 PI_WAVE_MODE_ONE_SHOT      0
03930 PI_WAVE_MODE_REPEAT        1
03931 PI_WAVE_MODE_ONE_SHOT_SYNC 2
03932 PI_WAVE_MODE_REPEAT_SYNC   3
03933 . .
03934 
03935 3. A file open mode.
03936 
03937 . .
03938 PI_FILE_READ  1
03939 PI_FILE_WRITE 2
03940 PI_FILE_RW    3
03941 . .
03942 
03943 The following values can be or'd into the mode.
03944 
03945 . .
03946 PI_FILE_APPEND 4
03947 PI_FILE_CREATE 8
03948 PI_FILE_TRUNC  16
03949 . .
03950 
03951 MOSI::
03952 The GPIO used for the MOSI signal when bit banging SPI.
03953 
03954 numBytes::
03955 The number of bytes used to store characters in a string.  Depending
03956 on the number of bits per character there may be 1, 2, or 4 bytes
03957 per character.
03958 
03959 numPar:: 0-10
03960 The number of parameters passed to a script.
03961 
03962 numPulses::
03963 The number of pulses to be added to a waveform.
03964 
03965 offset::
03966 The associated data starts this number of microseconds from the start of
03967 the waveform.
03968 
03969 *outBuf::
03970 A buffer used to return data from a function.
03971 
03972 outLen::
03973 The size in bytes of an output buffer.
03974 
03975 pad:: 0-2
03976 A set of GPIO which share common drivers.
03977 
03978 Pad @ GPIO
03979 0   @ 0-27
03980 1   @ 28-45
03981 2   @ 46-53
03982 
03983 padStrength:: 1-16
03984 The mA which may be drawn from each GPIO whilst still guaranteeing the
03985 high and low levels.
03986 
03987 *param::
03988 An array of script parameters.
03989 
03990 pi::
03991 An integer defining a connected Pi.  The value is returned by
03992 [*pigpio_start*] upon success.
03993 
03994 *portStr::
03995 A string specifying the port address used by the Pi running
03996 the pigpio daemon.  It may be NULL in which case "8888"
03997 is used unless overridden by the PIGPIO_PORT environment
03998 variable.
03999 
04000 *pth::
04001 A thread identifier, returned by [*start_thread*].
04002 
04003 
04004 pthread_t::
04005 A thread identifier.
04006 
04007 pud::0-2
04008 The setting of the pull up/down resistor for a GPIO, which may be off,
04009 pull-up, or pull-down.
04010 . .
04011 PI_PUD_OFF 0
04012 PI_PUD_DOWN 1
04013 PI_PUD_UP 2
04014 . .
04015 
04016 pulseLen::
04017 1-100, the length of a trigger pulse in microseconds.
04018 
04019 *pulses::
04020 An array of pulses to be added to a waveform.
04021 
04022 pulsewidth::0, 500-2500
04023 . .
04024 PI_SERVO_OFF 0
04025 PI_MIN_SERVO_PULSEWIDTH 500
04026 PI_MAX_SERVO_PULSEWIDTH 2500
04027 . .
04028 
04029 PWMduty::0-1000000 (1M)
04030 The hardware PWM dutycycle.
04031 
04032 . .
04033 #define PI_HW_PWM_RANGE 1000000
04034 . .
04035 
04036 PWMfreq::1-125000000 (125M)
04037 The hardware PWM frequency.
04038 
04039 . .
04040 #define PI_HW_PWM_MIN_FREQ 1
04041 #define PI_HW_PWM_MAX_FREQ 125000000
04042 . .
04043 
04044 range::25-40000
04045 The permissible dutycycle values are 0-range.
04046 
04047 . .
04048 PI_MIN_DUTYCYCLE_RANGE 25
04049 PI_MAX_DUTYCYCLE_RANGE 40000
04050 . .
04051 
04052 *retBuf::
04053 A buffer to hold a number of bytes returned to a used customised function,
04054 
04055 retMax::
04056 The maximum number of bytes a user customised function should return.
04057 
04058 
04059 *rxBuf::
04060 A pointer to a buffer to receive data.
04061 
04062 SCL::
04063 The user GPIO to use for the clock when bit banging I2C.
04064 
04065 SCLK::
04066 The GPIO used for the SCLK signal when bit banging SPI.
04067 
04068 *script::
04069 A pointer to the text of a script.
04070 
04071 script_id::
04072 An id of a stored script as returned by [*store_script*].
04073 
04074 *scriptName::
04075 The name of a [*shell_*] script to be executed.  The script must be present in
04076 /opt/pigpio/cgi and must have execute permission.
04077 
04078 *scriptString::
04079 The string to be passed to a [*shell_*] script to be executed.
04080 
04081 SDA::
04082 The user GPIO to use for data when bit banging I2C.
04083 
04084 seconds::
04085 The number of seconds.
04086 
04087 seekFrom::
04088 
04089 . .
04090 PI_FROM_START   0
04091 PI_FROM_CURRENT 1
04092 PI_FROM_END     2
04093 . .
04094 
04095 seekOffset::
04096 The number of bytes to move forward (positive) or backwards (negative)
04097 from the seek position (start, current, or end of file).
04098 
04099 ser_flags::
04100 Flags which modify a serial open command.  None are currently defined.
04101 
04102 *ser_tty::
04103 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
04104 
04105 size_t::
04106 A standard type used to indicate the size of an object in bytes.
04107 
04108 spi_channel::
04109 A SPI channel, 0-2.
04110 
04111 spi_flags::
04112 See [*spi_open*] and [*bb_spi_open*].
04113 
04114 steady:: 0-300000
04115 
04116 The number of microseconds level changes must be stable for
04117 before reporting the level changed ([*set_glitch_filter*]) or triggering
04118 the active part of a noise filter ([*set_noise_filter*]).
04119 
04120 stop_bits::2-8
04121 The number of (half) stop bits to be used when adding serial data
04122 to a waveform.
04123 
04124 . .
04125 #define PI_MIN_WAVE_HALFSTOPBITS 2
04126 #define PI_MAX_WAVE_HALFSTOPBITS 8
04127 . .
04128 
04129 *str::
04130  An array of characters.
04131 
04132 thread_func::
04133 A function of type gpioThreadFunc_t used as the main function of a
04134 thread.
04135 
04136 timeout::
04137 A GPIO watchdog timeout in milliseconds.
04138 
04139 . .
04140 PI_MIN_WDOG_TIMEOUT 0
04141 PI_MAX_WDOG_TIMEOUT 60000
04142 . .
04143 
04144 *txBuf::
04145 An array of bytes to transmit.
04146 
04147 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
04148 A 32-bit unsigned value.
04149 
04150 unsigned::
04151 A whole number >= 0.
04152 
04153 user_gpio::
04154 0-31, a Broadcom numbered GPIO.
04155 
04156 See [*gpio*].
04157 
04158 *userdata::
04159 
04160 A pointer to arbitrary user data.  This may be used to identify the instance.
04161 
04162 You must ensure that the pointer is in scope at the time it is processed.  If
04163 it is a pointer to a global this is automatic.  Do not pass the address of a
04164 local variable.  If you want to pass a transient object then use the
04165 following technique.
04166 
04167 In the calling function:
04168 
04169 . .
04170 user_type *userdata; 
04171 user_type my_userdata;
04172 
04173 userdata = malloc(sizeof(user_type)); 
04174 *userdata = my_userdata;
04175 . .
04176 
04177 In the receiving function:
04178 
04179 . .
04180 user_type my_userdata = *(user_type*)userdata;
04181 
04182 free(userdata);
04183 . .
04184 
04185 void::
04186 Denoting no parameter is required
04187 
04188 wave_add_*::
04189 One of
04190 
04191 [*wave_add_new*] 
04192 [*wave_add_generic*] 
04193 [*wave_add_serial*]
04194 
04195 wave_id::
04196 A number representing a waveform created by [*wave_create*].
04197 
04198 wave_send_*::
04199 One of
04200 
04201 [*wave_send_once*] 
04202 [*wave_send_repeat*]
04203 
04204 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
04205 A 16-bit word value.
04206 
04207 PARAMS*/
04208 
04209 /*DEF_S pigpiod_if2 Error Codes*/
04210 
04211 typedef enum
04212 {
04213    pigif_bad_send           = -2000,
04214    pigif_bad_recv           = -2001,
04215    pigif_bad_getaddrinfo    = -2002,
04216    pigif_bad_connect        = -2003,
04217    pigif_bad_socket         = -2004,
04218    pigif_bad_noib           = -2005,
04219    pigif_duplicate_callback = -2006,
04220    pigif_bad_malloc         = -2007,
04221    pigif_bad_callback       = -2008,
04222    pigif_notify_failed      = -2009,
04223    pigif_callback_not_found = -2010,
04224    pigif_unconnected_pi     = -2011,
04225    pigif_too_many_pis       = -2012,
04226 } pigifError_t;
04227 
04228 /*DEF_E*/
04229 
04230 #ifdef __cplusplus
04231 }
04232 #endif
04233 
04234 #endif
04235 


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