pigpiod_if.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_IF_H
00029 #define PIGPIOD_IF_H
00030 
00031 #include "pigpio.h"
00032 
00033 #define PIGPIOD_IF_VERSION 28
00034 
00035 /*TEXT
00036 
00037 THIS LIBRARY IS DEPRECATED.  NEW CODE SHOULD BE WRITTEN TO
00038 USE THE MORE VERSATILE pigpiod_if2 LIBRARY.
00039 
00040 pigpiod_if is a C library for the Raspberry which allows control
00041 of the GPIO via the socket interface to the pigpio daemon. 
00042 
00043 *Features*
00044 
00045 o hardware timed PWM on any of GPIO 0-31
00046 
00047 o hardware timed servo pulses on any of GPIO 0-31
00048 
00049 o callbacks when any of GPIO 0-31 change state
00050 
00051 o callbacks at timed intervals
00052 
00053 o reading/writing all of the GPIO in a bank as one operation
00054 
00055 o individually setting GPIO modes, reading and writing
00056 
00057 o notifications when any of GPIO 0-31 change state
00058 
00059 o the construction of output waveforms with microsecond timing
00060 
00061 o rudimentary permission control over GPIO
00062 
00063 o a simple interface to start and stop new threads
00064 
00065 o I2C, SPI, and serial link wrappers
00066 
00067 o creating and running scripts on the pigpio daemon
00068 
00069 *GPIO*
00070 
00071 ALL GPIO are identified by their Broadcom number.
00072 
00073 *Notes*
00074 
00075 The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals.
00076 
00077 *Usage*
00078 
00079 Include <pigpiod_if.h> in your source files.
00080 
00081 Assuming your source is in prog.c use the following command to build
00082 
00083 . .
00084 gcc -Wall -pthread -o prog prog.c -lpigpiod_if -lrt
00085 . .
00086 
00087 to run make sure the pigpio daemon is running
00088 
00089 . .
00090 sudo pigpiod
00091 
00092  ./prog # sudo is not required to run programs linked to pigpiod_if
00093 . .
00094 
00095 For examples see x_pigpiod_if.c within the pigpio archive file.
00096 
00097 *Notes*
00098 
00099 All the functions which return an int return < 0 on error
00100 
00101 TEXT*/
00102 
00103 /*OVERVIEW
00104 
00105 ESSENTIAL
00106 
00107 pigpio_start               Connects to the pigpio daemon
00108 pigpio_stop                Disconnects from the pigpio daemon
00109 
00110 BEGINNER
00111 
00112 set_mode                   Set a GPIO mode
00113 get_mode                   Get a GPIO mode
00114 
00115 set_pull_up_down           Set/clear GPIO pull up/down resistor
00116 
00117 gpio_read                  Read a GPIO
00118 gpio_write                 Write a GPIO
00119 
00120 set_PWM_dutycycle          Start/stop PWM pulses on a GPIO
00121 get_PWM_dutycycle          Get the PWM dutycycle in use on a GPIO
00122 
00123 set_servo_pulsewidth       Start/stop servo pulses on a GPIO
00124 get_servo_pulsewidth       Get the servo pulsewidth in use on a GPIO
00125 
00126 callback                   Create GPIO level change callback
00127 callback_ex                Create GPIO level change callback
00128 callback_cancel            Cancel a callback
00129 wait_for_edge              Wait for GPIO level change
00130 
00131 INTERMEDIATE
00132 
00133 gpio_trigger               Send a trigger pulse to a GPIO.
00134 
00135 set_watchdog               Set a watchdog on a GPIO.
00136 
00137 set_PWM_range              Configure PWM range for a GPIO
00138 get_PWM_range              Get configured PWM range for a GPIO
00139 
00140 set_PWM_frequency          Configure PWM frequency for a GPIO
00141 get_PWM_frequency          Get configured PWM frequency for a GPIO
00142 
00143 read_bank_1                Read all GPIO in bank 1
00144 read_bank_2                Read all GPIO in bank 2
00145 
00146 clear_bank_1               Clear selected GPIO in bank 1
00147 clear_bank_2               Clear selected GPIO in bank 2
00148 
00149 set_bank_1                 Set selected GPIO in bank 1
00150 set_bank_2                 Set selected GPIO in bank 2
00151 
00152 start_thread               Start a new thread
00153 stop_thread                Stop a previously started thread
00154 
00155 ADVANCED
00156 
00157 get_PWM_real_range         Get underlying PWM range for a GPIO
00158 
00159 notify_open                Request a notification handle
00160 notify_begin               Start notifications for selected GPIO
00161 notify_pause               Pause notifications
00162 notify_close               Close a notification
00163 
00164 bb_serial_read_open        Opens a GPIO for bit bang serial reads
00165 bb_serial_read             Reads bit bang serial data from a GPIO
00166 bb_serial_read_close       Closes a GPIO for bit bang serial reads
00167 bb_serial_invert           Invert serial logic (1 invert, 0 normal)
00168 
00169 hardware_clock             Start hardware clock on supported GPIO
00170 hardware_PWM               Start hardware PWM on supported GPIO
00171 
00172 set_glitch_filter         Set a glitch filter on a GPIO
00173 set_noise_filter          Set a noise filter on a GPIO
00174 
00175 SCRIPTS
00176 
00177 store_script               Store a script
00178 run_script                 Run a stored script
00179 script_status              Get script status and parameters
00180 stop_script                Stop a running script
00181 delete_script              Delete a stored script
00182 
00183 WAVES
00184 
00185 wave_clear                 Deletes all waveforms
00186 
00187 wave_add_new               Starts a new waveform
00188 wave_add_generic           Adds a series of pulses to the waveform
00189 wave_add_serial            Adds serial data to the waveform
00190 
00191 wave_create                Creates a waveform from added data
00192 wave_delete                Deletes one or more waveforms
00193 
00194 wave_send_once             Transmits a waveform once
00195 wave_send_repeat           Transmits a waveform repeatedly
00196 
00197 wave_chain                 Transmits a chain of waveforms
00198 
00199 wave_tx_busy               Checks to see if the waveform has ended
00200 wave_tx_stop               Aborts the current waveform
00201 
00202 wave_get_micros            Length in microseconds of the current waveform
00203 wave_get_high_micros       Length of longest waveform so far
00204 wave_get_max_micros        Absolute maximum allowed micros
00205 
00206 wave_get_pulses            Length in pulses of the current waveform
00207 wave_get_high_pulses       Length of longest waveform so far
00208 wave_get_max_pulses        Absolute maximum allowed pulses
00209 
00210 wave_get_cbs               Length in cbs of the current waveform
00211 wave_get_high_cbs          Length of longest waveform so far
00212 wave_get_max_cbs           Absolute maximum allowed cbs
00213 
00214 I2C
00215 
00216 i2c_open                   Opens an I2C device
00217 i2c_close                  Closes an I2C device
00218 
00219 i2c_write_quick            smbus write quick
00220 i2c_write_byte             smbus write byte
00221 i2c_read_byte              smbus read byte
00222 i2c_write_byte_data        smbus write byte data
00223 i2c_write_word_data        smbus write word data
00224 i2c_read_byte_data         smbus read byte data
00225 i2c_read_word_data         smbus read word data
00226 i2c_process_call           smbus process call
00227 i2c_write_block_data       smbus write block data
00228 i2c_read_block_data        smbus read block data
00229 i2c_block_process_call     smbus block process call
00230 
00231 i2c_write_i2c_block_data   smbus write I2C block data
00232 i2c_read_i2c_block_data    smbus read I2C block data
00233 
00234 i2c_read_device            Reads the raw I2C device
00235 i2c_write_device           Writes the raw I2C device
00236 
00237 i2c_zip                    Performs multiple I2C transactions
00238 
00239 bb_i2c_open                Opens GPIO for bit banging I2C
00240 bb_i2c_close               Closes GPIO for bit banging I2C
00241 bb_i2c_zip                 Performs multiple bit banged I2C transactions
00242 
00243 SPI
00244 
00245 spi_open                   Opens a SPI device
00246 spi_close                  Closes a SPI device
00247 
00248 spi_read                   Reads bytes from a SPI device
00249 spi_write                  Writes bytes to a SPI device
00250 spi_xfer                   Transfers bytes with a SPI device
00251 
00252 SERIAL
00253 
00254 serial_open                Opens a serial device
00255 serial_close               Closes a serial device
00256 
00257 serial_write_byte          Writes a byte to a serial device
00258 serial_read_byte           Reads a byte from a serial device
00259 serial_write               Writes bytes to a serial device
00260 serial_read                Reads bytes from a serial device
00261 
00262 serial_data_available      Returns number of bytes ready to be read
00263 
00264 CUSTOM
00265 
00266 custom_1                   User custom function 1
00267 custom_2                   User custom function 2
00268 
00269 UTILITIES
00270 
00271 get_current_tick           Get current tick (microseconds)
00272 
00273 get_hardware_revision      Get hardware revision
00274 get_pigpio_version         Get the pigpio version
00275 pigpiod_if_version         Get the pigpiod_if version
00276 
00277 pigpio_error               Get a text description of an error code.
00278 
00279 time_sleep                 Sleeps for a float number of seconds
00280 time_time                  Float number of seconds since the epoch
00281 
00282 OVERVIEW*/
00283 
00284 #ifdef __cplusplus
00285 extern "C" {
00286 #endif
00287 
00288 typedef void (*CBFunc_t)  (unsigned user_gpio, unsigned level, uint32_t tick);
00289 
00290 typedef void (*CBFuncEx_t)
00291    (unsigned user_gpio, unsigned level, uint32_t tick, void * user);
00292 
00293 typedef struct callback_s callback_t;
00294 
00295 /*F*/
00296 double time_time(void);
00297 /*D
00298 Return the current time in seconds since the Epoch.
00299 D*/
00300 
00301 /*F*/
00302 void time_sleep(double seconds);
00303 /*D
00304 Delay execution for a given number of seconds.
00305 
00306 . .
00307 seconds: the number of seconds to delay.
00308 . .
00309 D*/
00310 
00311 /*F*/
00312 char *pigpio_error(int errnum);
00313 /*D
00314 Return a text description for an error code.
00315 
00316 . .
00317 errnum: the error code.
00318 . .
00319 D*/
00320 
00321 /*F*/
00322 unsigned pigpiod_if_version(void);
00323 /*D
00324 Return the pigpiod_if version.
00325 D*/
00326 
00327 /*F*/
00328 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata);
00329 /*D
00330 Starts a new thread of execution with thread_func as the main routine.
00331 
00332 . .
00333 thread_func: the main function for the new thread.
00334    userdata: a pointer to an arbitrary argument.
00335 . .
00336 
00337 Returns a pointer to pthread_t if OK, otherwise NULL.
00338 
00339 The function is passed the single argument userdata.
00340 
00341 The thread can be cancelled by passing the pointer to pthread_t to
00342 [*stop_thread*].
00343 D*/
00344 
00345 /*F*/
00346 void stop_thread(pthread_t *pth);
00347 /*D
00348 Cancels the thread pointed at by pth.
00349 
00350 . .
00351 pth: the thread to be stopped.
00352 . .
00353 
00354 No value is returned.
00355 
00356 The thread to be stopped should have been started with [*start_thread*].
00357 D*/
00358 
00359 /*F*/
00360 int pigpio_start(char *addrStr, char *portStr);
00361 /*D
00362 Connect to the pigpio daemon.  Reserving command and
00363 notification streams.
00364 
00365 . .
00366 addrStr: specifies the host or IP address of the Pi running the
00367          pigpio daemon.  It may be NULL in which case localhost
00368          is used unless overridden by the PIGPIO_ADDR environment
00369          variable.
00370 
00371 portStr: specifies the port address used by the Pi running the
00372          pigpio daemon.  It may be NULL in which case "8888"
00373          is used unless overridden by the PIGPIO_PORT environment
00374          variable.
00375 . .
00376 D*/
00377 
00378 /*F*/
00379 void pigpio_stop(void);
00380 /*D
00381 Terminates the connection to the pigpio daemon and releases
00382 resources used by the library.
00383 D*/
00384 
00385 /*F*/
00386 int set_mode(unsigned gpio, unsigned mode);
00387 /*D
00388 Set the GPIO mode.
00389 
00390 . .
00391 gpio: 0-53.
00392 mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1,
00393       PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5.
00394 . .
00395 
00396 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE,
00397 or PI_NOT_PERMITTED.
00398 D*/
00399 
00400 /*F*/
00401 int get_mode(unsigned gpio);
00402 /*D
00403 Get the GPIO mode.
00404 
00405 . .
00406 gpio: 0-53.
00407 . .
00408 
00409 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
00410 D*/
00411 
00412 /*F*/
00413 int set_pull_up_down(unsigned gpio, unsigned pud);
00414 /*D
00415 Set or clear the GPIO pull-up/down resistor.
00416 
00417 . .
00418 gpio: 0-53.
00419  pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF.
00420 . .
00421 
00422 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD,
00423 or PI_NOT_PERMITTED.
00424 D*/
00425 
00426 /*F*/
00427 int gpio_read(unsigned gpio);
00428 /*D
00429 Read the GPIO level.
00430 
00431 . .
00432 gpio:0-53.
00433 . .
00434 
00435 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
00436 D*/
00437 
00438 /*F*/
00439 int gpio_write(unsigned gpio, unsigned level);
00440 /*D
00441 Write the GPIO level.
00442 
00443 . .
00444  gpio: 0-53.
00445 level: 0, 1.
00446 . .
00447 
00448 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL,
00449 or PI_NOT_PERMITTED.
00450 
00451 Notes
00452 
00453 If PWM or servo pulses are active on the GPIO they are switched off.
00454 D*/
00455 
00456 /*F*/
00457 int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle);
00458 /*D
00459 Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO.
00460 
00461 . .
00462 user_gpio: 0-31.
00463 dutycycle: 0-range (range defaults to 255).
00464 . .
00465 
00466 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE,
00467 or PI_NOT_PERMITTED.
00468 Notes
00469 
00470 The [*set_PWM_range*] function may be used to change the
00471 default range of 255.
00472 D*/
00473 
00474 /*F*/
00475 int get_PWM_dutycycle(unsigned user_gpio);
00476 /*D
00477 Return the PWM dutycycle in use on a GPIO.
00478 
00479 . .
00480 user_gpio: 0-31.
00481 . .
00482 
00483 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
00484 
00485 For normal PWM the dutycycle will be out of the defined range
00486 for the GPIO (see [*get_PWM_range*]).
00487 
00488 If a hardware clock is active on the GPIO the reported dutycycle
00489 will be 500000 (500k) out of 1000000 (1M).
00490 
00491 If hardware PWM is active on the GPIO the reported dutycycle
00492 will be out of a 1000000 (1M).
00493 D*/
00494 
00495 /*F*/
00496 int set_PWM_range(unsigned user_gpio, unsigned range);
00497 /*D
00498 Set the range of PWM values to be used on the GPIO.
00499 
00500 . .
00501 user_gpio: 0-31.
00502     range: 25-40000.
00503 . .
00504 
00505 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE,
00506 or PI_NOT_PERMITTED.
00507 
00508 Notes
00509 
00510 If PWM is currently active on the GPIO its dutycycle will be
00511 scaled to reflect the new range.
00512 
00513 The real range, the number of steps between fully off and fully on
00514 for each of the 18 available GPIO frequencies is
00515 
00516 . .
00517   25(#1),    50(#2),   100(#3),   125(#4),    200(#5),    250(#6),
00518  400(#7),   500(#8),   625(#9),   800(#10),  1000(#11),  1250(#12),
00519 2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18)
00520 . .
00521 
00522 The real value set by set_PWM_range is (dutycycle * real range) / range.
00523 D*/
00524 
00525 /*F*/
00526 int get_PWM_range(unsigned user_gpio);
00527 /*D
00528 Get the range of PWM values being used on the GPIO.
00529 
00530 . .
00531 user_gpio: 0-31.
00532 . .
00533 
00534 Returns the dutycycle range used for the GPIO if OK,
00535 otherwise PI_BAD_USER_GPIO.
00536 
00537 If a hardware clock or hardware PWM is active on the GPIO the
00538 reported range will be 1000000 (1M).
00539 D*/
00540 
00541 /*F*/
00542 int get_PWM_real_range(unsigned user_gpio);
00543 /*D
00544 Get the real underlying range of PWM values being used on the GPIO.
00545 
00546 . .
00547 user_gpio: 0-31.
00548 . .
00549 
00550 Returns the real range used for the GPIO if OK,
00551 otherwise PI_BAD_USER_GPIO.
00552 
00553 If a hardware clock is active on the GPIO the reported
00554 real range will be 1000000 (1M).
00555 
00556 If hardware PWM is active on the GPIO the reported real range
00557 will be approximately 250M divided by the set PWM frequency.
00558 
00559 D*/
00560 
00561 /*F*/
00562 int set_PWM_frequency(unsigned user_gpio, unsigned frequency);
00563 /*D
00564 Set the frequency (in Hz) of the PWM to be used on the GPIO.
00565 
00566 . .
00567 user_gpio: 0-31.
00568 frequency: >=0 (Hz).
00569 . .
00570 
00571 Returns the numerically closest frequency if OK, otherwise
00572 PI_BAD_USER_GPIO or PI_NOT_PERMITTED.
00573 
00574 If PWM is currently active on the GPIO it will be switched
00575 off and then back on at the new frequency.
00576 
00577 Each GPIO can be independently set to one of 18 different
00578 PWM frequencies.
00579 
00580 The selectable frequencies depend upon the sample rate which
00581 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5).  The
00582 sample rate is set when the pigpio daemon is started.
00583 
00584 The frequencies for each sample rate are:
00585 
00586 . .
00587                        Hertz
00588 
00589        1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
00590            1250  1000   800  500  400  250  200  100   50
00591 
00592        2: 20000 10000  5000 4000 2500 2000 1250 1000  800
00593             625   500   400  250  200  125  100   50   25
00594 
00595        4: 10000  5000  2500 2000 1250 1000  625  500  400
00596             313   250   200  125  100   63   50   25   13
00597 sample
00598  rate
00599  (us)  5:  8000  4000  2000 1600 1000  800  500  400  320
00600             250   200   160  100   80   50   40   20   10
00601 
00602        8:  5000  2500  1250 1000  625  500  313  250  200
00603             156   125   100   63   50   31   25   13    6
00604 
00605       10:  4000  2000  1000  800  500  400  250  200  160
00606             125   100    80   50   40   25   20   10    5
00607 . .
00608 D*/
00609 
00610 /*F*/
00611 int get_PWM_frequency(unsigned user_gpio);
00612 /*D
00613 Get the frequency of PWM being used on the GPIO.
00614 
00615 . .
00616 user_gpio: 0-31.
00617 . .
00618 
00619 For normal PWM the frequency will be that defined for the GPIO by
00620 [*set_PWM_frequency*].
00621 
00622 If a hardware clock is active on the GPIO the reported frequency
00623 will be that set by [*hardware_clock*].
00624 
00625 If hardware PWM is active on the GPIO the reported frequency
00626 will be that set by [*hardware_PWM*].
00627 
00628 Returns the frequency (in hertz) used for the GPIO if OK,
00629 otherwise PI_BAD_USER_GPIO.
00630 D*/
00631 
00632 /*F*/
00633 int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth);
00634 /*D
00635 Start (500-2500) or stop (0) servo pulses on the GPIO.
00636 
00637 . .
00638  user_gpio: 0-31.
00639 pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise).
00640 . .
00641 
00642 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or
00643 PI_NOT_PERMITTED.
00644 
00645 The selected pulsewidth will continue to be transmitted until
00646 changed by a subsequent call to set_servo_pulsewidth.
00647 
00648 The pulsewidths supported by servos varies and should probably be
00649 determined by experiment. A value of 1500 should always be safe and
00650 represents the mid-point of rotation.
00651 
00652 You can DAMAGE a servo if you command it to move beyond its limits.
00653 
00654 OTHER UPDATE RATES:
00655 
00656 This function updates servos at 50Hz.  If you wish to use a different
00657 update frequency you will have to use the PWM functions.
00658 
00659 . .
00660 Update Rate (Hz)     50   100  200  400  500
00661 1E6/Hz            20000 10000 5000 2500 2000
00662 . .
00663 
00664 Firstly set the desired PWM frequency using [*set_PWM_frequency*].
00665 
00666 Then set the PWM range using [*set_PWM_range*] to 1E6/Hz.
00667 Doing this allows you to use units of microseconds when setting
00668 the servo pulsewidth.
00669 
00670 E.g. If you want to update a servo connected to GPIO 25 at 400Hz
00671 
00672 . .
00673 set_PWM_frequency(25, 400);
00674 set_PWM_range(25, 2500);
00675 . .
00676 
00677 Thereafter use the [*set_PWM_dutycycle*] function to move the servo,
00678 e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. 
00679 D*/
00680 
00681 /*F*/
00682 int get_servo_pulsewidth(unsigned user_gpio);
00683 /*D
00684 Return the servo pulsewidth in use on a GPIO.
00685 
00686 . .
00687 user_gpio: 0-31.
00688 . .
00689 
00690 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
00691 D*/
00692 
00693 /*F*/
00694 int notify_open(void);
00695 /*D
00696 Get a free notification handle.
00697 
00698 Returns a handle greater than or equal to zero if OK,
00699 otherwise PI_NO_HANDLE.
00700 
00701 A notification is a method for being notified of GPIO state
00702 changes via a pipe.
00703 
00704 Pipes are only accessible from the local machine so this function
00705 serves no purpose if you are using the library from a remote machine.
00706 The in-built (socket) notifications provided by [*callback*]
00707 should be used instead.
00708 
00709 Notifications for handle x will be available at the pipe
00710 named /dev/pigpiox (where x is the handle number).
00711 E.g. if the function returns 15 then the notifications must be
00712 read from /dev/pigpio15.
00713 D*/
00714 
00715 /*F*/
00716 int notify_begin(unsigned handle, uint32_t bits);
00717 /*D
00718 Start notifications on a previously opened handle.
00719 
00720 . .
00721 handle: 0-31 (as returned by [*notify_open*])
00722   bits: a mask indicating the GPIO to be notified.
00723 . .
00724 
00725 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00726 
00727 The notification sends state changes for each GPIO whose
00728 corresponding bit in bits is set.
00729 
00730 Each notification occupies 12 bytes in the fifo as follows:
00731 
00732 . .
00733 typedef struct
00734 {
00735    uint16_t seqno;
00736    uint16_t flags;
00737    uint32_t tick;
00738    uint32_t level;
00739 } gpioReport_t;
00740 . .
00741 
00742 seqno: starts at 0 each time the handle is opened and then increments
00743 by one for each report.
00744 
00745 flags: two flags are defined, PI_NTFY_FLAGS_WDOG and PI_NTFY_FLAGS_ALIVE.
00746 
00747 PI_NTFY_FLAGS_WDOG, if bit 5 is set then bits 0-4 of the flags
00748 indicate a GPIO which has had a watchdog timeout.
00749 
00750 PI_NTFY_FLAGS_ALIVE, if bit 6 is set this indicates a keep alive
00751 signal on the pipe/socket and is sent once a minute in the absence
00752 of other notification activity.
00753 
00754 tick: the number of microseconds since system boot.  It wraps around
00755 after 1h12m.
00756 
00757 level: indicates the level of each GPIO.  If bit 1<<x is set then
00758 GPIO x is high.
00759 D*/
00760 
00761 /*F*/
00762 int notify_pause(unsigned handle);
00763 /*D
00764 Pause notifications on a previously opened handle.
00765 
00766 . .
00767 handle: 0-31 (as returned by [*notify_open*])
00768 . .
00769 
00770 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00771 
00772 Notifications for the handle are suspended until
00773 [*notify_begin*] is called again.
00774 D*/
00775 
00776 /*F*/
00777 int notify_close(unsigned handle);
00778 /*D
00779 Stop notifications on a previously opened handle and
00780 release the handle for reuse.
00781 
00782 . .
00783 handle: 0-31 (as returned by [*notify_open*])
00784 . .
00785 
00786 Returns 0 if OK, otherwise PI_BAD_HANDLE.
00787 D*/
00788 
00789 /*F*/
00790 int set_watchdog(unsigned user_gpio, unsigned timeout);
00791 /*D
00792 Sets a watchdog for a GPIO.
00793 
00794 . .
00795 user_gpio: 0-31.
00796   timeout: 0-60000.
00797 . .
00798 
00799 Returns 0 if OK, otherwise PI_BAD_USER_GPIO
00800 or PI_BAD_WDOG_TIMEOUT.
00801 
00802 The watchdog is nominally in milliseconds.
00803 
00804 Only one watchdog may be registered per GPIO.
00805 
00806 The watchdog may be cancelled by setting timeout to 0.
00807 
00808 Once a watchdog has been started callbacks for the GPIO will be
00809 triggered every timeout interval after the last GPIO activity.
00810 
00811 The callback will receive the special level PI_TIMEOUT.
00812 D*/
00813 
00814 /*F*/
00815 int set_glitch_filter(unsigned user_gpio, unsigned steady);
00816 /*D
00817 Sets a glitch filter on a GPIO.
00818 
00819 Level changes on the GPIO are not reported unless the level
00820 has been stable for at least [*steady*] microseconds.  The
00821 level is then reported.  Level changes of less than [*steady*]
00822 microseconds are ignored.
00823 
00824 . .
00825 user_gpio: 0-31
00826    steady: 0-300000
00827 . .
00828 
00829 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
00830 
00831 This filter affects the GPIO samples returned to callbacks set up
00832 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
00833 
00834 It does not affect levels read by [*gpio_read*],
00835 [*read_bank_1*], or [*read_bank_2*].
00836 Each (stable) edge will be timestamped [*steady*] microseconds
00837 after it was first detected.
00838 D*/
00839 
00840 /*F*/
00841 int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active);
00842 /*D
00843 Sets a noise filter on a GPIO.
00844 
00845 Level changes on the GPIO are ignored until a level which has
00846 been stable for [*steady*] microseconds is detected.  Level changes
00847 on the GPIO are then reported for [*active*] microseconds after
00848 which the process repeats.
00849 
00850 . .
00851 user_gpio: 0-31
00852    steady: 0-300000
00853    active: 0-1000000
00854 . .
00855 
00856 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
00857 
00858 This filter affects the GPIO samples returned to callbacks set up
00859 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
00860 
00861 It does not affect levels read by [*gpio_read*],
00862 [*read_bank_1*], or [*read_bank_2*].
00863 
00864 Level changes before and after the active period may
00865 be reported.  Your software must be designed to cope with
00866 such reports.
00867 D*/
00868 
00869 /*F*/
00870 uint32_t read_bank_1(void);
00871 /*D
00872 Read the levels of the bank 1 GPIO (GPIO 0-31).
00873 
00874 The returned 32 bit integer has a bit set if the corresponding
00875 GPIO is logic 1.  GPIO n has bit value (1<<n).
00876 D*/
00877 
00878 /*F*/
00879 uint32_t read_bank_2(void);
00880 /*D
00881 Read the levels of the bank 2 GPIO (GPIO 32-53).
00882 
00883 The returned 32 bit integer has a bit set if the corresponding
00884 GPIO is logic 1.  GPIO n has bit value (1<<(n-32)).
00885 D*/
00886 
00887 /*F*/
00888 int clear_bank_1(uint32_t bits);
00889 /*D
00890 Clears GPIO 0-31 if the corresponding bit in bits is set.
00891 
00892 . .
00893 bits: a bit mask with 1 set if the corresponding GPIO is
00894       to be cleared.
00895 . .
00896 
00897 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
00898 
00899 A status of PI_SOME_PERMITTED indicates that the user is not
00900 allowed to write to one or more of the GPIO.
00901 D*/
00902 
00903 /*F*/
00904 int clear_bank_2(uint32_t bits);
00905 /*D
00906 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
00907 
00908 . .
00909 bits: a bit mask with 1 set if the corresponding GPIO is
00910       to be cleared.
00911 . .
00912 
00913 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
00914 
00915 A status of PI_SOME_PERMITTED indicates that the user is not
00916 allowed to write to one or more of the GPIO.
00917 D*/
00918 
00919 /*F*/
00920 int set_bank_1(uint32_t bits);
00921 /*D
00922 Sets GPIO 0-31 if the corresponding bit in bits is set.
00923 
00924 . .
00925 bits: a bit mask with 1 set if the corresponding GPIO is
00926       to be set.
00927 . .
00928 
00929 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
00930 
00931 A status of PI_SOME_PERMITTED indicates that the user is not
00932 allowed to write to one or more of the GPIO.
00933 D*/
00934 
00935 /*F*/
00936 int set_bank_2(uint32_t bits);
00937 /*D
00938 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
00939 
00940 . .
00941 bits: a bit mask with 1 set if the corresponding GPIO is
00942       to be set.
00943 . .
00944 
00945 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
00946 
00947 A status of PI_SOME_PERMITTED indicates that the user is not
00948 allowed to write to one or more of the GPIO.
00949 D*/
00950 
00951 
00952 /*F*/
00953 int hardware_clock(unsigned gpio, unsigned clkfreq);
00954 /*D
00955 Starts a hardware clock on a GPIO at the specified frequency.
00956 Frequencies above 30MHz are unlikely to work.
00957 
00958 . .
00959      gpio: see description
00960 frequency: 0 (off) or 4689-250000000 (250M)
00961 . .
00962 
00963 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
00964 PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
00965 
00966 The same clock is available on multiple GPIO.  The latest
00967 frequency setting will be used by all GPIO which share a clock.
00968 
00969 The GPIO must be one of the following.
00970 
00971 . .
00972 4   clock 0  All models
00973 5   clock 1  All models but A and B (reserved for system use)
00974 6   clock 2  All models but A and B
00975 20  clock 0  All models but A and B
00976 21  clock 1  All models but A and Rev.2 B (reserved for system use)
00977 
00978 32  clock 0  Compute module only
00979 34  clock 0  Compute module only
00980 42  clock 1  Compute module only (reserved for system use)
00981 43  clock 2  Compute module only
00982 44  clock 1  Compute module only (reserved for system use)
00983 . .
00984 
00985 Access to clock 1 is protected by a password as its use will likely
00986 crash the Pi.  The password is given by or'ing 0x5A000000 with the
00987 GPIO number.
00988 D*/
00989 
00990 
00991 /*F*/
00992 int hardware_PWM(unsigned gpio, unsigned PWMfreq, uint32_t PWMduty);
00993 /*D
00994 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
00995 Frequencies above 30MHz are unlikely to work.
00996 
00997 NOTE: Any waveform started by [*wave_send_once*], [*wave_send_repeat*],
00998 or [*wave_chain*] will be cancelled.
00999 
01000 This function is only valid if the pigpio main clock is PCM.  The
01001 main clock defaults to PCM but may be overridden when the pigpio
01002 daemon is started (option -t).
01003 
01004 . .
01005    gpio: see descripton
01006 PWMfreq: 0 (off) or 1-125000000 (125M)
01007 PWMduty: 0 (off) to 1000000 (1M)(fully on)
01008 . .
01009 
01010 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
01011 PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ,
01012 or PI_HPWM_ILLEGAL.
01013 
01014 The same PWM channel is available on multiple GPIO.  The latest
01015 frequency and dutycycle setting will be used by all GPIO which
01016 share a PWM channel.
01017 
01018 The GPIO must be one of the following.
01019 
01020 . .
01021 12  PWM channel 0  All models but A and B
01022 13  PWM channel 1  All models but A and B
01023 18  PWM channel 0  All models
01024 19  PWM channel 1  All models but A and B
01025 
01026 40  PWM channel 0  Compute module only
01027 41  PWM channel 1  Compute module only
01028 45  PWM channel 1  Compute module only
01029 52  PWM channel 0  Compute module only
01030 53  PWM channel 1  Compute module only
01031 . .
01032 D*/
01033 
01034 
01035 /*F*/
01036 uint32_t get_current_tick(void);
01037 /*D
01038 Gets the current system tick.
01039 
01040 Tick is the number of microseconds since system boot.
01041 
01042 As tick is an unsigned 32 bit quantity it wraps around after
01043 2**32 microseconds, which is approximately 1 hour 12 minutes.
01044 
01045 D*/
01046 
01047 /*F*/
01048 uint32_t get_hardware_revision(void);
01049 /*D
01050 Get the Pi's hardware revision number.
01051 
01052 The hardware revision is the last few characters on the Revision line
01053 of /proc/cpuinfo.
01054 
01055 If the hardware revision can not be found or is not a valid
01056 hexadecimal number the function returns 0.
01057 
01058 The revision number can be used to determine the assignment of GPIO
01059 to pins (see [*gpio*]).
01060 
01061 There are at least three types of board.
01062 
01063 Type 1 boards have hardware revision numbers of 2 and 3.
01064 
01065 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
01066 
01067 Type 3 boards have hardware revision numbers of 16 or greater.
01068 D*/
01069 
01070 /*F*/
01071 uint32_t get_pigpio_version(void);
01072 /*D
01073 Returns the pigpio version.
01074 D*/
01075 
01076 
01077 /*F*/
01078 int wave_clear(void);
01079 /*D
01080 This function clears all waveforms and any data added by calls to the
01081 [*wave_add_**] functions.
01082 
01083 Returns 0 if OK.
01084 D*/
01085 
01086 /*F*/
01087 int wave_add_new(void);
01088 /*D
01089 This function starts a new empty waveform.  You wouldn't normally need
01090 to call this function as it is automatically called after a waveform is
01091 created with the [*wave_create*] function.
01092 
01093 Returns 0 if OK.
01094 D*/
01095 
01096 /*F*/
01097 int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses);
01098 /*D
01099 This function adds a number of pulses to the current waveform.
01100 
01101 . .
01102 numPulses: the number of pulses.
01103    pulses: an array of pulses.
01104 . .
01105 
01106 Returns the new total number of pulses in the current waveform if OK,
01107 otherwise PI_TOO_MANY_PULSES.
01108 
01109 The pulses are interleaved in time order within the existing waveform
01110 (if any).
01111 
01112 Merging allows the waveform to be built in parts, that is the settings
01113 for GPIO#1 can be added, and then GPIO#2 etc.
01114 
01115 If the added waveform is intended to start after or within the existing
01116 waveform then the first pulse should consist solely of a delay.
01117 D*/
01118 
01119 /*F*/
01120 int wave_add_serial
01121    (unsigned user_gpio, unsigned baud, unsigned data_bits,
01122     unsigned stop_bits, unsigned offset, unsigned numBytes, char *str);
01123 /*D
01124 This function adds a waveform representing serial data to the
01125 existing waveform (if any).  The serial data starts offset
01126 microseconds from the start of the waveform.
01127 
01128 . .
01129 user_gpio: 0-31.
01130      baud: 50-1000000
01131 data_bits: number of data bits (1-32)
01132 stop_bits: number of stop half bits (2-8)
01133    offset: >=0
01134  numBytes: >=1
01135       str: an array of chars.
01136 . .
01137 
01138 Returns the new total number of pulses in the current waveform if OK,
01139 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
01140 PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
01141 or PI_TOO_MANY_PULSES.
01142 
01143 NOTES:
01144 
01145 The serial data is formatted as one start bit, [*data_bits*] data bits,
01146 and [*stop_bits*]/2 stop bits.
01147 
01148 It is legal to add serial data streams with different baud rates to
01149 the same waveform.
01150 
01151 [*numBytes*] is the number of bytes of data in str.
01152 
01153 The bytes required for each character depend upon [*data_bits*].
01154 
01155 For [*data_bits*] 1-8 there will be one byte per character. 
01156 For [*data_bits*] 9-16 there will be two bytes per character. 
01157 For [*data_bits*] 17-32 there will be four bytes per character.
01158 D*/
01159 
01160 /*F*/
01161 int wave_create(void);
01162 /*D
01163 This function creates a waveform from the data provided by the prior
01164 calls to the [*wave_add_**] functions.  Upon success a wave id
01165 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
01166 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
01167 
01168 The data provided by the [*wave_add_**] functions is consumed by this
01169 function.
01170 
01171 As many waveforms may be created as there is space available.  The
01172 wave id is passed to [*wave_send_**] to specify the waveform to transmit.
01173 
01174 Normal usage would be
01175 
01176 Step 1. [*wave_clear*] to clear all waveforms and added data.
01177 
01178 Step 2. [*wave_add_**] calls to supply the waveform data.
01179 
01180 Step 3. [*wave_create*] to create the waveform and get a unique id
01181 
01182 Repeat steps 2 and 3 as needed.
01183 
01184 Step 4. [*wave_send_**] with the id of the waveform to transmit.
01185 
01186 A waveform comprises one or more pulses.  Each pulse consists of a
01187 [*gpioPulse_t*] structure.
01188 
01189 . .
01190 typedef struct
01191 {
01192    uint32_t gpioOn;
01193    uint32_t gpioOff;
01194    uint32_t usDelay;
01195 } gpioPulse_t;
01196 . .
01197 
01198 The fields specify
01199 
01200 1) the GPIO to be switched on at the start of the pulse. 
01201 2) the GPIO to be switched off at the start of the pulse. 
01202 3) the delay in microseconds before the next pulse. 
01203 
01204 Any or all the fields can be zero.  It doesn't make any sense to
01205 set all the fields to zero (the pulse will be ignored).
01206 
01207 When a waveform is started each pulse is executed in order with the
01208 specified delay between the pulse and the next.
01209 
01210 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
01211 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
01212 D*/
01213 
01214 
01215 /*F*/
01216 int wave_delete(unsigned wave_id);
01217 /*D
01218 This function deletes the waveform with id wave_id.
01219 
01220 . .
01221 wave_id: >=0, as returned by [*wave_create*].
01222 . .
01223 
01224 Wave ids are allocated in order, 0, 1, 2, etc.
01225 
01226 The wave is flagged for deletion.  The resources used by the wave
01227 will only be reused when either of the following apply.
01228 
01229 - all waves with higher numbered wave ids have been deleted or have
01230 been flagged for deletion.
01231 
01232 - a new wave is created which uses exactly the same resources as
01233 the current wave (see the C source for gpioWaveCreate for details).
01234 
01235 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
01236 D*/
01237 
01238 /*F*/
01239 int wave_send_once(unsigned wave_id);
01240 /*D
01241 This function transmits the waveform with id wave_id.  The waveform
01242 is sent once.
01243 
01244 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01245 
01246 . .
01247 wave_id: >=0, as returned by [*wave_create*].
01248 . .
01249 
01250 Returns the number of DMA control blocks in the waveform if OK,
01251 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
01252 D*/
01253 
01254 /*F*/
01255 int wave_send_repeat(unsigned wave_id);
01256 /*D
01257 This function transmits the waveform with id wave_id.  The waveform
01258 cycles until cancelled (either by the sending of a new waveform or
01259 by [*wave_tx_stop*]).
01260 
01261 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01262 
01263 . .
01264 wave_id: >=0, as returned by [*wave_create*].
01265 . .
01266 
01267 Returns the number of DMA control blocks in the waveform if OK,
01268 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
01269 D*/
01270 
01271 /*F*/
01272 int wave_chain(char *buf, unsigned bufSize);
01273 /*D
01274 This function transmits a chain of waveforms.
01275 
01276 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
01277 
01278 The waves to be transmitted are specified by the contents of buf
01279 which contains an ordered list of [*wave_id*]s and optional command
01280 codes and related data.
01281 
01282 . .
01283     buf: pointer to the wave_ids and optional command codes
01284 bufSize: the number of bytes in buf
01285 . .
01286 
01287 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
01288 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
01289 
01290 Each wave is transmitted in the order specified.  A wave may
01291 occur multiple times per chain.
01292 
01293 A blocks of waves may be transmitted multiple times by using
01294 the loop commands. The block is bracketed by loop start and
01295 end commands.  Loops may be nested.
01296 
01297 Delays between waves may be added with the delay command.
01298 
01299 The following command codes are supported:
01300 
01301 Name         @ Cmd & Data @ Meaning
01302 Loop Start   @ 255 0      @ Identify start of a wave block
01303 Loop Repeat  @ 255 1 x y  @ loop x + y*256 times
01304 Delay        @ 255 2 x y  @ delay x + y*256 microseconds
01305 Loop Forever @ 255 3      @ loop forever
01306 
01307 If present Loop Forever must be the last entry in the chain.
01308 
01309 The code is currently dimensioned to support a chain with roughly
01310 600 entries and 20 loop counters.
01311 
01312 ...
01313 #include <stdio.h>
01314 #include <pigpiod_if.h>
01315 
01316 #define WAVES 5
01317 #define GPIO 4
01318 
01319 int main(int argc, char *argv[])
01320 {
01321    int i, wid[WAVES];
01322 
01323    if (pigpio_start(0, 0)<0) return -1;
01324 
01325    set_mode(GPIO, PI_OUTPUT);
01326 
01327    for (i=0; i<WAVES; i++)
01328    {
01329       wave_add_generic(2, (gpioPulse_t[])
01330          {{1<<GPIO, 0,        20},
01331           {0, 1<<GPIO, (i+1)*200}});
01332 
01333       wid[i] = wave_create();
01334    }
01335 
01336    wave_chain((char []) {
01337       wid[4], wid[3], wid[2],       // transmit waves 4+3+2
01338       255, 0,                       // loop start
01339          wid[0], wid[0], wid[0],    // transmit waves 0+0+0
01340          255, 0,                    // loop start
01341             wid[0], wid[1],         // transmit waves 0+1
01342             255, 2, 0x88, 0x13,     // delay 5000us
01343          255, 1, 30, 0,             // loop end (repeat 30 times)
01344          255, 0,                    // loop start
01345             wid[2], wid[3], wid[0], // transmit waves 2+3+0
01346             wid[3], wid[1], wid[2], // transmit waves 3+1+2
01347          255, 1, 10, 0,             // loop end (repeat 10 times)
01348       255, 1, 5, 0,                 // loop end (repeat 5 times)
01349       wid[4], wid[4], wid[4],       // transmit waves 4+4+4
01350       255, 2, 0x20, 0x4E,           // delay 20000us
01351       wid[0], wid[0], wid[0],       // transmit waves 0+0+0
01352 
01353       }, 46);
01354 
01355    while (wave_tx_busy()) time_sleep(0.1);
01356 
01357    for (i=0; i<WAVES; i++) wave_delete(wid[i]);
01358 
01359    pigpio_stop();
01360 }
01361 ...
01362 D*/
01363 
01364 
01365 /*F*/
01366 int wave_tx_busy(void);
01367 /*D
01368 This function checks to see if a waveform is currently being
01369 transmitted.
01370 
01371 Returns 1 if a waveform is currently being transmitted, otherwise 0.
01372 D*/
01373 
01374 /*F*/
01375 int wave_tx_stop(void);
01376 /*D
01377 This function stops the transmission of the current waveform.
01378 
01379 Returns 0 if OK.
01380 
01381 This function is intended to stop a waveform started with the repeat mode.
01382 D*/
01383 
01384 /*F*/
01385 int wave_get_micros(void);
01386 /*D
01387 This function returns the length in microseconds of the current
01388 waveform.
01389 D*/
01390 
01391 /*F*/
01392 int wave_get_high_micros(void);
01393 /*D
01394 This function returns the length in microseconds of the longest waveform
01395 created since the pigpio daemon was started.
01396 D*/
01397 
01398 /*F*/
01399 int wave_get_max_micros(void);
01400 /*D
01401 This function returns the maximum possible size of a waveform in 
01402 microseconds.
01403 D*/
01404 
01405 /*F*/
01406 int wave_get_pulses(void);
01407 /*D
01408 This function returns the length in pulses of the current waveform.
01409 D*/
01410 
01411 /*F*/
01412 int wave_get_high_pulses(void);
01413 /*D
01414 This function returns the length in pulses of the longest waveform
01415 created since the pigpio daemon was started.
01416 D*/
01417 
01418 /*F*/
01419 int wave_get_max_pulses(void);
01420 /*D
01421 This function returns the maximum possible size of a waveform in pulses.
01422 D*/
01423 
01424 /*F*/
01425 int wave_get_cbs(void);
01426 /*D
01427 This function returns the length in DMA control blocks of the current
01428 waveform.
01429 D*/
01430 
01431 /*F*/
01432 int wave_get_high_cbs(void);
01433 /*D
01434 This function returns the length in DMA control blocks of the longest
01435 waveform created since the pigpio daemon was started.
01436 D*/
01437 
01438 /*F*/
01439 int wave_get_max_cbs(void);
01440 /*D
01441 This function returns the maximum possible size of a waveform in DMA
01442 control blocks.
01443 D*/
01444 
01445 /*F*/
01446 int gpio_trigger(unsigned user_gpio, unsigned pulseLen, unsigned level);
01447 /*D
01448 This function sends a trigger pulse to a GPIO.  The GPIO is set to
01449 level for pulseLen microseconds and then reset to not level.
01450 
01451 . .
01452 user_gpio: 0-31.
01453  pulseLen: 1-100.
01454     level: 0,1.
01455 . .
01456 
01457 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
01458 PI_BAD_PULSELEN, or PI_NOT_PERMITTED.
01459 D*/
01460 
01461 /*F*/
01462 int store_script(char *script);
01463 /*D
01464 This function stores a script for later execution.
01465 
01466 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
01467 
01468 . .
01469 script: the text of the script.
01470 . .
01471 
01472 The function returns a script id if the script is valid,
01473 otherwise PI_BAD_SCRIPT.
01474 D*/
01475 
01476 /*F*/
01477 int run_script(unsigned script_id, unsigned numPar, uint32_t *param);
01478 /*D
01479 This function runs a stored script.
01480 
01481 . .
01482 script_id: >=0, as returned by [*store_script*].
01483    numPar: 0-10, the number of parameters.
01484     param: an array of parameters.
01485 . .
01486 
01487 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
01488 PI_TOO_MANY_PARAM
01489 
01490 param is an array of up to 10 parameters which may be referenced in
01491 the script as p0 to p9.
01492 D*/
01493 
01494 /*F*/
01495 int script_status(unsigned script_id, uint32_t *param);
01496 /*D
01497 This function returns the run status of a stored script as well
01498 as the current values of parameters 0 to 9.
01499 
01500 . .
01501 script_id: >=0, as returned by [*store_script*].
01502     param: an array to hold the returned 10 parameters.
01503 . .
01504 
01505 The function returns greater than or equal to 0 if OK,
01506 otherwise PI_BAD_SCRIPT_ID.
01507 
01508 The run status may be
01509 
01510 . .
01511 PI_SCRIPT_INITING
01512 PI_SCRIPT_HALTED
01513 PI_SCRIPT_RUNNING
01514 PI_SCRIPT_WAITING
01515 PI_SCRIPT_FAILED
01516 . .
01517 
01518 The current value of script parameters 0 to 9 are returned in param.
01519 D*/
01520 
01521 /*F*/
01522 int stop_script(unsigned script_id);
01523 /*D
01524 This function stops a running script.
01525 
01526 . .
01527 script_id: >=0, as returned by [*store_script*].
01528 . .
01529 
01530 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
01531 D*/
01532 
01533 /*F*/
01534 int delete_script(unsigned script_id);
01535 /*D
01536 This function deletes a stored script.
01537 
01538 . .
01539 script_id: >=0, as returned by [*store_script*].
01540 . .
01541 
01542 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
01543 D*/
01544 
01545 /*F*/
01546 int bb_serial_read_open(unsigned user_gpio, unsigned baud, unsigned data_bits);
01547 /*D
01548 This function opens a GPIO for bit bang reading of serial data.
01549 
01550 . .
01551 user_gpio: 0-31.
01552      baud: 50-250000
01553 data_bits: 1-32
01554 . .
01555 
01556 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
01557 or PI_GPIO_IN_USE.
01558 
01559 The serial data is returned in a cyclic buffer and is read using
01560 bb_serial_read.
01561 
01562 It is the caller's responsibility to read data from the cyclic buffer
01563 in a timely fashion.
01564 D*/
01565 
01566 /*F*/
01567 int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize);
01568 /*D
01569 This function copies up to bufSize bytes of data read from the
01570 bit bang serial cyclic buffer to the buffer starting at buf.
01571 
01572 . .
01573 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01574       buf: an array to receive the read bytes.
01575   bufSize: >=0
01576 . .
01577 
01578 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
01579 or PI_NOT_SERIAL_GPIO.
01580 
01581 The bytes returned for each character depend upon the number of
01582 data bits [*data_bits*] specified in the [*bb_serial_read_open*] command.
01583 
01584 For [*data_bits*] 1-8 there will be one byte per character. 
01585 For [*data_bits*] 9-16 there will be two bytes per character. 
01586 For [*data_bits*] 17-32 there will be four bytes per character.
01587 D*/
01588 
01589 /*F*/
01590 int bb_serial_read_close(unsigned user_gpio);
01591 /*D
01592 This function closes a GPIO for bit bang reading of serial data.
01593 
01594 . .
01595 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01596 . .
01597 
01598 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
01599 D*/
01600 
01601 /*F*/
01602 int bb_serial_invert(unsigned user_gpio, unsigned invert);
01603 /*D
01604 This function inverts serial logic for big bang serial reads.
01605 
01606 . .
01607 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
01608    invert: 0-1, 1 invert, 0 normal.
01609 . .
01610 
01611 Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT.
01612 D*/
01613 
01614 /*F*/
01615 int i2c_open(unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags);
01616 /*D
01617 This returns a handle for the device at address i2c_addr on bus i2c_bus.
01618 
01619 . .
01620   i2c_bus: >=0.
01621  i2c_addr: 0-0x7F.
01622 i2c_flags: 0.
01623 . .
01624 
01625 No flags are currently defined.  This parameter should be set to zero.
01626 
01627 Physically buses 0 and 1 are available on the Pi.  Higher numbered buses
01628 will be available if a kernel supported bus multiplexor is being used.
01629 
01630 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
01631 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
01632 
01633 For the SMBus commands the low level transactions are shown at the end
01634 of the function description.  The following abbreviations are used.
01635 
01636 . .
01637 S     (1 bit) : Start bit
01638 P     (1 bit) : Stop bit
01639 Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
01640 A, NA (1 bit) : Accept and not accept bit. 
01641 Addr  (7 bits): I2C 7 bit address.
01642 Comm  (8 bits): Command byte, a data byte which often selects a register.
01643 Data  (8 bits): A data byte.
01644 Count (8 bits): A data byte containing the length of a block operation.
01645 
01646 [..]: Data sent by the device.
01647 . .
01648 D*/
01649 
01650 /*F*/
01651 int i2c_close(unsigned handle);
01652 /*D
01653 This closes the I2C device associated with the handle.
01654 
01655 . .
01656 handle: >=0, as returned by a call to [*i2c_open*].
01657 . .
01658 
01659 Returns 0 if OK, otherwise PI_BAD_HANDLE.
01660 D*/
01661 
01662 /*F*/
01663 int i2c_write_quick(unsigned handle, unsigned bit);
01664 /*D
01665 This sends a single bit (in the Rd/Wr bit) to the device associated
01666 with handle.
01667 
01668 . .
01669 handle: >=0, as returned by a call to [*i2c_open*].
01670    bit: 0-1, the value to write.
01671 . .
01672 
01673 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01674 PI_I2C_WRITE_FAILED.
01675 
01676 Quick command. SMBus 2.0 5.5.1
01677 . .
01678 S Addr Rd/Wr [A] P
01679 . .
01680 D*/
01681 
01682 /*F*/
01683 int i2c_write_byte(unsigned handle, unsigned bVal);
01684 /*D
01685 This sends a single byte to the device associated with handle.
01686 
01687 . .
01688 handle: >=0, as returned by a call to [*i2c_open*].
01689   bVal: 0-0xFF, the value to write.
01690 . .
01691 
01692 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01693 PI_I2C_WRITE_FAILED.
01694 
01695 Send byte. SMBus 2.0 5.5.2
01696 . .
01697 S Addr Wr [A] Data [A] P
01698 . .
01699 D*/
01700 
01701 /*F*/
01702 int i2c_read_byte(unsigned handle);
01703 /*D
01704 This reads a single byte from the device associated with handle.
01705 
01706 . .
01707 handle: >=0, as returned by a call to [*i2c_open*].
01708 . .
01709 
01710 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
01711 or PI_I2C_READ_FAILED.
01712 
01713 Receive byte. SMBus 2.0 5.5.3
01714 . .
01715 S Addr Rd [A] [Data] NA P
01716 . .
01717 D*/
01718 
01719 /*F*/
01720 int i2c_write_byte_data(unsigned handle, unsigned i2c_reg, unsigned bVal);
01721 /*D
01722 This writes a single byte to the specified register of the device
01723 associated with handle.
01724 
01725 . .
01726  handle: >=0, as returned by a call to [*i2c_open*].
01727 i2c_reg: 0-255, the register to write.
01728    bVal: 0-0xFF, the value to write.
01729 . .
01730 
01731 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01732 PI_I2C_WRITE_FAILED.
01733 
01734 Write byte. SMBus 2.0 5.5.4
01735 . .
01736 S Addr Wr [A] Comm [A] Data [A] P
01737 . .
01738 D*/
01739 
01740 /*F*/
01741 int i2c_write_word_data(unsigned handle, unsigned i2c_reg, unsigned wVal);
01742 /*D
01743 This writes a single 16 bit word to the specified register of the device
01744 associated with handle.
01745 
01746 . .
01747  handle: >=0, as returned by a call to [*i2c_open*].
01748 i2c_reg: 0-255, the register to write.
01749    wVal: 0-0xFFFF, the value to write.
01750 . .
01751 
01752 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01753 PI_I2C_WRITE_FAILED.
01754 
01755 Write word. SMBus 2.0 5.5.4
01756 . .
01757 S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] P
01758 . .
01759 D*/
01760 
01761 /*F*/
01762 int i2c_read_byte_data(unsigned handle, unsigned i2c_reg);
01763 /*D
01764 This reads a single byte from the specified register of the device
01765 associated with handle.
01766 
01767 . .
01768  handle: >=0, as returned by a call to [*i2c_open*].
01769 i2c_reg: 0-255, the register to read.
01770 . .
01771 
01772 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
01773 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01774 
01775 Read byte. SMBus 2.0 5.5.5
01776 . .
01777 S Addr Wr [A] Comm [A] S Addr Rd [A] [Data] NA P
01778 . .
01779 D*/
01780 
01781 /*F*/
01782 int i2c_read_word_data(unsigned handle, unsigned i2c_reg);
01783 /*D
01784 This reads a single 16 bit word from the specified register of the device
01785 associated with handle.
01786 
01787 . .
01788  handle: >=0, as returned by a call to [*i2c_open*].
01789 i2c_reg: 0-255, the register to read.
01790 . .
01791 
01792 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
01793 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01794 
01795 Read word. SMBus 2.0 5.5.5
01796 . .
01797 S Addr Wr [A] Comm [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P
01798 . .
01799 D*/
01800 
01801 /*F*/
01802 int i2c_process_call(unsigned handle, unsigned i2c_reg, unsigned wVal);
01803 /*D
01804 This writes 16 bits of data to the specified register of the device
01805 associated with handle and and reads 16 bits of data in return.
01806 
01807 . .
01808  handle: >=0, as returned by a call to [*i2c_open*].
01809 i2c_reg: 0-255, the register to write/read.
01810    wVal: 0-0xFFFF, the value to write.
01811 . .
01812 
01813 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
01814 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01815 
01816 Process call. SMBus 2.0 5.5.6
01817 . .
01818 S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A]
01819    S Addr Rd [A] [DataLow] A [DataHigh] NA P
01820 . .
01821 D*/
01822 
01823 /*F*/
01824 int i2c_write_block_data(
01825 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
01826 /*D
01827 This writes up to 32 bytes to the specified register of the device
01828 associated with handle.
01829 
01830 . .
01831  handle: >=0, as returned by a call to [*i2c_open*].
01832 i2c_reg: 0-255, the register to write.
01833     buf: an array with the data to send.
01834   count: 1-32, the number of bytes to write.
01835 . .
01836 
01837 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01838 PI_I2C_WRITE_FAILED.
01839 
01840 Block write. SMBus 2.0 5.5.7
01841 . .
01842 S Addr Wr [A] Comm [A] Count [A] Data [A] Data [A] ... [A] Data [A] P
01843 . .
01844 D*/
01845 
01846 /*F*/
01847 int i2c_read_block_data(unsigned handle, unsigned i2c_reg, char *buf);
01848 /*D
01849 This reads a block of up to 32 bytes from the specified register of
01850 the device associated with handle.
01851 
01852 . .
01853  handle: >=0, as returned by a call to [*i2c_open*].
01854 i2c_reg: 0-255, the register to read.
01855     buf: an array to receive the read data.
01856 . .
01857 
01858 The amount of returned data is set by the device.
01859 
01860 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
01861 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01862 
01863 Block read. SMBus 2.0 5.5.7
01864 . .
01865 S Addr Wr [A] Comm [A]
01866    S Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P
01867 . .
01868 D*/
01869 
01870 /*F*/
01871 int i2c_block_process_call(
01872 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
01873 /*D
01874 This writes data bytes to the specified register of the device
01875 associated with handle and reads a device specified number
01876 of bytes of data in return.
01877 
01878 . .
01879  handle: >=0, as returned by a call to [*i2c_open*].
01880 i2c_reg: 0-255, the register to write/read.
01881     buf: an array with the data to send and to receive the read data.
01882   count: 1-32, the number of bytes to write.
01883 . .
01884 
01885 
01886 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
01887 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01888 
01889 The smbus 2.0 documentation states that a minimum of 1 byte may be
01890 sent and a minimum of 1 byte may be received.  The total number of
01891 bytes sent/received must be 32 or less.
01892 
01893 Block write-block read. SMBus 2.0 5.5.8
01894 . .
01895 S Addr Wr [A] Comm [A] Count [A] Data [A] ...
01896    S Addr Rd [A] [Count] A [Data] ... A P
01897 . .
01898 D*/
01899 
01900 /*F*/
01901 int i2c_read_i2c_block_data(
01902 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
01903 /*D
01904 This reads count bytes from the specified register of the device
01905 associated with handle .  The count may be 1-32.
01906 
01907 . .
01908  handle: >=0, as returned by a call to [*i2c_open*].
01909 i2c_reg: 0-255, the register to read.
01910     buf: an array to receive the read data.
01911   count: 1-32, the number of bytes to read.
01912 . .
01913 
01914 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
01915 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
01916 
01917 . .
01918 S Addr Wr [A] Comm [A]
01919    S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P
01920 . .
01921 D*/
01922 
01923 
01924 /*F*/
01925 int i2c_write_i2c_block_data(
01926 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
01927 /*D
01928 This writes 1 to 32 bytes to the specified register of the device
01929 associated with handle.
01930 
01931 . .
01932  handle: >=0, as returned by a call to [*i2c_open*].
01933 i2c_reg: 0-255, the register to write.
01934     buf: the data to write.
01935   count: 1-32, the number of bytes to write.
01936 . .
01937 
01938 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01939 PI_I2C_WRITE_FAILED.
01940 
01941 . .
01942 S Addr Wr [A] Comm [A] Data [A] Data [A] ... [A] Data [A] P
01943 . .
01944 D*/
01945 
01946 /*F*/
01947 int i2c_read_device(unsigned handle, char *buf, unsigned count);
01948 /*D
01949 This reads count bytes from the raw device into buf.
01950 
01951 . .
01952 handle: >=0, as returned by a call to [*i2c_open*].
01953    buf: an array to receive the read data bytes.
01954  count: >0, the number of bytes to read.
01955 . .
01956 
01957 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01958 PI_I2C_READ_FAILED.
01959 D*/
01960 
01961 /*F*/
01962 int i2c_write_device(unsigned handle, char *buf, unsigned count);
01963 /*D
01964 This writes count bytes from buf to the raw device.
01965 
01966 . .
01967 handle: >=0, as returned by a call to [*i2c_open*].
01968    buf: an array containing the data bytes to write.
01969  count: >0, the number of bytes to write.
01970 . .
01971 
01972 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
01973 PI_I2C_WRITE_FAILED.
01974 D*/
01975 
01976 /*F*/
01977 int i2c_zip(
01978    unsigned handle,
01979    char    *inBuf,
01980    unsigned inLen,
01981    char    *outBuf,
01982    unsigned outLen);
01983 /*D
01984 This function executes a sequence of I2C operations.  The
01985 operations to be performed are specified by the contents of inBuf
01986 which contains the concatenated command codes and associated data.
01987 
01988 . .
01989 handle: >=0, as returned by a call to [*i2cOpen*]
01990  inBuf: pointer to the concatenated I2C commands, see below
01991  inLen: size of command buffer
01992 outBuf: pointer to buffer to hold returned data
01993 outLen: size of output buffer
01994 . .
01995 
01996 Returns >= 0 if OK (the number of bytes read), otherwise
01997 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
01998 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
01999 
02000 The following command codes are supported:
02001 
02002 Name    @ Cmd & Data @ Meaning
02003 End     @ 0          @ No more commands
02004 Escape  @ 1          @ Next P is two bytes
02005 On      @ 2          @ Switch combined flag on
02006 Off     @ 3          @ Switch combined flag off
02007 Address @ 4 P        @ Set I2C address to P
02008 Flags   @ 5 lsb msb  @ Set I2C flags to lsb + (msb << 8)
02009 Read    @ 6 P        @ Read P bytes of data
02010 Write   @ 7 P ...    @ Write P bytes of data
02011 
02012 The address, read, and write commands take a parameter P.
02013 Normally P is one byte (0-255).  If the command is preceded by
02014 the Escape command then P is two bytes (0-65535, least significant
02015 byte first).
02016 
02017 The address defaults to that associated with the handle.
02018 The flags default to 0.  The address and flags maintain their
02019 previous value until updated.
02020 
02021 The returned I2C data is stored in consecutive locations of outBuf.
02022 
02023 ...
02024 Set address 0x53, write 0x32, read 6 bytes
02025 Set address 0x1E, write 0x03, read 6 bytes
02026 Set address 0x68, write 0x1B, read 8 bytes
02027 End
02028 
02029 0x04 0x53   0x07 0x01 0x32   0x06 0x06
02030 0x04 0x1E   0x07 0x01 0x03   0x06 0x06
02031 0x04 0x68   0x07 0x01 0x1B   0x06 0x08
02032 0x00
02033 ...
02034 
02035 D*/
02036 
02037 /*F*/
02038 int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud);
02039 /*D
02040 This function selects a pair of GPIO for bit banging I2C at a
02041 specified baud rate.
02042 
02043 Bit banging I2C allows for certain operations which are not possible
02044 with the standard I2C driver.
02045 
02046 o baud rates as low as 50 
02047 o repeated starts 
02048 o clock stretching 
02049 o I2C on any pair of spare GPIO
02050 
02051 . .
02052  SDA: 0-31
02053  SCL: 0-31
02054 baud: 50-500000
02055 . .
02056 
02057 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
02058 PI_GPIO_IN_USE.
02059 
02060 NOTE:
02061 
02062 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected.  As
02063 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
02064 D*/
02065 
02066 /*F*/
02067 int bb_i2c_close(unsigned SDA);
02068 /*D
02069 This function stops bit banging I2C on a pair of GPIO previously
02070 opened with [*bb_i2c_open*].
02071 
02072 . .
02073 SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*]
02074 . .
02075 
02076 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
02077 D*/
02078 
02079 /*F*/
02080 int bb_i2c_zip(
02081    unsigned SDA,
02082    char    *inBuf,
02083    unsigned inLen,
02084    char    *outBuf,
02085    unsigned outLen);
02086 /*D
02087 This function executes a sequence of bit banged I2C operations.  The
02088 operations to be performed are specified by the contents of inBuf
02089 which contains the concatenated command codes and associated data.
02090 
02091 . .
02092    SDA: 0-31 (as used in a prior call to [*bb_i2c_open*])
02093  inBuf: pointer to the concatenated I2C commands, see below
02094  inLen: size of command buffer
02095 outBuf: pointer to buffer to hold returned data
02096 outLen: size of output buffer
02097 . .
02098 
02099 Returns >= 0 if OK (the number of bytes read), otherwise
02100 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
02101 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
02102 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
02103 
02104 The following command codes are supported:
02105 
02106 Name    @ Cmd & Data   @ Meaning
02107 End     @ 0            @ No more commands
02108 Escape  @ 1            @ Next P is two bytes
02109 Start   @ 2            @ Start condition
02110 Stop    @ 3            @ Stop condition
02111 Address @ 4 P          @ Set I2C address to P
02112 Flags   @ 5 lsb msb    @ Set I2C flags to lsb + (msb << 8)
02113 Read    @ 6 P          @ Read P bytes of data
02114 Write   @ 7 P ...      @ Write P bytes of data
02115 
02116 The address, read, and write commands take a parameter P.
02117 Normally P is one byte (0-255).  If the command is preceded by
02118 the Escape command then P is two bytes (0-65535, least significant
02119 byte first).
02120 
02121 The address and flags default to 0.  The address and flags maintain
02122 their previous value until updated.
02123 
02124 No flags are currently defined.
02125 
02126 The returned I2C data is stored in consecutive locations of outBuf.
02127 
02128 ...
02129 Set address 0x53
02130 start, write 0x32, (re)start, read 6 bytes, stop
02131 Set address 0x1E
02132 start, write 0x03, (re)start, read 6 bytes, stop
02133 Set address 0x68
02134 start, write 0x1B, (re)start, read 8 bytes, stop
02135 End
02136 
02137 0x04 0x53
02138 0x02 0x07 0x01 0x32   0x02 0x06 0x06 0x03
02139 
02140 0x04 0x1E
02141 0x02 0x07 0x01 0x03   0x02 0x06 0x06 0x03
02142 
02143 0x04 0x68
02144 0x02 0x07 0x01 0x1B   0x02 0x06 0x08 0x03
02145 
02146 0x00
02147 ...
02148 D*/
02149 
02150 /*F*/
02151 int spi_open(unsigned spi_channel, unsigned baud, unsigned spi_flags);
02152 /*D
02153 This function returns a handle for the SPI device on channel.
02154 Data will be transferred at baud bits per second.  The flags may
02155 be used to modify the default behaviour of 4-wire operation, mode 0,
02156 active low chip select.
02157 
02158 An auxiliary SPI device is available on all models but the
02159 A and B and may be selected by setting the A bit in the
02160 flags.  The auxiliary device has 3 chip selects and a
02161 selectable word size in bits.
02162 
02163 . .
02164 spi_channel: 0-1 (0-2 for the auxiliary SPI device).
02165        baud: 32K-125M (values above 30M are unlikely to work).
02166   spi_flags: see below.
02167 . .
02168 
02169 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
02170 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
02171 
02172 spi_flags consists of the least significant 22 bits.
02173 
02174 . .
02175 21 20 19 18 17 16 15 14 13 12 11 10  9  8  7  6  5  4  3  2  1  0
02176  b  b  b  b  b  b  R  T  n  n  n  n  W  A u2 u1 u0 p2 p1 p0  m  m
02177 . .
02178 
02179 mm defines the SPI mode.
02180 
02181 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
02182 
02183 . .
02184 Mode POL PHA
02185  0    0   0
02186  1    0   1
02187  2    1   0
02188  3    1   1
02189 . .
02190 
02191 px is 0 if CEx is active low (default) and 1 for active high.
02192 
02193 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
02194 
02195 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
02196 
02197 W is 0 if the device is not 3-wire, 1 if the device is 3-wire.  Standard
02198 SPI device only.
02199 
02200 nnnn defines the number of bytes (0-15) to write before switching
02201 the MOSI line to MISO to read data.  This field is ignored
02202 if W is not set.  Standard SPI device only.
02203 
02204 T is 1 if the least significant bit is transmitted on MOSI first, the
02205 default (0) shifts the most significant bit out first.  Auxiliary SPI
02206 device only.
02207 
02208 R is 1 if the least significant bit is received on MISO first, the
02209 default (0) receives the most significant bit first.  Auxiliary SPI
02210 device only.
02211 
02212 bbbbbb defines the word size in bits (0-32).  The default (0)
02213 sets 8 bits per word.  Auxiliary SPI device only.
02214 
02215 The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions
02216 transfer data packed into 1, 2, or 4 bytes according to
02217 the word size in bits.
02218 
02219 For bits 1-8 there will be one byte per word. 
02220 For bits 9-16 there will be two bytes per word. 
02221 For bits 17-32 there will be four bytes per word.
02222 
02223 Multi-byte transfers are made in least significant byte first order.
02224 
02225 E.g. to transfer 32 11-bit words buf should contain 64 bytes
02226 and count should be 64.
02227 
02228 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
02229 by 0x1A.
02230 
02231 The other bits in flags should be set to zero.
02232 D*/
02233 
02234 /*F*/
02235 int spi_close(unsigned handle);
02236 /*D
02237 This functions closes the SPI device identified by the handle.
02238 
02239 . .
02240 handle: >=0, as returned by a call to [*spi_open*].
02241 . .
02242 
02243 Returns 0 if OK, otherwise PI_BAD_HANDLE.
02244 D*/
02245 
02246 /*F*/
02247 int spi_read(unsigned handle, char *buf, unsigned count);
02248 /*D
02249 This function reads count bytes of data from the SPI
02250 device associated with the handle.
02251 
02252 . .
02253 handle: >=0, as returned by a call to [*spi_open*].
02254    buf: an array to receive the read data bytes.
02255  count: the number of bytes to read.
02256 . .
02257 
02258 Returns the number of bytes transferred if OK, otherwise
02259 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02260 D*/
02261 
02262 /*F*/
02263 int spi_write(unsigned handle, char *buf, unsigned count);
02264 /*D
02265 This function writes count bytes of data from buf to the SPI
02266 device associated with the handle.
02267 
02268 . .
02269 handle: >=0, as returned by a call to [*spi_open*].
02270    buf: the data bytes to write.
02271  count: the number of bytes to write.
02272 . .
02273 
02274 Returns the number of bytes transferred if OK, otherwise
02275 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02276 D*/
02277 
02278 /*F*/
02279 int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count);
02280 /*D
02281 This function transfers count bytes of data from txBuf to the SPI
02282 device associated with the handle.  Simultaneously count bytes of
02283 data are read from the device and placed in rxBuf.
02284 
02285 . .
02286 handle: >=0, as returned by a call to [*spi_open*].
02287  txBuf: the data bytes to write.
02288  rxBuf: the received data bytes.
02289  count: the number of bytes to transfer.
02290 . .
02291 
02292 Returns the number of bytes transferred if OK, otherwise
02293 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
02294 D*/
02295 
02296 /*F*/
02297 int serial_open(char *ser_tty, unsigned baud, unsigned ser_flags);
02298 /*D
02299 This function opens a serial device at a specified baud rate
02300 with specified flags.  The device name must start with
02301 /dev/tty or /dev/serial.
02302 
02303 . .
02304   ser_tty: the serial device to open.
02305      baud: the baud rate in bits per second, see below.
02306 ser_flags: 0.
02307 . .
02308 
02309 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
02310 PI_SER_OPEN_FAILED.
02311 
02312 The baud rate must be one of 50, 75, 110, 134, 150,
02313 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
02314 38400, 57600, 115200, or 230400.
02315 
02316 No flags are currently defined.  This parameter should be set to zero.
02317 D*/
02318 
02319 /*F*/
02320 int serial_close(unsigned handle);
02321 /*D
02322 This function closes the serial device associated with handle.
02323 
02324 . .
02325 handle: >=0, as returned by a call to [*serial_open*].
02326 . .
02327 
02328 Returns 0 if OK, otherwise PI_BAD_HANDLE.
02329 D*/
02330 
02331 /*F*/
02332 int serial_write_byte(unsigned handle, unsigned bVal);
02333 /*D
02334 This function writes bVal to the serial port associated with handle.
02335 
02336 . .
02337 handle: >=0, as returned by a call to [*serial_open*].
02338 . .
02339 
02340 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02341 PI_SER_WRITE_FAILED.
02342 D*/
02343 
02344 /*F*/
02345 int serial_read_byte(unsigned handle);
02346 /*D
02347 This function reads a byte from the serial port associated with handle.
02348 
02349 . .
02350 handle: >=0, as returned by a call to [*serial_open*].
02351 . .
02352 
02353 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
02354 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
02355 
02356 If no data is ready PI_SER_READ_NO_DATA is returned.
02357 D*/
02358 
02359 /*F*/
02360 int serial_write(unsigned handle, char *buf, unsigned count);
02361 /*D
02362 This function writes count bytes from buf to the the serial port
02363 associated with handle.
02364 
02365 . .
02366 handle: >=0, as returned by a call to [*serial_open*].
02367    buf: the array of bytes to write.
02368  count: the number of bytes to write.
02369 . .
02370 
02371 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
02372 PI_SER_WRITE_FAILED.
02373 D*/
02374 
02375 /*F*/
02376 int serial_read(unsigned handle, char *buf, unsigned count);
02377 /*D
02378 This function reads up to count bytes from the the serial port
02379 associated with handle and writes them to buf.
02380 
02381 . .
02382 handle: >=0, as returned by a call to [*serial_open*].
02383    buf: an array to receive the read data.
02384  count: the maximum number of bytes to read.
02385 . .
02386 
02387 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
02388 PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED.
02389 
02390 If no data is ready zero is returned.
02391 D*/
02392 
02393 /*F*/
02394 int serial_data_available(unsigned handle);
02395 /*D
02396 Returns the number of bytes available to be read from the
02397 device associated with handle.
02398 
02399 . .
02400 handle: >=0, as returned by a call to [*serial_open*].
02401 . .
02402 
02403 Returns the number of bytes of data available (>=0) if OK,
02404 otherwise PI_BAD_HANDLE.
02405 D*/
02406 
02407 /*F*/
02408 int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned argc);
02409 /*D
02410 This function is available for user customisation.
02411 
02412 It returns a single integer value.
02413 
02414 . .
02415 arg1: >=0
02416 arg2: >=0
02417 argx: extra (byte) arguments
02418 argc: number of extra arguments
02419 . .
02420 
02421 Returns >= 0 if OK, less than 0 indicates a user defined error.
02422 D*/
02423 
02424 
02425 /*F*/
02426 int custom_2(unsigned arg1, char *argx, unsigned argc,
02427              char *retBuf, unsigned retMax);
02428 /*D
02429 This function is available for user customisation.
02430 
02431 It differs from custom_1 in that it returns an array of bytes
02432 rather than just an integer.
02433 
02434 The return value is an integer indicating the number of returned bytes.
02435 . .
02436   arg1: >=0
02437   argc: extra (byte) arguments
02438  count: number of extra arguments
02439 retBuf: buffer for returned data
02440 retMax: maximum number of bytes to return
02441 . .
02442 
02443 Returns >= 0 if OK, less than 0 indicates a user defined error.
02444 
02445 Note, the number of returned bytes will be retMax or less.
02446 D*/
02447 
02448 
02449 /*F*/
02450 int callback(unsigned user_gpio, unsigned edge, CBFunc_t f);
02451 /*D
02452 This function initialises a new callback.
02453 
02454 . .
02455 user_gpio: 0-31.
02456      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
02457         f: the callback function.
02458 . .
02459 
02460 The function returns a callback id if OK, otherwise pigif_bad_malloc,
02461 pigif_duplicate_callback, or pigif_bad_callback.
02462 
02463 The callback is called with the GPIO, edge, and tick, whenever the
02464 GPIO has the identified edge.
02465 
02466 . .
02467 Parameter   Value    Meaning
02468 
02469 GPIO        0-31     The GPIO which has changed state
02470 
02471 edge        0-2      0 = change to low (a falling edge)
02472                      1 = change to high (a rising edge)
02473                      2 = no level change (a watchdog timeout)
02474 
02475 tick        32 bit   The number of microseconds since boot
02476                      WARNING: this wraps around from
02477                      4294967295 to 0 roughly every 72 minutes
02478 . .
02479 D*/
02480 
02481 /*F*/
02482 int callback_ex
02483    (unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata);
02484 /*D
02485 This function initialises a new callback.
02486 
02487 . .
02488 user_gpio: 0-31.
02489      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
02490         f: the callback function.
02491  userdata: a pointer to arbitrary user data.
02492 . .
02493 
02494 The function returns a callback id if OK, otherwise pigif_bad_malloc,
02495 pigif_duplicate_callback, or pigif_bad_callback.
02496 
02497 The callback is called with the GPIO, edge, tick, and user, whenever
02498 the GPIO has the identified edge.
02499 
02500 . .
02501 Parameter   Value    Meaning
02502 
02503 GPIO        0-31     The GPIO which has changed state
02504 
02505 edge        0-2      0 = change to low (a falling edge)
02506                      1 = change to high (a rising edge)
02507                      2 = no level change (a watchdog timeout)
02508 
02509 tick        32 bit   The number of microseconds since boot
02510                      WARNING: this wraps around from
02511                      4294967295 to 0 roughly every 72 minutes
02512 
02513 userdata    pointer  Pointer to an arbitrary object
02514 . .
02515 D*/
02516 
02517 /*F*/
02518 int callback_cancel(unsigned callback_id);
02519 /*D
02520 This function cancels a callback identified by its id.
02521 
02522 . .
02523 callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*].
02524 . .
02525 
02526 The function returns 0 if OK, otherwise pigif_callback_not_found.
02527 D*/
02528 
02529 /*F*/
02530 int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout);
02531 /*D
02532 This function waits for edge on the GPIO for up to timeout
02533 seconds.
02534 
02535 . .
02536 user_gpio: 0-31.
02537      edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
02538   timeout: >=0.
02539 . .
02540 
02541 The function returns 1 if the edge occurred, otherwise 0.
02542 
02543 The function returns when the edge occurs or after the timeout.
02544 D*/
02545 
02546 /*PARAMS
02547 
02548 active :: 0-1000000
02549 
02550 The number of microseconds level changes are reported for once
02551 a noise filter has been triggered (by [*steady*] microseconds of
02552 a stable level).
02553 
02554 *addrStr::
02555 A string specifying the host or IP address of the Pi running
02556 the pigpio daemon.  It may be NULL in which case localhost
02557 is used unless overridden by the PIGPIO_ADDR environment
02558 variable.
02559 
02560 arg1::
02561 An unsigned argument passed to a user customised function.  Its
02562 meaning is defined by the customiser.
02563 
02564 arg2::
02565 An unsigned argument passed to a user customised function.  Its
02566 meaning is defined by the customiser.
02567 
02568 argc::
02569 The count of bytes passed to a user customised function.
02570 
02571 *argx::
02572 A pointer to an array of bytes passed to a user customised function.
02573 Its meaning and content is defined by the customiser.
02574 
02575 baud::
02576 The speed of serial communication (I2C, SPI, serial link, waves) in
02577 bits per second.
02578 
02579 bit::
02580 A value of 0 or 1.
02581 
02582 bits::
02583 A value used to select GPIO.  If bit n of bits is set then GPIO n is
02584 selected.
02585 
02586 A convenient way to set bit n is to or in (1<<n).
02587 
02588 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
02589 
02590 *buf::
02591 A buffer to hold data being sent or being received.
02592 
02593 bufSize::
02594 The size in bytes of a buffer.
02595 
02596 
02597 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
02598 An 8-bit byte value.
02599 
02600 callback_id::
02601 A >=0, as returned by a call to [*callback*] or [*callback_ex*].  This is
02602 passed to [*callback_cancel*] to cancel the callback.
02603 
02604 CBFunc_t::
02605 . .
02606 typedef void (*CBFunc_t)
02607    (unsigned user_gpio, unsigned level, uint32_t tick);
02608 . .
02609 
02610 CBFuncEx_t::
02611 . .
02612 typedef void (*CBFuncEx_t)
02613    (unsigned user_gpio, unsigned level, uint32_t tick, void * user);
02614 . .
02615 
02616 char::
02617 A single character, an 8 bit quantity able to store 0-255.
02618 
02619 clkfreq::4689-250000000 (250M)
02620 The hardware clock frequency.
02621 
02622 count::
02623 The number of bytes to be transferred in an I2C, SPI, or Serial
02624 command.
02625 
02626 data_bits::1-32
02627 The number of data bits in each character of serial data.
02628 
02629 . .
02630 #define PI_MIN_WAVE_DATABITS 1
02631 #define PI_MAX_WAVE_DATABITS 32
02632 . .
02633 
02634 double::
02635 A floating point number.
02636 
02637 dutycycle::0-range
02638 A number representing the ratio of on time to off time for PWM.
02639 
02640 The number may vary between 0 and range (default 255) where
02641 0 is off and range is fully on.
02642 
02643 edge::
02644 Used to identify a GPIO level transition of interest.  A rising edge is
02645 a level change from 0 to 1.  A falling edge is a level change from 1 to 0.
02646 
02647 . .
02648 RISING_EDGE  0
02649 FALLING_EDGE 1
02650 EITHER_EDGE. 2
02651 . .
02652 
02653 errnum::
02654 A negative number indicating a function call failed and the nature
02655 of the error.
02656 
02657 f::
02658 A function.
02659 
02660 frequency::>=0
02661 The number of times a GPIO is swiched on and off per second.  This
02662 can be set per GPIO and may be as little as 5Hz or as much as
02663 40KHz.  The GPIO will be on for a proportion of the time as defined
02664 by its dutycycle.
02665 
02666 
02667 gpio::
02668 A Broadcom numbered GPIO, in the range 0-53.
02669 
02670 There  are 54 General Purpose Input Outputs (GPIO) named gpio0 through
02671 gpio53.
02672 
02673 They are split into two  banks.   Bank  1  consists  of  gpio0  through
02674 gpio31.  Bank 2 consists of gpio32 through gpio53.
02675 
02676 All the GPIO which are safe for the user to read and write are in
02677 bank 1.  Not all GPIO in bank 1 are safe though.  Type 1 boards
02678 have 17  safe GPIO.  Type 2 boards have 21.  Type 3 boards have 26.
02679 
02680 See [*get_hardware_revision*].
02681 
02682 The user GPIO are marked with an X in the following table.
02683 
02684 . .
02685           0  1  2  3  4  5  6  7  8  9 10 11 12 13 14 15
02686 Type 1    X  X  -  -  X  -  -  X  X  X  X  X  -  -  X  X
02687 Type 2    -  -  X  X  X  -  -  X  X  X  X  X  -  -  X  X
02688 Type 3          X  X  X  X  X  X  X  X  X  X  X  X  X  X
02689 
02690          16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
02691 Type 1    -  X  X  -  -  X  X  X  X  X  -  -  -  -  -  -
02692 Type 2    -  X  X  -  -  -  X  X  X  X  -  X  X  X  X  X
02693 Type 3    X  X  X  X  X  X  X  X  X  X  X  X  -  -  -  -
02694 . .
02695 
02696 gpioPulse_t::
02697 . .
02698 typedef struct
02699 {
02700 uint32_t gpioOn;
02701 uint32_t gpioOff;
02702 uint32_t usDelay;
02703 } gpioPulse_t;
02704 . .
02705 
02706 gpioThreadFunc_t::
02707 . .
02708 typedef void *(gpioThreadFunc_t) (void *);
02709 . .
02710 
02711 handle::>=0
02712 A number referencing an object opened by one of [*i2c_open*], [*notify_open*],
02713 [*serial_open*], and [*spi_open*].
02714 
02715 i2c_addr:: 0-0x7F
02716 The address of a device on the I2C bus.
02717 
02718 i2c_bus::>=0
02719 An I2C bus number.
02720 
02721 i2c_flags::0
02722 Flags which modify an I2C open command.  None are currently defined.
02723 
02724 i2c_reg:: 0-255
02725 A register of an I2C device.
02726 
02727 *inBuf::
02728 A buffer used to pass data to a function.
02729 
02730 inLen::
02731 The number of bytes of data in a buffer.
02732 
02733 int::
02734 A whole number, negative or positive.
02735 
02736 invert::
02737 A flag used to set normal or inverted bit bang serial data level logic.
02738 
02739 level::
02740 The level of a GPIO.  Low or High.
02741 
02742 . .
02743 PI_OFF 0
02744 PI_ON 1
02745 
02746 PI_CLEAR 0
02747 PI_SET 1
02748 
02749 PI_LOW 0
02750 PI_HIGH 1
02751 . .
02752 
02753 There is one exception.  If a watchdog expires on a GPIO the level will be
02754 reported as PI_TIMEOUT.  See [*set_watchdog*].
02755 
02756 . .
02757 PI_TIMEOUT 2
02758 . .
02759 
02760 mode::0-7
02761 The operational mode of a GPIO, normally INPUT or OUTPUT.
02762 
02763 . .
02764 PI_INPUT 0
02765 PI_OUTPUT 1
02766 PI_ALT0 4
02767 PI_ALT1 5
02768 PI_ALT2 6
02769 PI_ALT3 7
02770 PI_ALT4 3
02771 PI_ALT5 2
02772 . .
02773 
02774 numBytes::
02775 The number of bytes used to store characters in a string.  Depending
02776 on the number of bits per character there may be 1, 2, or 4 bytes
02777 per character.
02778 
02779 numPar:: 0-10
02780 The number of parameters passed to a script.
02781 
02782 numPulses::
02783 The number of pulses to be added to a waveform.
02784 
02785 offset::
02786 The associated data starts this number of microseconds from the start of
02787 the waveform.
02788 
02789 *outBuf::
02790 A buffer used to return data from a function.
02791 
02792 outLen::
02793 The size in bytes of an output buffer.
02794 
02795 *param::
02796 An array of script parameters.
02797 
02798 *portStr::
02799 A string specifying the port address used by the Pi running
02800 the pigpio daemon.  It may be NULL in which case "8888"
02801 is used unless overridden by the PIGPIO_PORT environment
02802 variable.
02803 
02804 *pth::
02805 A thread identifier, returned by [*start_thread*].
02806 
02807 
02808 pthread_t::
02809 A thread identifier.
02810 
02811 pud::0-2
02812 The setting of the pull up/down resistor for a GPIO, which may be off,
02813 pull-up, or pull-down.
02814 . .
02815 PI_PUD_OFF 0
02816 PI_PUD_DOWN 1
02817 PI_PUD_UP 2
02818 . .
02819 
02820 pulseLen::
02821 1-100, the length of a trigger pulse in microseconds.
02822 
02823 *pulses::
02824 An array of pulses to be added to a waveform.
02825 
02826 pulsewidth::0, 500-2500
02827 . .
02828 PI_SERVO_OFF 0
02829 PI_MIN_SERVO_PULSEWIDTH 500
02830 PI_MAX_SERVO_PULSEWIDTH 2500
02831 . .
02832 
02833 PWMduty::0-1000000 (1M)
02834 The hardware PWM dutycycle.
02835 
02836 . .
02837 #define PI_HW_PWM_RANGE 1000000
02838 . .
02839 
02840 PWMfreq::1-125000000 (125M)
02841 The hardware PWM frequency.
02842 
02843 . .
02844 #define PI_HW_PWM_MIN_FREQ 1
02845 #define PI_HW_PWM_MAX_FREQ 125000000
02846 . .
02847 
02848 range::25-40000
02849 The permissible dutycycle values are 0-range.
02850 . .
02851 PI_MIN_DUTYCYCLE_RANGE 25
02852 PI_MAX_DUTYCYCLE_RANGE 40000
02853 . .
02854 
02855 *retBuf::
02856 A buffer to hold a number of bytes returned to a used customised function,
02857 
02858 retMax::
02859 The maximum number of bytes a user customised function should return.
02860 
02861 
02862 *rxBuf::
02863 A pointer to a buffer to receive data.
02864 
02865 SCL::
02866 The user GPIO to use for the clock when bit banging I2C.
02867 
02868 *script::
02869 A pointer to the text of a script.
02870 
02871 script_id::
02872 An id of a stored script as returned by [*store_script*].
02873 
02874 SDA::
02875 The user GPIO to use for data when bit banging I2C.
02876 
02877 seconds::
02878 The number of seconds.
02879 
02880 ser_flags::
02881 Flags which modify a serial open command.  None are currently defined.
02882 
02883 *ser_tty::
02884 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
02885 
02886 size_t::
02887 A standard type used to indicate the size of an object in bytes.
02888 
02889 spi_channel::
02890 A SPI channel, 0-2.
02891 
02892 spi_flags::
02893 See [*spi_open*].
02894 
02895 steady :: 0-300000
02896 
02897 The number of microseconds level changes must be stable for
02898 before reporting the level changed ([*set_glitch_filter*]) or triggering
02899 the active part of a noise filter ([*set_noise_filter*]).
02900 
02901 stop_bits::2-8
02902 The number of (half) stop bits to be used when adding serial data
02903 to a waveform.
02904 
02905 . .
02906 #define PI_MIN_WAVE_HALFSTOPBITS 2
02907 #define PI_MAX_WAVE_HALFSTOPBITS 8
02908 . .
02909 
02910 *str::
02911  An array of characters.
02912 
02913 thread_func::
02914 A function of type gpioThreadFunc_t used as the main function of a
02915 thread.
02916 
02917 timeout::
02918 A GPIO watchdog timeout in milliseconds.
02919 . .
02920 PI_MIN_WDOG_TIMEOUT 0
02921 PI_MAX_WDOG_TIMEOUT 60000
02922 . .
02923 
02924 *txBuf::
02925 An array of bytes to transmit.
02926 
02927 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
02928 A 32-bit unsigned value.
02929 
02930 unsigned::
02931 A whole number >= 0.
02932 
02933 user_gpio::
02934 0-31, a Broadcom numbered GPIO.
02935 
02936 See [*gpio*].
02937 
02938 *userdata::
02939 A pointer to arbitrary user data.  This may be used to identify the instance.
02940 
02941 void::
02942 Denoting no parameter is required
02943 
02944 wave_add_*::
02945 One of [*wave_add_new*], [*wave_add_generic*], [*wave_add_serial*].
02946 
02947 wave_id::
02948 A number representing a waveform created by [*wave_create*].
02949 
02950 wave_send_*::
02951 One of [*wave_send_once*], [*wave_send_repeat*].
02952 
02953 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
02954 A 16-bit word value.
02955 
02956 PARAMS*/
02957 
02958 /*DEF_S pigpiod_if Error Codes*/
02959 
02960 typedef enum
02961 {
02962    pigif_bad_send           = -2000,
02963    pigif_bad_recv           = -2001,
02964    pigif_bad_getaddrinfo    = -2002,
02965    pigif_bad_connect        = -2003,
02966    pigif_bad_socket         = -2004,
02967    pigif_bad_noib           = -2005,
02968    pigif_duplicate_callback = -2006,
02969    pigif_bad_malloc         = -2007,
02970    pigif_bad_callback       = -2008,
02971    pigif_notify_failed      = -2009,
02972    pigif_callback_not_found = -2010,
02973 } pigifError_t;
02974 
02975 /*DEF_E*/
02976 
02977 #ifdef __cplusplus
02978 }
02979 #endif
02980 
02981 #endif
02982 


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