pigpiod_if.h
Go to the documentation of this file.
1 /*
2 This is free and unencumbered software released into the public domain.
3 
4 Anyone is free to copy, modify, publish, use, compile, sell, or
5 distribute this software, either in source code form or as a compiled
6 binary, for any purpose, commercial or non-commercial, and by any
7 means.
8 
9 In jurisdictions that recognize copyright laws, the author or authors
10 of this software dedicate any and all copyright interest in the
11 software to the public domain. We make this dedication for the benefit
12 of the public at large and to the detriment of our heirs and
13 successors. We intend this dedication to be an overt act of
14 relinquishment in perpetuity of all present and future rights to this
15 software under copyright law.
16 
17 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
18 EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
19 MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
20 IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
21 OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
22 ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
23 OTHER DEALINGS IN THE SOFTWARE.
24 
25 For more information, please refer to <http://unlicense.org/>
26 */
27 
28 #ifndef PIGPIOD_IF_H
29 #define PIGPIOD_IF_H
30 
31 #include "pigpio.h"
32 
33 #define PIGPIOD_IF_VERSION 28
34 
35 /*TEXT
36 
37 THIS LIBRARY IS DEPRECATED. NEW CODE SHOULD BE WRITTEN TO
38 USE THE MORE VERSATILE pigpiod_if2 LIBRARY.
39 
40 pigpiod_if is a C library for the Raspberry which allows control
41 of the GPIO via the socket interface to the pigpio daemon.
42 
43 *Features*
44 
45 o hardware timed PWM on any of GPIO 0-31
46 
47 o hardware timed servo pulses on any of GPIO 0-31
48 
49 o callbacks when any of GPIO 0-31 change state
50 
51 o callbacks at timed intervals
52 
53 o reading/writing all of the GPIO in a bank as one operation
54 
55 o individually setting GPIO modes, reading and writing
56 
57 o notifications when any of GPIO 0-31 change state
58 
59 o the construction of output waveforms with microsecond timing
60 
61 o rudimentary permission control over GPIO
62 
63 o a simple interface to start and stop new threads
64 
65 o I2C, SPI, and serial link wrappers
66 
67 o creating and running scripts on the pigpio daemon
68 
69 *GPIO*
70 
71 ALL GPIO are identified by their Broadcom number.
72 
73 *Notes*
74 
75 The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals.
76 
77 *Usage*
78 
79 Include <pigpiod_if.h> in your source files.
80 
81 Assuming your source is in prog.c use the following command to build
82 
83 . .
84 gcc -Wall -pthread -o prog prog.c -lpigpiod_if -lrt
85 . .
86 
87 to run make sure the pigpio daemon is running
88 
89 . .
90 sudo pigpiod
91 
92  ./prog # sudo is not required to run programs linked to pigpiod_if
93 . .
94 
95 For examples see x_pigpiod_if.c within the pigpio archive file.
96 
97 *Notes*
98 
99 All the functions which return an int return < 0 on error
100 
101 TEXT*/
102 
103 /*OVERVIEW
104 
105 ESSENTIAL
106 
107 pigpio_start Connects to the pigpio daemon
108 pigpio_stop Disconnects from the pigpio daemon
109 
110 BEGINNER
111 
112 set_mode Set a GPIO mode
113 get_mode Get a GPIO mode
114 
115 set_pull_up_down Set/clear GPIO pull up/down resistor
116 
117 gpio_read Read a GPIO
118 gpio_write Write a GPIO
119 
120 set_PWM_dutycycle Start/stop PWM pulses on a GPIO
121 get_PWM_dutycycle Get the PWM dutycycle in use on a GPIO
122 
123 set_servo_pulsewidth Start/stop servo pulses on a GPIO
124 get_servo_pulsewidth Get the servo pulsewidth in use on a GPIO
125 
126 callback Create GPIO level change callback
127 callback_ex Create GPIO level change callback
128 callback_cancel Cancel a callback
129 wait_for_edge Wait for GPIO level change
130 
131 INTERMEDIATE
132 
133 gpio_trigger Send a trigger pulse to a GPIO.
134 
135 set_watchdog Set a watchdog on a GPIO.
136 
137 set_PWM_range Configure PWM range for a GPIO
138 get_PWM_range Get configured PWM range for a GPIO
139 
140 set_PWM_frequency Configure PWM frequency for a GPIO
141 get_PWM_frequency Get configured PWM frequency for a GPIO
142 
143 read_bank_1 Read all GPIO in bank 1
144 read_bank_2 Read all GPIO in bank 2
145 
146 clear_bank_1 Clear selected GPIO in bank 1
147 clear_bank_2 Clear selected GPIO in bank 2
148 
149 set_bank_1 Set selected GPIO in bank 1
150 set_bank_2 Set selected GPIO in bank 2
151 
152 start_thread Start a new thread
153 stop_thread Stop a previously started thread
154 
155 ADVANCED
156 
157 get_PWM_real_range Get underlying PWM range for a GPIO
158 
159 notify_open Request a notification handle
160 notify_begin Start notifications for selected GPIO
161 notify_pause Pause notifications
162 notify_close Close a notification
163 
164 bb_serial_read_open Opens a GPIO for bit bang serial reads
165 bb_serial_read Reads bit bang serial data from a GPIO
166 bb_serial_read_close Closes a GPIO for bit bang serial reads
167 bb_serial_invert Invert serial logic (1 invert, 0 normal)
168 
169 hardware_clock Start hardware clock on supported GPIO
170 hardware_PWM Start hardware PWM on supported GPIO
171 
172 set_glitch_filter Set a glitch filter on a GPIO
173 set_noise_filter Set a noise filter on a GPIO
174 
175 SCRIPTS
176 
177 store_script Store a script
178 run_script Run a stored script
179 script_status Get script status and parameters
180 stop_script Stop a running script
181 delete_script Delete a stored script
182 
183 WAVES
184 
185 wave_clear Deletes all waveforms
186 
187 wave_add_new Starts a new waveform
188 wave_add_generic Adds a series of pulses to the waveform
189 wave_add_serial Adds serial data to the waveform
190 
191 wave_create Creates a waveform from added data
192 wave_delete Deletes one or more waveforms
193 
194 wave_send_once Transmits a waveform once
195 wave_send_repeat Transmits a waveform repeatedly
196 
197 wave_chain Transmits a chain of waveforms
198 
199 wave_tx_busy Checks to see if the waveform has ended
200 wave_tx_stop Aborts the current waveform
201 
202 wave_get_micros Length in microseconds of the current waveform
203 wave_get_high_micros Length of longest waveform so far
204 wave_get_max_micros Absolute maximum allowed micros
205 
206 wave_get_pulses Length in pulses of the current waveform
207 wave_get_high_pulses Length of longest waveform so far
208 wave_get_max_pulses Absolute maximum allowed pulses
209 
210 wave_get_cbs Length in cbs of the current waveform
211 wave_get_high_cbs Length of longest waveform so far
212 wave_get_max_cbs Absolute maximum allowed cbs
213 
214 I2C
215 
216 i2c_open Opens an I2C device
217 i2c_close Closes an I2C device
218 
219 i2c_write_quick smbus write quick
220 i2c_write_byte smbus write byte
221 i2c_read_byte smbus read byte
222 i2c_write_byte_data smbus write byte data
223 i2c_write_word_data smbus write word data
224 i2c_read_byte_data smbus read byte data
225 i2c_read_word_data smbus read word data
226 i2c_process_call smbus process call
227 i2c_write_block_data smbus write block data
228 i2c_read_block_data smbus read block data
229 i2c_block_process_call smbus block process call
230 
231 i2c_write_i2c_block_data smbus write I2C block data
232 i2c_read_i2c_block_data smbus read I2C block data
233 
234 i2c_read_device Reads the raw I2C device
235 i2c_write_device Writes the raw I2C device
236 
237 i2c_zip Performs multiple I2C transactions
238 
239 bb_i2c_open Opens GPIO for bit banging I2C
240 bb_i2c_close Closes GPIO for bit banging I2C
241 bb_i2c_zip Performs multiple bit banged I2C transactions
242 
243 SPI
244 
245 spi_open Opens a SPI device
246 spi_close Closes a SPI device
247 
248 spi_read Reads bytes from a SPI device
249 spi_write Writes bytes to a SPI device
250 spi_xfer Transfers bytes with a SPI device
251 
252 SERIAL
253 
254 serial_open Opens a serial device
255 serial_close Closes a serial device
256 
257 serial_write_byte Writes a byte to a serial device
258 serial_read_byte Reads a byte from a serial device
259 serial_write Writes bytes to a serial device
260 serial_read Reads bytes from a serial device
261 
262 serial_data_available Returns number of bytes ready to be read
263 
264 CUSTOM
265 
266 custom_1 User custom function 1
267 custom_2 User custom function 2
268 
269 UTILITIES
270 
271 get_current_tick Get current tick (microseconds)
272 
273 get_hardware_revision Get hardware revision
274 get_pigpio_version Get the pigpio version
275 pigpiod_if_version Get the pigpiod_if version
276 
277 pigpio_error Get a text description of an error code.
278 
279 time_sleep Sleeps for a float number of seconds
280 time_time Float number of seconds since the epoch
281 
282 OVERVIEW*/
283 
284 #ifdef __cplusplus
285 extern "C" {
286 #endif
287 
288 typedef void (*CBFunc_t) (unsigned user_gpio, unsigned level, uint32_t tick);
289 
290 typedef void (*CBFuncEx_t)
291  (unsigned user_gpio, unsigned level, uint32_t tick, void * user);
292 
293 typedef struct callback_s callback_t;
294 
295 /*F*/
296 double time_time(void);
297 /*D
298 Return the current time in seconds since the Epoch.
299 D*/
300 
301 /*F*/
302 void time_sleep(double seconds);
303 /*D
304 Delay execution for a given number of seconds.
305 
306 . .
307 seconds: the number of seconds to delay.
308 . .
309 D*/
310 
311 /*F*/
312 char *pigpio_error(int errnum);
313 /*D
314 Return a text description for an error code.
315 
316 . .
317 errnum: the error code.
318 . .
319 D*/
320 
321 /*F*/
322 unsigned pigpiod_if_version(void);
323 /*D
324 Return the pigpiod_if version.
325 D*/
326 
327 /*F*/
328 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata);
329 /*D
330 Starts a new thread of execution with thread_func as the main routine.
331 
332 . .
333 thread_func: the main function for the new thread.
334  userdata: a pointer to an arbitrary argument.
335 . .
336 
337 Returns a pointer to pthread_t if OK, otherwise NULL.
338 
339 The function is passed the single argument userdata.
340 
341 The thread can be cancelled by passing the pointer to pthread_t to
342 [*stop_thread*].
343 D*/
344 
345 /*F*/
346 void stop_thread(pthread_t *pth);
347 /*D
348 Cancels the thread pointed at by pth.
349 
350 . .
351 pth: the thread to be stopped.
352 . .
353 
354 No value is returned.
355 
356 The thread to be stopped should have been started with [*start_thread*].
357 D*/
358 
359 /*F*/
360 int pigpio_start(char *addrStr, char *portStr);
361 /*D
362 Connect to the pigpio daemon. Reserving command and
363 notification streams.
364 
365 . .
366 addrStr: specifies the host or IP address of the Pi running the
367  pigpio daemon. It may be NULL in which case localhost
368  is used unless overridden by the PIGPIO_ADDR environment
369  variable.
370 
371 portStr: specifies the port address used by the Pi running the
372  pigpio daemon. It may be NULL in which case "8888"
373  is used unless overridden by the PIGPIO_PORT environment
374  variable.
375 . .
376 D*/
377 
378 /*F*/
379 void pigpio_stop(void);
380 /*D
381 Terminates the connection to the pigpio daemon and releases
382 resources used by the library.
383 D*/
384 
385 /*F*/
386 int set_mode(unsigned gpio, unsigned mode);
387 /*D
388 Set the GPIO mode.
389 
390 . .
391 gpio: 0-53.
392 mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1,
393  PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5.
394 . .
395 
396 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE,
397 or PI_NOT_PERMITTED.
398 D*/
399 
400 /*F*/
401 int get_mode(unsigned gpio);
402 /*D
403 Get the GPIO mode.
404 
405 . .
406 gpio: 0-53.
407 . .
408 
409 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
410 D*/
411 
412 /*F*/
413 int set_pull_up_down(unsigned gpio, unsigned pud);
414 /*D
415 Set or clear the GPIO pull-up/down resistor.
416 
417 . .
418 gpio: 0-53.
419  pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF.
420 . .
421 
422 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD,
423 or PI_NOT_PERMITTED.
424 D*/
425 
426 /*F*/
427 int gpio_read(unsigned gpio);
428 /*D
429 Read the GPIO level.
430 
431 . .
432 gpio:0-53.
433 . .
434 
435 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
436 D*/
437 
438 /*F*/
439 int gpio_write(unsigned gpio, unsigned level);
440 /*D
441 Write the GPIO level.
442 
443 . .
444  gpio: 0-53.
445 level: 0, 1.
446 . .
447 
448 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL,
449 or PI_NOT_PERMITTED.
450 
451 Notes
452 
453 If PWM or servo pulses are active on the GPIO they are switched off.
454 D*/
455 
456 /*F*/
457 int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle);
458 /*D
459 Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO.
460 
461 . .
462 user_gpio: 0-31.
463 dutycycle: 0-range (range defaults to 255).
464 . .
465 
466 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE,
467 or PI_NOT_PERMITTED.
468 Notes
469 
470 The [*set_PWM_range*] function may be used to change the
471 default range of 255.
472 D*/
473 
474 /*F*/
475 int get_PWM_dutycycle(unsigned user_gpio);
476 /*D
477 Return the PWM dutycycle in use on a GPIO.
478 
479 . .
480 user_gpio: 0-31.
481 . .
482 
483 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
484 
485 For normal PWM the dutycycle will be out of the defined range
486 for the GPIO (see [*get_PWM_range*]).
487 
488 If a hardware clock is active on the GPIO the reported dutycycle
489 will be 500000 (500k) out of 1000000 (1M).
490 
491 If hardware PWM is active on the GPIO the reported dutycycle
492 will be out of a 1000000 (1M).
493 D*/
494 
495 /*F*/
496 int set_PWM_range(unsigned user_gpio, unsigned range);
497 /*D
498 Set the range of PWM values to be used on the GPIO.
499 
500 . .
501 user_gpio: 0-31.
502  range: 25-40000.
503 . .
504 
505 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE,
506 or PI_NOT_PERMITTED.
507 
508 Notes
509 
510 If PWM is currently active on the GPIO its dutycycle will be
511 scaled to reflect the new range.
512 
513 The real range, the number of steps between fully off and fully on
514 for each of the 18 available GPIO frequencies is
515 
516 . .
517  25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6),
518  400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12),
519 2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18)
520 . .
521 
522 The real value set by set_PWM_range is (dutycycle * real range) / range.
523 D*/
524 
525 /*F*/
526 int get_PWM_range(unsigned user_gpio);
527 /*D
528 Get the range of PWM values being used on the GPIO.
529 
530 . .
531 user_gpio: 0-31.
532 . .
533 
534 Returns the dutycycle range used for the GPIO if OK,
535 otherwise PI_BAD_USER_GPIO.
536 
537 If a hardware clock or hardware PWM is active on the GPIO the
538 reported range will be 1000000 (1M).
539 D*/
540 
541 /*F*/
542 int get_PWM_real_range(unsigned user_gpio);
543 /*D
544 Get the real underlying range of PWM values being used on the GPIO.
545 
546 . .
547 user_gpio: 0-31.
548 . .
549 
550 Returns the real range used for the GPIO if OK,
551 otherwise PI_BAD_USER_GPIO.
552 
553 If a hardware clock is active on the GPIO the reported
554 real range will be 1000000 (1M).
555 
556 If hardware PWM is active on the GPIO the reported real range
557 will be approximately 250M divided by the set PWM frequency.
558 
559 D*/
560 
561 /*F*/
562 int set_PWM_frequency(unsigned user_gpio, unsigned frequency);
563 /*D
564 Set the frequency (in Hz) of the PWM to be used on the GPIO.
565 
566 . .
567 user_gpio: 0-31.
568 frequency: >=0 (Hz).
569 . .
570 
571 Returns the numerically closest frequency if OK, otherwise
572 PI_BAD_USER_GPIO or PI_NOT_PERMITTED.
573 
574 If PWM is currently active on the GPIO it will be switched
575 off and then back on at the new frequency.
576 
577 Each GPIO can be independently set to one of 18 different
578 PWM frequencies.
579 
580 The selectable frequencies depend upon the sample rate which
581 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The
582 sample rate is set when the pigpio daemon is started.
583 
584 The frequencies for each sample rate are:
585 
586 . .
587  Hertz
588 
589  1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
590  1250 1000 800 500 400 250 200 100 50
591 
592  2: 20000 10000 5000 4000 2500 2000 1250 1000 800
593  625 500 400 250 200 125 100 50 25
594 
595  4: 10000 5000 2500 2000 1250 1000 625 500 400
596  313 250 200 125 100 63 50 25 13
597 sample
598  rate
599  (us) 5: 8000 4000 2000 1600 1000 800 500 400 320
600  250 200 160 100 80 50 40 20 10
601 
602  8: 5000 2500 1250 1000 625 500 313 250 200
603  156 125 100 63 50 31 25 13 6
604 
605  10: 4000 2000 1000 800 500 400 250 200 160
606  125 100 80 50 40 25 20 10 5
607 . .
608 D*/
609 
610 /*F*/
611 int get_PWM_frequency(unsigned user_gpio);
612 /*D
613 Get the frequency of PWM being used on the GPIO.
614 
615 . .
616 user_gpio: 0-31.
617 . .
618 
619 For normal PWM the frequency will be that defined for the GPIO by
620 [*set_PWM_frequency*].
621 
622 If a hardware clock is active on the GPIO the reported frequency
623 will be that set by [*hardware_clock*].
624 
625 If hardware PWM is active on the GPIO the reported frequency
626 will be that set by [*hardware_PWM*].
627 
628 Returns the frequency (in hertz) used for the GPIO if OK,
629 otherwise PI_BAD_USER_GPIO.
630 D*/
631 
632 /*F*/
633 int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth);
634 /*D
635 Start (500-2500) or stop (0) servo pulses on the GPIO.
636 
637 . .
638  user_gpio: 0-31.
639 pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise).
640 . .
641 
642 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or
643 PI_NOT_PERMITTED.
644 
645 The selected pulsewidth will continue to be transmitted until
646 changed by a subsequent call to set_servo_pulsewidth.
647 
648 The pulsewidths supported by servos varies and should probably be
649 determined by experiment. A value of 1500 should always be safe and
650 represents the mid-point of rotation.
651 
652 You can DAMAGE a servo if you command it to move beyond its limits.
653 
654 OTHER UPDATE RATES:
655 
656 This function updates servos at 50Hz. If you wish to use a different
657 update frequency you will have to use the PWM functions.
658 
659 . .
660 Update Rate (Hz) 50 100 200 400 500
661 1E6/Hz 20000 10000 5000 2500 2000
662 . .
663 
664 Firstly set the desired PWM frequency using [*set_PWM_frequency*].
665 
666 Then set the PWM range using [*set_PWM_range*] to 1E6/Hz.
667 Doing this allows you to use units of microseconds when setting
668 the servo pulsewidth.
669 
670 E.g. If you want to update a servo connected to GPIO 25 at 400Hz
671 
672 . .
673 set_PWM_frequency(25, 400);
674 set_PWM_range(25, 2500);
675 . .
676 
677 Thereafter use the [*set_PWM_dutycycle*] function to move the servo,
678 e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse.
679 D*/
680 
681 /*F*/
682 int get_servo_pulsewidth(unsigned user_gpio);
683 /*D
684 Return the servo pulsewidth in use on a GPIO.
685 
686 . .
687 user_gpio: 0-31.
688 . .
689 
690 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
691 D*/
692 
693 /*F*/
694 int notify_open(void);
695 /*D
696 Get a free notification handle.
697 
698 Returns a handle greater than or equal to zero if OK,
699 otherwise PI_NO_HANDLE.
700 
701 A notification is a method for being notified of GPIO state
702 changes via a pipe.
703 
704 Pipes are only accessible from the local machine so this function
705 serves no purpose if you are using the library from a remote machine.
706 The in-built (socket) notifications provided by [*callback*]
707 should be used instead.
708 
709 Notifications for handle x will be available at the pipe
710 named /dev/pigpiox (where x is the handle number).
711 E.g. if the function returns 15 then the notifications must be
712 read from /dev/pigpio15.
713 D*/
714 
715 /*F*/
716 int notify_begin(unsigned handle, uint32_t bits);
717 /*D
718 Start notifications on a previously opened handle.
719 
720 . .
721 handle: 0-31 (as returned by [*notify_open*])
722  bits: a mask indicating the GPIO to be notified.
723 . .
724 
725 Returns 0 if OK, otherwise PI_BAD_HANDLE.
726 
727 The notification sends state changes for each GPIO whose
728 corresponding bit in bits is set.
729 
730 Each notification occupies 12 bytes in the fifo as follows:
731 
732 . .
733 typedef struct
734 {
735  uint16_t seqno;
736  uint16_t flags;
737  uint32_t tick;
738  uint32_t level;
739 } gpioReport_t;
740 . .
741 
742 seqno: starts at 0 each time the handle is opened and then increments
743 by one for each report.
744 
745 flags: two flags are defined, PI_NTFY_FLAGS_WDOG and PI_NTFY_FLAGS_ALIVE.
746 
747 PI_NTFY_FLAGS_WDOG, if bit 5 is set then bits 0-4 of the flags
748 indicate a GPIO which has had a watchdog timeout.
749 
750 PI_NTFY_FLAGS_ALIVE, if bit 6 is set this indicates a keep alive
751 signal on the pipe/socket and is sent once a minute in the absence
752 of other notification activity.
753 
754 tick: the number of microseconds since system boot. It wraps around
755 after 1h12m.
756 
757 level: indicates the level of each GPIO. If bit 1<<x is set then
758 GPIO x is high.
759 D*/
760 
761 /*F*/
762 int notify_pause(unsigned handle);
763 /*D
764 Pause notifications on a previously opened handle.
765 
766 . .
767 handle: 0-31 (as returned by [*notify_open*])
768 . .
769 
770 Returns 0 if OK, otherwise PI_BAD_HANDLE.
771 
772 Notifications for the handle are suspended until
773 [*notify_begin*] is called again.
774 D*/
775 
776 /*F*/
777 int notify_close(unsigned handle);
778 /*D
779 Stop notifications on a previously opened handle and
780 release the handle for reuse.
781 
782 . .
783 handle: 0-31 (as returned by [*notify_open*])
784 . .
785 
786 Returns 0 if OK, otherwise PI_BAD_HANDLE.
787 D*/
788 
789 /*F*/
790 int set_watchdog(unsigned user_gpio, unsigned timeout);
791 /*D
792 Sets a watchdog for a GPIO.
793 
794 . .
795 user_gpio: 0-31.
796  timeout: 0-60000.
797 . .
798 
799 Returns 0 if OK, otherwise PI_BAD_USER_GPIO
800 or PI_BAD_WDOG_TIMEOUT.
801 
802 The watchdog is nominally in milliseconds.
803 
804 Only one watchdog may be registered per GPIO.
805 
806 The watchdog may be cancelled by setting timeout to 0.
807 
808 Once a watchdog has been started callbacks for the GPIO will be
809 triggered every timeout interval after the last GPIO activity.
810 
811 The callback will receive the special level PI_TIMEOUT.
812 D*/
813 
814 /*F*/
815 int set_glitch_filter(unsigned user_gpio, unsigned steady);
816 /*D
817 Sets a glitch filter on a GPIO.
818 
819 Level changes on the GPIO are not reported unless the level
820 has been stable for at least [*steady*] microseconds. The
821 level is then reported. Level changes of less than [*steady*]
822 microseconds are ignored.
823 
824 . .
825 user_gpio: 0-31
826  steady: 0-300000
827 . .
828 
829 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
830 
831 This filter affects the GPIO samples returned to callbacks set up
832 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
833 
834 It does not affect levels read by [*gpio_read*],
835 [*read_bank_1*], or [*read_bank_2*].
836 Each (stable) edge will be timestamped [*steady*] microseconds
837 after it was first detected.
838 D*/
839 
840 /*F*/
841 int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active);
842 /*D
843 Sets a noise filter on a GPIO.
844 
845 Level changes on the GPIO are ignored until a level which has
846 been stable for [*steady*] microseconds is detected. Level changes
847 on the GPIO are then reported for [*active*] microseconds after
848 which the process repeats.
849 
850 . .
851 user_gpio: 0-31
852  steady: 0-300000
853  active: 0-1000000
854 . .
855 
856 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
857 
858 This filter affects the GPIO samples returned to callbacks set up
859 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
860 
861 It does not affect levels read by [*gpio_read*],
862 [*read_bank_1*], or [*read_bank_2*].
863 
864 Level changes before and after the active period may
865 be reported. Your software must be designed to cope with
866 such reports.
867 D*/
868 
869 /*F*/
870 uint32_t read_bank_1(void);
871 /*D
872 Read the levels of the bank 1 GPIO (GPIO 0-31).
873 
874 The returned 32 bit integer has a bit set if the corresponding
875 GPIO is logic 1. GPIO n has bit value (1<<n).
876 D*/
877 
878 /*F*/
879 uint32_t read_bank_2(void);
880 /*D
881 Read the levels of the bank 2 GPIO (GPIO 32-53).
882 
883 The returned 32 bit integer has a bit set if the corresponding
884 GPIO is logic 1. GPIO n has bit value (1<<(n-32)).
885 D*/
886 
887 /*F*/
888 int clear_bank_1(uint32_t bits);
889 /*D
890 Clears GPIO 0-31 if the corresponding bit in bits is set.
891 
892 . .
893 bits: a bit mask with 1 set if the corresponding GPIO is
894  to be cleared.
895 . .
896 
897 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
898 
899 A status of PI_SOME_PERMITTED indicates that the user is not
900 allowed to write to one or more of the GPIO.
901 D*/
902 
903 /*F*/
904 int clear_bank_2(uint32_t bits);
905 /*D
906 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
907 
908 . .
909 bits: a bit mask with 1 set if the corresponding GPIO is
910  to be cleared.
911 . .
912 
913 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
914 
915 A status of PI_SOME_PERMITTED indicates that the user is not
916 allowed to write to one or more of the GPIO.
917 D*/
918 
919 /*F*/
920 int set_bank_1(uint32_t bits);
921 /*D
922 Sets GPIO 0-31 if the corresponding bit in bits is set.
923 
924 . .
925 bits: a bit mask with 1 set if the corresponding GPIO is
926  to be set.
927 . .
928 
929 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
930 
931 A status of PI_SOME_PERMITTED indicates that the user is not
932 allowed to write to one or more of the GPIO.
933 D*/
934 
935 /*F*/
936 int set_bank_2(uint32_t bits);
937 /*D
938 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
939 
940 . .
941 bits: a bit mask with 1 set if the corresponding GPIO is
942  to be set.
943 . .
944 
945 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
946 
947 A status of PI_SOME_PERMITTED indicates that the user is not
948 allowed to write to one or more of the GPIO.
949 D*/
950 
951 
952 /*F*/
953 int hardware_clock(unsigned gpio, unsigned clkfreq);
954 /*D
955 Starts a hardware clock on a GPIO at the specified frequency.
956 Frequencies above 30MHz are unlikely to work.
957 
958 . .
959  gpio: see description
960 frequency: 0 (off) or 4689-250000000 (250M)
961 . .
962 
963 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
964 PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
965 
966 The same clock is available on multiple GPIO. The latest
967 frequency setting will be used by all GPIO which share a clock.
968 
969 The GPIO must be one of the following.
970 
971 . .
972 4 clock 0 All models
973 5 clock 1 All models but A and B (reserved for system use)
974 6 clock 2 All models but A and B
975 20 clock 0 All models but A and B
976 21 clock 1 All models but A and Rev.2 B (reserved for system use)
977 
978 32 clock 0 Compute module only
979 34 clock 0 Compute module only
980 42 clock 1 Compute module only (reserved for system use)
981 43 clock 2 Compute module only
982 44 clock 1 Compute module only (reserved for system use)
983 . .
984 
985 Access to clock 1 is protected by a password as its use will likely
986 crash the Pi. The password is given by or'ing 0x5A000000 with the
987 GPIO number.
988 D*/
989 
990 
991 /*F*/
992 int hardware_PWM(unsigned gpio, unsigned PWMfreq, uint32_t PWMduty);
993 /*D
994 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
995 Frequencies above 30MHz are unlikely to work.
996 
997 NOTE: Any waveform started by [*wave_send_once*], [*wave_send_repeat*],
998 or [*wave_chain*] will be cancelled.
999 
1000 This function is only valid if the pigpio main clock is PCM. The
1001 main clock defaults to PCM but may be overridden when the pigpio
1002 daemon is started (option -t).
1003 
1004 . .
1005  gpio: see descripton
1006 PWMfreq: 0 (off) or 1-125000000 (125M)
1007 PWMduty: 0 (off) to 1000000 (1M)(fully on)
1008 . .
1009 
1010 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
1011 PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ,
1012 or PI_HPWM_ILLEGAL.
1013 
1014 The same PWM channel is available on multiple GPIO. The latest
1015 frequency and dutycycle setting will be used by all GPIO which
1016 share a PWM channel.
1017 
1018 The GPIO must be one of the following.
1019 
1020 . .
1021 12 PWM channel 0 All models but A and B
1022 13 PWM channel 1 All models but A and B
1023 18 PWM channel 0 All models
1024 19 PWM channel 1 All models but A and B
1025 
1026 40 PWM channel 0 Compute module only
1027 41 PWM channel 1 Compute module only
1028 45 PWM channel 1 Compute module only
1029 52 PWM channel 0 Compute module only
1030 53 PWM channel 1 Compute module only
1031 . .
1032 D*/
1033 
1034 
1035 /*F*/
1036 uint32_t get_current_tick(void);
1037 /*D
1038 Gets the current system tick.
1039 
1040 Tick is the number of microseconds since system boot.
1041 
1042 As tick is an unsigned 32 bit quantity it wraps around after
1043 2**32 microseconds, which is approximately 1 hour 12 minutes.
1044 
1045 D*/
1046 
1047 /*F*/
1048 uint32_t get_hardware_revision(void);
1049 /*D
1050 Get the Pi's hardware revision number.
1051 
1052 The hardware revision is the last few characters on the Revision line
1053 of /proc/cpuinfo.
1054 
1055 If the hardware revision can not be found or is not a valid
1056 hexadecimal number the function returns 0.
1057 
1058 The revision number can be used to determine the assignment of GPIO
1059 to pins (see [*gpio*]).
1060 
1061 There are at least three types of board.
1062 
1063 Type 1 boards have hardware revision numbers of 2 and 3.
1064 
1065 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
1066 
1067 Type 3 boards have hardware revision numbers of 16 or greater.
1068 D*/
1069 
1070 /*F*/
1071 uint32_t get_pigpio_version(void);
1072 /*D
1073 Returns the pigpio version.
1074 D*/
1075 
1076 
1077 /*F*/
1078 int wave_clear(void);
1079 /*D
1080 This function clears all waveforms and any data added by calls to the
1081 [*wave_add_**] functions.
1082 
1083 Returns 0 if OK.
1084 D*/
1085 
1086 /*F*/
1087 int wave_add_new(void);
1088 /*D
1089 This function starts a new empty waveform. You wouldn't normally need
1090 to call this function as it is automatically called after a waveform is
1091 created with the [*wave_create*] function.
1092 
1093 Returns 0 if OK.
1094 D*/
1095 
1096 /*F*/
1097 int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses);
1098 /*D
1099 This function adds a number of pulses to the current waveform.
1100 
1101 . .
1102 numPulses: the number of pulses.
1103  pulses: an array of pulses.
1104 . .
1105 
1106 Returns the new total number of pulses in the current waveform if OK,
1107 otherwise PI_TOO_MANY_PULSES.
1108 
1109 The pulses are interleaved in time order within the existing waveform
1110 (if any).
1111 
1112 Merging allows the waveform to be built in parts, that is the settings
1113 for GPIO#1 can be added, and then GPIO#2 etc.
1114 
1115 If the added waveform is intended to start after or within the existing
1116 waveform then the first pulse should consist solely of a delay.
1117 D*/
1118 
1119 /*F*/
1120 int wave_add_serial
1121  (unsigned user_gpio, unsigned baud, unsigned data_bits,
1122  unsigned stop_bits, unsigned offset, unsigned numBytes, char *str);
1123 /*D
1124 This function adds a waveform representing serial data to the
1125 existing waveform (if any). The serial data starts offset
1126 microseconds from the start of the waveform.
1127 
1128 . .
1129 user_gpio: 0-31.
1130  baud: 50-1000000
1131 data_bits: number of data bits (1-32)
1132 stop_bits: number of stop half bits (2-8)
1133  offset: >=0
1134  numBytes: >=1
1135  str: an array of chars.
1136 . .
1137 
1138 Returns the new total number of pulses in the current waveform if OK,
1139 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
1140 PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
1141 or PI_TOO_MANY_PULSES.
1142 
1143 NOTES:
1144 
1145 The serial data is formatted as one start bit, [*data_bits*] data bits,
1146 and [*stop_bits*]/2 stop bits.
1147 
1148 It is legal to add serial data streams with different baud rates to
1149 the same waveform.
1150 
1151 [*numBytes*] is the number of bytes of data in str.
1152 
1153 The bytes required for each character depend upon [*data_bits*].
1154 
1155 For [*data_bits*] 1-8 there will be one byte per character.
1156 For [*data_bits*] 9-16 there will be two bytes per character.
1157 For [*data_bits*] 17-32 there will be four bytes per character.
1158 D*/
1159 
1160 /*F*/
1161 int wave_create(void);
1162 /*D
1163 This function creates a waveform from the data provided by the prior
1164 calls to the [*wave_add_**] functions. Upon success a wave id
1165 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
1166 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
1167 
1168 The data provided by the [*wave_add_**] functions is consumed by this
1169 function.
1170 
1171 As many waveforms may be created as there is space available. The
1172 wave id is passed to [*wave_send_**] to specify the waveform to transmit.
1173 
1174 Normal usage would be
1175 
1176 Step 1. [*wave_clear*] to clear all waveforms and added data.
1177 
1178 Step 2. [*wave_add_**] calls to supply the waveform data.
1179 
1180 Step 3. [*wave_create*] to create the waveform and get a unique id
1181 
1182 Repeat steps 2 and 3 as needed.
1183 
1184 Step 4. [*wave_send_**] with the id of the waveform to transmit.
1185 
1186 A waveform comprises one or more pulses. Each pulse consists of a
1187 [*gpioPulse_t*] structure.
1188 
1189 . .
1190 typedef struct
1191 {
1192  uint32_t gpioOn;
1193  uint32_t gpioOff;
1194  uint32_t usDelay;
1195 } gpioPulse_t;
1196 . .
1197 
1198 The fields specify
1199 
1200 1) the GPIO to be switched on at the start of the pulse.
1201 2) the GPIO to be switched off at the start of the pulse.
1202 3) the delay in microseconds before the next pulse.
1203 
1204 Any or all the fields can be zero. It doesn't make any sense to
1205 set all the fields to zero (the pulse will be ignored).
1206 
1207 When a waveform is started each pulse is executed in order with the
1208 specified delay between the pulse and the next.
1209 
1210 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
1211 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
1212 D*/
1213 
1214 
1215 /*F*/
1216 int wave_delete(unsigned wave_id);
1217 /*D
1218 This function deletes the waveform with id wave_id.
1219 
1220 . .
1221 wave_id: >=0, as returned by [*wave_create*].
1222 . .
1223 
1224 Wave ids are allocated in order, 0, 1, 2, etc.
1225 
1226 The wave is flagged for deletion. The resources used by the wave
1227 will only be reused when either of the following apply.
1228 
1229 - all waves with higher numbered wave ids have been deleted or have
1230 been flagged for deletion.
1231 
1232 - a new wave is created which uses exactly the same resources as
1233 the current wave (see the C source for gpioWaveCreate for details).
1234 
1235 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
1236 D*/
1237 
1238 /*F*/
1239 int wave_send_once(unsigned wave_id);
1240 /*D
1241 This function transmits the waveform with id wave_id. The waveform
1242 is sent once.
1243 
1244 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1245 
1246 . .
1247 wave_id: >=0, as returned by [*wave_create*].
1248 . .
1249 
1250 Returns the number of DMA control blocks in the waveform if OK,
1251 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
1252 D*/
1253 
1254 /*F*/
1255 int wave_send_repeat(unsigned wave_id);
1256 /*D
1257 This function transmits the waveform with id wave_id. The waveform
1258 cycles until cancelled (either by the sending of a new waveform or
1259 by [*wave_tx_stop*]).
1260 
1261 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1262 
1263 . .
1264 wave_id: >=0, as returned by [*wave_create*].
1265 . .
1266 
1267 Returns the number of DMA control blocks in the waveform if OK,
1268 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
1269 D*/
1270 
1271 /*F*/
1272 int wave_chain(char *buf, unsigned bufSize);
1273 /*D
1274 This function transmits a chain of waveforms.
1275 
1276 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1277 
1278 The waves to be transmitted are specified by the contents of buf
1279 which contains an ordered list of [*wave_id*]s and optional command
1280 codes and related data.
1281 
1282 . .
1283  buf: pointer to the wave_ids and optional command codes
1284 bufSize: the number of bytes in buf
1285 . .
1286 
1287 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
1288 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
1289 
1290 Each wave is transmitted in the order specified. A wave may
1291 occur multiple times per chain.
1292 
1293 A blocks of waves may be transmitted multiple times by using
1294 the loop commands. The block is bracketed by loop start and
1295 end commands. Loops may be nested.
1296 
1297 Delays between waves may be added with the delay command.
1298 
1299 The following command codes are supported:
1300 
1301 Name @ Cmd & Data @ Meaning
1302 Loop Start @ 255 0 @ Identify start of a wave block
1303 Loop Repeat @ 255 1 x y @ loop x + y*256 times
1304 Delay @ 255 2 x y @ delay x + y*256 microseconds
1305 Loop Forever @ 255 3 @ loop forever
1306 
1307 If present Loop Forever must be the last entry in the chain.
1308 
1309 The code is currently dimensioned to support a chain with roughly
1310 600 entries and 20 loop counters.
1311 
1312 ...
1313 #include <stdio.h>
1314 #include <pigpiod_if.h>
1315 
1316 #define WAVES 5
1317 #define GPIO 4
1318 
1319 int main(int argc, char *argv[])
1320 {
1321  int i, wid[WAVES];
1322 
1323  if (pigpio_start(0, 0)<0) return -1;
1324 
1325  set_mode(GPIO, PI_OUTPUT);
1326 
1327  for (i=0; i<WAVES; i++)
1328  {
1329  wave_add_generic(2, (gpioPulse_t[])
1330  {{1<<GPIO, 0, 20},
1331  {0, 1<<GPIO, (i+1)*200}});
1332 
1333  wid[i] = wave_create();
1334  }
1335 
1336  wave_chain((char []) {
1337  wid[4], wid[3], wid[2], // transmit waves 4+3+2
1338  255, 0, // loop start
1339  wid[0], wid[0], wid[0], // transmit waves 0+0+0
1340  255, 0, // loop start
1341  wid[0], wid[1], // transmit waves 0+1
1342  255, 2, 0x88, 0x13, // delay 5000us
1343  255, 1, 30, 0, // loop end (repeat 30 times)
1344  255, 0, // loop start
1345  wid[2], wid[3], wid[0], // transmit waves 2+3+0
1346  wid[3], wid[1], wid[2], // transmit waves 3+1+2
1347  255, 1, 10, 0, // loop end (repeat 10 times)
1348  255, 1, 5, 0, // loop end (repeat 5 times)
1349  wid[4], wid[4], wid[4], // transmit waves 4+4+4
1350  255, 2, 0x20, 0x4E, // delay 20000us
1351  wid[0], wid[0], wid[0], // transmit waves 0+0+0
1352 
1353  }, 46);
1354 
1355  while (wave_tx_busy()) time_sleep(0.1);
1356 
1357  for (i=0; i<WAVES; i++) wave_delete(wid[i]);
1358 
1359  pigpio_stop();
1360 }
1361 ...
1362 D*/
1363 
1364 
1365 /*F*/
1366 int wave_tx_busy(void);
1367 /*D
1368 This function checks to see if a waveform is currently being
1369 transmitted.
1370 
1371 Returns 1 if a waveform is currently being transmitted, otherwise 0.
1372 D*/
1373 
1374 /*F*/
1375 int wave_tx_stop(void);
1376 /*D
1377 This function stops the transmission of the current waveform.
1378 
1379 Returns 0 if OK.
1380 
1381 This function is intended to stop a waveform started with the repeat mode.
1382 D*/
1383 
1384 /*F*/
1385 int wave_get_micros(void);
1386 /*D
1387 This function returns the length in microseconds of the current
1388 waveform.
1389 D*/
1390 
1391 /*F*/
1392 int wave_get_high_micros(void);
1393 /*D
1394 This function returns the length in microseconds of the longest waveform
1395 created since the pigpio daemon was started.
1396 D*/
1397 
1398 /*F*/
1399 int wave_get_max_micros(void);
1400 /*D
1401 This function returns the maximum possible size of a waveform in
1402 microseconds.
1403 D*/
1404 
1405 /*F*/
1406 int wave_get_pulses(void);
1407 /*D
1408 This function returns the length in pulses of the current waveform.
1409 D*/
1410 
1411 /*F*/
1412 int wave_get_high_pulses(void);
1413 /*D
1414 This function returns the length in pulses of the longest waveform
1415 created since the pigpio daemon was started.
1416 D*/
1417 
1418 /*F*/
1419 int wave_get_max_pulses(void);
1420 /*D
1421 This function returns the maximum possible size of a waveform in pulses.
1422 D*/
1423 
1424 /*F*/
1425 int wave_get_cbs(void);
1426 /*D
1427 This function returns the length in DMA control blocks of the current
1428 waveform.
1429 D*/
1430 
1431 /*F*/
1432 int wave_get_high_cbs(void);
1433 /*D
1434 This function returns the length in DMA control blocks of the longest
1435 waveform created since the pigpio daemon was started.
1436 D*/
1437 
1438 /*F*/
1439 int wave_get_max_cbs(void);
1440 /*D
1441 This function returns the maximum possible size of a waveform in DMA
1442 control blocks.
1443 D*/
1444 
1445 /*F*/
1446 int gpio_trigger(unsigned user_gpio, unsigned pulseLen, unsigned level);
1447 /*D
1448 This function sends a trigger pulse to a GPIO. The GPIO is set to
1449 level for pulseLen microseconds and then reset to not level.
1450 
1451 . .
1452 user_gpio: 0-31.
1453  pulseLen: 1-100.
1454  level: 0,1.
1455 . .
1456 
1457 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
1458 PI_BAD_PULSELEN, or PI_NOT_PERMITTED.
1459 D*/
1460 
1461 /*F*/
1462 int store_script(char *script);
1463 /*D
1464 This function stores a script for later execution.
1465 
1466 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
1467 
1468 . .
1469 script: the text of the script.
1470 . .
1471 
1472 The function returns a script id if the script is valid,
1473 otherwise PI_BAD_SCRIPT.
1474 D*/
1475 
1476 /*F*/
1477 int run_script(unsigned script_id, unsigned numPar, uint32_t *param);
1478 /*D
1479 This function runs a stored script.
1480 
1481 . .
1482 script_id: >=0, as returned by [*store_script*].
1483  numPar: 0-10, the number of parameters.
1484  param: an array of parameters.
1485 . .
1486 
1487 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
1488 PI_TOO_MANY_PARAM
1489 
1490 param is an array of up to 10 parameters which may be referenced in
1491 the script as p0 to p9.
1492 D*/
1493 
1494 /*F*/
1495 int script_status(unsigned script_id, uint32_t *param);
1496 /*D
1497 This function returns the run status of a stored script as well
1498 as the current values of parameters 0 to 9.
1499 
1500 . .
1501 script_id: >=0, as returned by [*store_script*].
1502  param: an array to hold the returned 10 parameters.
1503 . .
1504 
1505 The function returns greater than or equal to 0 if OK,
1506 otherwise PI_BAD_SCRIPT_ID.
1507 
1508 The run status may be
1509 
1510 . .
1511 PI_SCRIPT_INITING
1512 PI_SCRIPT_HALTED
1513 PI_SCRIPT_RUNNING
1514 PI_SCRIPT_WAITING
1515 PI_SCRIPT_FAILED
1516 . .
1517 
1518 The current value of script parameters 0 to 9 are returned in param.
1519 D*/
1520 
1521 /*F*/
1522 int stop_script(unsigned script_id);
1523 /*D
1524 This function stops a running script.
1525 
1526 . .
1527 script_id: >=0, as returned by [*store_script*].
1528 . .
1529 
1530 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
1531 D*/
1532 
1533 /*F*/
1534 int delete_script(unsigned script_id);
1535 /*D
1536 This function deletes a stored script.
1537 
1538 . .
1539 script_id: >=0, as returned by [*store_script*].
1540 . .
1541 
1542 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
1543 D*/
1544 
1545 /*F*/
1546 int bb_serial_read_open(unsigned user_gpio, unsigned baud, unsigned data_bits);
1547 /*D
1548 This function opens a GPIO for bit bang reading of serial data.
1549 
1550 . .
1551 user_gpio: 0-31.
1552  baud: 50-250000
1553 data_bits: 1-32
1554 . .
1555 
1556 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
1557 or PI_GPIO_IN_USE.
1558 
1559 The serial data is returned in a cyclic buffer and is read using
1560 bb_serial_read.
1561 
1562 It is the caller's responsibility to read data from the cyclic buffer
1563 in a timely fashion.
1564 D*/
1565 
1566 /*F*/
1567 int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize);
1568 /*D
1569 This function copies up to bufSize bytes of data read from the
1570 bit bang serial cyclic buffer to the buffer starting at buf.
1571 
1572 . .
1573 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1574  buf: an array to receive the read bytes.
1575  bufSize: >=0
1576 . .
1577 
1578 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
1579 or PI_NOT_SERIAL_GPIO.
1580 
1581 The bytes returned for each character depend upon the number of
1582 data bits [*data_bits*] specified in the [*bb_serial_read_open*] command.
1583 
1584 For [*data_bits*] 1-8 there will be one byte per character.
1585 For [*data_bits*] 9-16 there will be two bytes per character.
1586 For [*data_bits*] 17-32 there will be four bytes per character.
1587 D*/
1588 
1589 /*F*/
1590 int bb_serial_read_close(unsigned user_gpio);
1591 /*D
1592 This function closes a GPIO for bit bang reading of serial data.
1593 
1594 . .
1595 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1596 . .
1597 
1598 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
1599 D*/
1600 
1601 /*F*/
1602 int bb_serial_invert(unsigned user_gpio, unsigned invert);
1603 /*D
1604 This function inverts serial logic for big bang serial reads.
1605 
1606 . .
1607 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1608  invert: 0-1, 1 invert, 0 normal.
1609 . .
1610 
1611 Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT.
1612 D*/
1613 
1614 /*F*/
1615 int i2c_open(unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags);
1616 /*D
1617 This returns a handle for the device at address i2c_addr on bus i2c_bus.
1618 
1619 . .
1620  i2c_bus: >=0.
1621  i2c_addr: 0-0x7F.
1622 i2c_flags: 0.
1623 . .
1624 
1625 No flags are currently defined. This parameter should be set to zero.
1626 
1627 Physically buses 0 and 1 are available on the Pi. Higher numbered buses
1628 will be available if a kernel supported bus multiplexor is being used.
1629 
1630 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
1631 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
1632 
1633 For the SMBus commands the low level transactions are shown at the end
1634 of the function description. The following abbreviations are used.
1635 
1636 . .
1637 S (1 bit) : Start bit
1638 P (1 bit) : Stop bit
1639 Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
1640 A, NA (1 bit) : Accept and not accept bit.
1641 Addr (7 bits): I2C 7 bit address.
1642 Comm (8 bits): Command byte, a data byte which often selects a register.
1643 Data (8 bits): A data byte.
1644 Count (8 bits): A data byte containing the length of a block operation.
1645 
1646 [..]: Data sent by the device.
1647 . .
1648 D*/
1649 
1650 /*F*/
1651 int i2c_close(unsigned handle);
1652 /*D
1653 This closes the I2C device associated with the handle.
1654 
1655 . .
1656 handle: >=0, as returned by a call to [*i2c_open*].
1657 . .
1658 
1659 Returns 0 if OK, otherwise PI_BAD_HANDLE.
1660 D*/
1661 
1662 /*F*/
1663 int i2c_write_quick(unsigned handle, unsigned bit);
1664 /*D
1665 This sends a single bit (in the Rd/Wr bit) to the device associated
1666 with handle.
1667 
1668 . .
1669 handle: >=0, as returned by a call to [*i2c_open*].
1670  bit: 0-1, the value to write.
1671 . .
1672 
1673 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1674 PI_I2C_WRITE_FAILED.
1675 
1676 Quick command. SMBus 2.0 5.5.1
1677 . .
1678 S Addr Rd/Wr [A] P
1679 . .
1680 D*/
1681 
1682 /*F*/
1683 int i2c_write_byte(unsigned handle, unsigned bVal);
1684 /*D
1685 This sends a single byte to the device associated with handle.
1686 
1687 . .
1688 handle: >=0, as returned by a call to [*i2c_open*].
1689  bVal: 0-0xFF, the value to write.
1690 . .
1691 
1692 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1693 PI_I2C_WRITE_FAILED.
1694 
1695 Send byte. SMBus 2.0 5.5.2
1696 . .
1697 S Addr Wr [A] Data [A] P
1698 . .
1699 D*/
1700 
1701 /*F*/
1702 int i2c_read_byte(unsigned handle);
1703 /*D
1704 This reads a single byte from the device associated with handle.
1705 
1706 . .
1707 handle: >=0, as returned by a call to [*i2c_open*].
1708 . .
1709 
1710 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
1711 or PI_I2C_READ_FAILED.
1712 
1713 Receive byte. SMBus 2.0 5.5.3
1714 . .
1715 S Addr Rd [A] [Data] NA P
1716 . .
1717 D*/
1718 
1719 /*F*/
1720 int i2c_write_byte_data(unsigned handle, unsigned i2c_reg, unsigned bVal);
1721 /*D
1722 This writes a single byte to the specified register of the device
1723 associated with handle.
1724 
1725 . .
1726  handle: >=0, as returned by a call to [*i2c_open*].
1727 i2c_reg: 0-255, the register to write.
1728  bVal: 0-0xFF, the value to write.
1729 . .
1730 
1731 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1732 PI_I2C_WRITE_FAILED.
1733 
1734 Write byte. SMBus 2.0 5.5.4
1735 . .
1736 S Addr Wr [A] Comm [A] Data [A] P
1737 . .
1738 D*/
1739 
1740 /*F*/
1741 int i2c_write_word_data(unsigned handle, unsigned i2c_reg, unsigned wVal);
1742 /*D
1743 This writes a single 16 bit word to the specified register of the device
1744 associated with handle.
1745 
1746 . .
1747  handle: >=0, as returned by a call to [*i2c_open*].
1748 i2c_reg: 0-255, the register to write.
1749  wVal: 0-0xFFFF, the value to write.
1750 . .
1751 
1752 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1753 PI_I2C_WRITE_FAILED.
1754 
1755 Write word. SMBus 2.0 5.5.4
1756 . .
1757 S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] P
1758 . .
1759 D*/
1760 
1761 /*F*/
1762 int i2c_read_byte_data(unsigned handle, unsigned i2c_reg);
1763 /*D
1764 This reads a single byte from the specified register of the device
1765 associated with handle.
1766 
1767 . .
1768  handle: >=0, as returned by a call to [*i2c_open*].
1769 i2c_reg: 0-255, the register to read.
1770 . .
1771 
1772 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
1773 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1774 
1775 Read byte. SMBus 2.0 5.5.5
1776 . .
1777 S Addr Wr [A] Comm [A] S Addr Rd [A] [Data] NA P
1778 . .
1779 D*/
1780 
1781 /*F*/
1782 int i2c_read_word_data(unsigned handle, unsigned i2c_reg);
1783 /*D
1784 This reads a single 16 bit word from the specified register of the device
1785 associated with handle.
1786 
1787 . .
1788  handle: >=0, as returned by a call to [*i2c_open*].
1789 i2c_reg: 0-255, the register to read.
1790 . .
1791 
1792 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
1793 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1794 
1795 Read word. SMBus 2.0 5.5.5
1796 . .
1797 S Addr Wr [A] Comm [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P
1798 . .
1799 D*/
1800 
1801 /*F*/
1802 int i2c_process_call(unsigned handle, unsigned i2c_reg, unsigned wVal);
1803 /*D
1804 This writes 16 bits of data to the specified register of the device
1805 associated with handle and and reads 16 bits of data in return.
1806 
1807 . .
1808  handle: >=0, as returned by a call to [*i2c_open*].
1809 i2c_reg: 0-255, the register to write/read.
1810  wVal: 0-0xFFFF, the value to write.
1811 . .
1812 
1813 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
1814 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1815 
1816 Process call. SMBus 2.0 5.5.6
1817 . .
1818 S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A]
1819  S Addr Rd [A] [DataLow] A [DataHigh] NA P
1820 . .
1821 D*/
1822 
1823 /*F*/
1825 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
1826 /*D
1827 This writes up to 32 bytes to the specified register of the device
1828 associated with handle.
1829 
1830 . .
1831  handle: >=0, as returned by a call to [*i2c_open*].
1832 i2c_reg: 0-255, the register to write.
1833  buf: an array with the data to send.
1834  count: 1-32, the number of bytes to write.
1835 . .
1836 
1837 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1838 PI_I2C_WRITE_FAILED.
1839 
1840 Block write. SMBus 2.0 5.5.7
1841 . .
1842 S Addr Wr [A] Comm [A] Count [A] Data [A] Data [A] ... [A] Data [A] P
1843 . .
1844 D*/
1845 
1846 /*F*/
1847 int i2c_read_block_data(unsigned handle, unsigned i2c_reg, char *buf);
1848 /*D
1849 This reads a block of up to 32 bytes from the specified register of
1850 the device associated with handle.
1851 
1852 . .
1853  handle: >=0, as returned by a call to [*i2c_open*].
1854 i2c_reg: 0-255, the register to read.
1855  buf: an array to receive the read data.
1856 . .
1857 
1858 The amount of returned data is set by the device.
1859 
1860 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
1861 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1862 
1863 Block read. SMBus 2.0 5.5.7
1864 . .
1865 S Addr Wr [A] Comm [A]
1866  S Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P
1867 . .
1868 D*/
1869 
1870 /*F*/
1872 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
1873 /*D
1874 This writes data bytes to the specified register of the device
1875 associated with handle and reads a device specified number
1876 of bytes of data in return.
1877 
1878 . .
1879  handle: >=0, as returned by a call to [*i2c_open*].
1880 i2c_reg: 0-255, the register to write/read.
1881  buf: an array with the data to send and to receive the read data.
1882  count: 1-32, the number of bytes to write.
1883 . .
1884 
1885 
1886 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
1887 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1888 
1889 The smbus 2.0 documentation states that a minimum of 1 byte may be
1890 sent and a minimum of 1 byte may be received. The total number of
1891 bytes sent/received must be 32 or less.
1892 
1893 Block write-block read. SMBus 2.0 5.5.8
1894 . .
1895 S Addr Wr [A] Comm [A] Count [A] Data [A] ...
1896  S Addr Rd [A] [Count] A [Data] ... A P
1897 . .
1898 D*/
1899 
1900 /*F*/
1902 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
1903 /*D
1904 This reads count bytes from the specified register of the device
1905 associated with handle . The count may be 1-32.
1906 
1907 . .
1908  handle: >=0, as returned by a call to [*i2c_open*].
1909 i2c_reg: 0-255, the register to read.
1910  buf: an array to receive the read data.
1911  count: 1-32, the number of bytes to read.
1912 . .
1913 
1914 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
1915 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
1916 
1917 . .
1918 S Addr Wr [A] Comm [A]
1919  S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P
1920 . .
1921 D*/
1922 
1923 
1924 /*F*/
1926 unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
1927 /*D
1928 This writes 1 to 32 bytes to the specified register of the device
1929 associated with handle.
1930 
1931 . .
1932  handle: >=0, as returned by a call to [*i2c_open*].
1933 i2c_reg: 0-255, the register to write.
1934  buf: the data to write.
1935  count: 1-32, the number of bytes to write.
1936 . .
1937 
1938 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1939 PI_I2C_WRITE_FAILED.
1940 
1941 . .
1942 S Addr Wr [A] Comm [A] Data [A] Data [A] ... [A] Data [A] P
1943 . .
1944 D*/
1945 
1946 /*F*/
1947 int i2c_read_device(unsigned handle, char *buf, unsigned count);
1948 /*D
1949 This reads count bytes from the raw device into buf.
1950 
1951 . .
1952 handle: >=0, as returned by a call to [*i2c_open*].
1953  buf: an array to receive the read data bytes.
1954  count: >0, the number of bytes to read.
1955 . .
1956 
1957 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1958 PI_I2C_READ_FAILED.
1959 D*/
1960 
1961 /*F*/
1962 int i2c_write_device(unsigned handle, char *buf, unsigned count);
1963 /*D
1964 This writes count bytes from buf to the raw device.
1965 
1966 . .
1967 handle: >=0, as returned by a call to [*i2c_open*].
1968  buf: an array containing the data bytes to write.
1969  count: >0, the number of bytes to write.
1970 . .
1971 
1972 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1973 PI_I2C_WRITE_FAILED.
1974 D*/
1975 
1976 /*F*/
1977 int i2c_zip(
1978  unsigned handle,
1979  char *inBuf,
1980  unsigned inLen,
1981  char *outBuf,
1982  unsigned outLen);
1983 /*D
1984 This function executes a sequence of I2C operations. The
1985 operations to be performed are specified by the contents of inBuf
1986 which contains the concatenated command codes and associated data.
1987 
1988 . .
1989 handle: >=0, as returned by a call to [*i2cOpen*]
1990  inBuf: pointer to the concatenated I2C commands, see below
1991  inLen: size of command buffer
1992 outBuf: pointer to buffer to hold returned data
1993 outLen: size of output buffer
1994 . .
1995 
1996 Returns >= 0 if OK (the number of bytes read), otherwise
1997 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
1998 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
1999 
2000 The following command codes are supported:
2001 
2002 Name @ Cmd & Data @ Meaning
2003 End @ 0 @ No more commands
2004 Escape @ 1 @ Next P is two bytes
2005 On @ 2 @ Switch combined flag on
2006 Off @ 3 @ Switch combined flag off
2007 Address @ 4 P @ Set I2C address to P
2008 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2009 Read @ 6 P @ Read P bytes of data
2010 Write @ 7 P ... @ Write P bytes of data
2011 
2012 The address, read, and write commands take a parameter P.
2013 Normally P is one byte (0-255). If the command is preceded by
2014 the Escape command then P is two bytes (0-65535, least significant
2015 byte first).
2016 
2017 The address defaults to that associated with the handle.
2018 The flags default to 0. The address and flags maintain their
2019 previous value until updated.
2020 
2021 The returned I2C data is stored in consecutive locations of outBuf.
2022 
2023 ...
2024 Set address 0x53, write 0x32, read 6 bytes
2025 Set address 0x1E, write 0x03, read 6 bytes
2026 Set address 0x68, write 0x1B, read 8 bytes
2027 End
2028 
2029 0x04 0x53 0x07 0x01 0x32 0x06 0x06
2030 0x04 0x1E 0x07 0x01 0x03 0x06 0x06
2031 0x04 0x68 0x07 0x01 0x1B 0x06 0x08
2032 0x00
2033 ...
2034 
2035 D*/
2036 
2037 /*F*/
2038 int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud);
2039 /*D
2040 This function selects a pair of GPIO for bit banging I2C at a
2041 specified baud rate.
2042 
2043 Bit banging I2C allows for certain operations which are not possible
2044 with the standard I2C driver.
2045 
2046 o baud rates as low as 50
2047 o repeated starts
2048 o clock stretching
2049 o I2C on any pair of spare GPIO
2050 
2051 . .
2052  SDA: 0-31
2053  SCL: 0-31
2054 baud: 50-500000
2055 . .
2056 
2057 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
2058 PI_GPIO_IN_USE.
2059 
2060 NOTE:
2061 
2062 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As
2063 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
2064 D*/
2065 
2066 /*F*/
2067 int bb_i2c_close(unsigned SDA);
2068 /*D
2069 This function stops bit banging I2C on a pair of GPIO previously
2070 opened with [*bb_i2c_open*].
2071 
2072 . .
2073 SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*]
2074 . .
2075 
2076 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
2077 D*/
2078 
2079 /*F*/
2080 int bb_i2c_zip(
2081  unsigned SDA,
2082  char *inBuf,
2083  unsigned inLen,
2084  char *outBuf,
2085  unsigned outLen);
2086 /*D
2087 This function executes a sequence of bit banged I2C operations. The
2088 operations to be performed are specified by the contents of inBuf
2089 which contains the concatenated command codes and associated data.
2090 
2091 . .
2092  SDA: 0-31 (as used in a prior call to [*bb_i2c_open*])
2093  inBuf: pointer to the concatenated I2C commands, see below
2094  inLen: size of command buffer
2095 outBuf: pointer to buffer to hold returned data
2096 outLen: size of output buffer
2097 . .
2098 
2099 Returns >= 0 if OK (the number of bytes read), otherwise
2100 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
2101 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
2102 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
2103 
2104 The following command codes are supported:
2105 
2106 Name @ Cmd & Data @ Meaning
2107 End @ 0 @ No more commands
2108 Escape @ 1 @ Next P is two bytes
2109 Start @ 2 @ Start condition
2110 Stop @ 3 @ Stop condition
2111 Address @ 4 P @ Set I2C address to P
2112 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2113 Read @ 6 P @ Read P bytes of data
2114 Write @ 7 P ... @ Write P bytes of data
2115 
2116 The address, read, and write commands take a parameter P.
2117 Normally P is one byte (0-255). If the command is preceded by
2118 the Escape command then P is two bytes (0-65535, least significant
2119 byte first).
2120 
2121 The address and flags default to 0. The address and flags maintain
2122 their previous value until updated.
2123 
2124 No flags are currently defined.
2125 
2126 The returned I2C data is stored in consecutive locations of outBuf.
2127 
2128 ...
2129 Set address 0x53
2130 start, write 0x32, (re)start, read 6 bytes, stop
2131 Set address 0x1E
2132 start, write 0x03, (re)start, read 6 bytes, stop
2133 Set address 0x68
2134 start, write 0x1B, (re)start, read 8 bytes, stop
2135 End
2136 
2137 0x04 0x53
2138 0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03
2139 
2140 0x04 0x1E
2141 0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03
2142 
2143 0x04 0x68
2144 0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03
2145 
2146 0x00
2147 ...
2148 D*/
2149 
2150 /*F*/
2151 int spi_open(unsigned spi_channel, unsigned baud, unsigned spi_flags);
2152 /*D
2153 This function returns a handle for the SPI device on channel.
2154 Data will be transferred at baud bits per second. The flags may
2155 be used to modify the default behaviour of 4-wire operation, mode 0,
2156 active low chip select.
2157 
2158 An auxiliary SPI device is available on all models but the
2159 A and B and may be selected by setting the A bit in the
2160 flags. The auxiliary device has 3 chip selects and a
2161 selectable word size in bits.
2162 
2163 . .
2164 spi_channel: 0-1 (0-2 for the auxiliary SPI device).
2165  baud: 32K-125M (values above 30M are unlikely to work).
2166  spi_flags: see below.
2167 . .
2168 
2169 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
2170 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
2171 
2172 spi_flags consists of the least significant 22 bits.
2173 
2174 . .
2175 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
2176  b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m
2177 . .
2178 
2179 mm defines the SPI mode.
2180 
2181 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
2182 
2183 . .
2184 Mode POL PHA
2185  0 0 0
2186  1 0 1
2187  2 1 0
2188  3 1 1
2189 . .
2190 
2191 px is 0 if CEx is active low (default) and 1 for active high.
2192 
2193 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
2194 
2195 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
2196 
2197 W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Standard
2198 SPI device only.
2199 
2200 nnnn defines the number of bytes (0-15) to write before switching
2201 the MOSI line to MISO to read data. This field is ignored
2202 if W is not set. Standard SPI device only.
2203 
2204 T is 1 if the least significant bit is transmitted on MOSI first, the
2205 default (0) shifts the most significant bit out first. Auxiliary SPI
2206 device only.
2207 
2208 R is 1 if the least significant bit is received on MISO first, the
2209 default (0) receives the most significant bit first. Auxiliary SPI
2210 device only.
2211 
2212 bbbbbb defines the word size in bits (0-32). The default (0)
2213 sets 8 bits per word. Auxiliary SPI device only.
2214 
2215 The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions
2216 transfer data packed into 1, 2, or 4 bytes according to
2217 the word size in bits.
2218 
2219 For bits 1-8 there will be one byte per word.
2220 For bits 9-16 there will be two bytes per word.
2221 For bits 17-32 there will be four bytes per word.
2222 
2223 Multi-byte transfers are made in least significant byte first order.
2224 
2225 E.g. to transfer 32 11-bit words buf should contain 64 bytes
2226 and count should be 64.
2227 
2228 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
2229 by 0x1A.
2230 
2231 The other bits in flags should be set to zero.
2232 D*/
2233 
2234 /*F*/
2235 int spi_close(unsigned handle);
2236 /*D
2237 This functions closes the SPI device identified by the handle.
2238 
2239 . .
2240 handle: >=0, as returned by a call to [*spi_open*].
2241 . .
2242 
2243 Returns 0 if OK, otherwise PI_BAD_HANDLE.
2244 D*/
2245 
2246 /*F*/
2247 int spi_read(unsigned handle, char *buf, unsigned count);
2248 /*D
2249 This function reads count bytes of data from the SPI
2250 device associated with the handle.
2251 
2252 . .
2253 handle: >=0, as returned by a call to [*spi_open*].
2254  buf: an array to receive the read data bytes.
2255  count: the number of bytes to read.
2256 . .
2257 
2258 Returns the number of bytes transferred if OK, otherwise
2259 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2260 D*/
2261 
2262 /*F*/
2263 int spi_write(unsigned handle, char *buf, unsigned count);
2264 /*D
2265 This function writes count bytes of data from buf to the SPI
2266 device associated with the handle.
2267 
2268 . .
2269 handle: >=0, as returned by a call to [*spi_open*].
2270  buf: the data bytes to write.
2271  count: the number of bytes to write.
2272 . .
2273 
2274 Returns the number of bytes transferred if OK, otherwise
2275 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2276 D*/
2277 
2278 /*F*/
2279 int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count);
2280 /*D
2281 This function transfers count bytes of data from txBuf to the SPI
2282 device associated with the handle. Simultaneously count bytes of
2283 data are read from the device and placed in rxBuf.
2284 
2285 . .
2286 handle: >=0, as returned by a call to [*spi_open*].
2287  txBuf: the data bytes to write.
2288  rxBuf: the received data bytes.
2289  count: the number of bytes to transfer.
2290 . .
2291 
2292 Returns the number of bytes transferred if OK, otherwise
2293 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2294 D*/
2295 
2296 /*F*/
2297 int serial_open(char *ser_tty, unsigned baud, unsigned ser_flags);
2298 /*D
2299 This function opens a serial device at a specified baud rate
2300 with specified flags. The device name must start with
2301 /dev/tty or /dev/serial.
2302 
2303 . .
2304  ser_tty: the serial device to open.
2305  baud: the baud rate in bits per second, see below.
2306 ser_flags: 0.
2307 . .
2308 
2309 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
2310 PI_SER_OPEN_FAILED.
2311 
2312 The baud rate must be one of 50, 75, 110, 134, 150,
2313 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
2314 38400, 57600, 115200, or 230400.
2315 
2316 No flags are currently defined. This parameter should be set to zero.
2317 D*/
2318 
2319 /*F*/
2320 int serial_close(unsigned handle);
2321 /*D
2322 This function closes the serial device associated with handle.
2323 
2324 . .
2325 handle: >=0, as returned by a call to [*serial_open*].
2326 . .
2327 
2328 Returns 0 if OK, otherwise PI_BAD_HANDLE.
2329 D*/
2330 
2331 /*F*/
2332 int serial_write_byte(unsigned handle, unsigned bVal);
2333 /*D
2334 This function writes bVal to the serial port associated with handle.
2335 
2336 . .
2337 handle: >=0, as returned by a call to [*serial_open*].
2338 . .
2339 
2340 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2341 PI_SER_WRITE_FAILED.
2342 D*/
2343 
2344 /*F*/
2345 int serial_read_byte(unsigned handle);
2346 /*D
2347 This function reads a byte from the serial port associated with handle.
2348 
2349 . .
2350 handle: >=0, as returned by a call to [*serial_open*].
2351 . .
2352 
2353 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
2354 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
2355 
2356 If no data is ready PI_SER_READ_NO_DATA is returned.
2357 D*/
2358 
2359 /*F*/
2360 int serial_write(unsigned handle, char *buf, unsigned count);
2361 /*D
2362 This function writes count bytes from buf to the the serial port
2363 associated with handle.
2364 
2365 . .
2366 handle: >=0, as returned by a call to [*serial_open*].
2367  buf: the array of bytes to write.
2368  count: the number of bytes to write.
2369 . .
2370 
2371 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2372 PI_SER_WRITE_FAILED.
2373 D*/
2374 
2375 /*F*/
2376 int serial_read(unsigned handle, char *buf, unsigned count);
2377 /*D
2378 This function reads up to count bytes from the the serial port
2379 associated with handle and writes them to buf.
2380 
2381 . .
2382 handle: >=0, as returned by a call to [*serial_open*].
2383  buf: an array to receive the read data.
2384  count: the maximum number of bytes to read.
2385 . .
2386 
2387 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
2388 PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED.
2389 
2390 If no data is ready zero is returned.
2391 D*/
2392 
2393 /*F*/
2394 int serial_data_available(unsigned handle);
2395 /*D
2396 Returns the number of bytes available to be read from the
2397 device associated with handle.
2398 
2399 . .
2400 handle: >=0, as returned by a call to [*serial_open*].
2401 . .
2402 
2403 Returns the number of bytes of data available (>=0) if OK,
2404 otherwise PI_BAD_HANDLE.
2405 D*/
2406 
2407 /*F*/
2408 int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned argc);
2409 /*D
2410 This function is available for user customisation.
2411 
2412 It returns a single integer value.
2413 
2414 . .
2415 arg1: >=0
2416 arg2: >=0
2417 argx: extra (byte) arguments
2418 argc: number of extra arguments
2419 . .
2420 
2421 Returns >= 0 if OK, less than 0 indicates a user defined error.
2422 D*/
2423 
2424 
2425 /*F*/
2426 int custom_2(unsigned arg1, char *argx, unsigned argc,
2427  char *retBuf, unsigned retMax);
2428 /*D
2429 This function is available for user customisation.
2430 
2431 It differs from custom_1 in that it returns an array of bytes
2432 rather than just an integer.
2433 
2434 The return value is an integer indicating the number of returned bytes.
2435 . .
2436  arg1: >=0
2437  argc: extra (byte) arguments
2438  count: number of extra arguments
2439 retBuf: buffer for returned data
2440 retMax: maximum number of bytes to return
2441 . .
2442 
2443 Returns >= 0 if OK, less than 0 indicates a user defined error.
2444 
2445 Note, the number of returned bytes will be retMax or less.
2446 D*/
2447 
2448 
2449 /*F*/
2450 int callback(unsigned user_gpio, unsigned edge, CBFunc_t f);
2451 /*D
2452 This function initialises a new callback.
2453 
2454 . .
2455 user_gpio: 0-31.
2456  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
2457  f: the callback function.
2458 . .
2459 
2460 The function returns a callback id if OK, otherwise pigif_bad_malloc,
2461 pigif_duplicate_callback, or pigif_bad_callback.
2462 
2463 The callback is called with the GPIO, edge, and tick, whenever the
2464 GPIO has the identified edge.
2465 
2466 . .
2467 Parameter Value Meaning
2468 
2469 GPIO 0-31 The GPIO which has changed state
2470 
2471 edge 0-2 0 = change to low (a falling edge)
2472  1 = change to high (a rising edge)
2473  2 = no level change (a watchdog timeout)
2474 
2475 tick 32 bit The number of microseconds since boot
2476  WARNING: this wraps around from
2477  4294967295 to 0 roughly every 72 minutes
2478 . .
2479 D*/
2480 
2481 /*F*/
2482 int callback_ex
2483  (unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata);
2484 /*D
2485 This function initialises a new callback.
2486 
2487 . .
2488 user_gpio: 0-31.
2489  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
2490  f: the callback function.
2491  userdata: a pointer to arbitrary user data.
2492 . .
2493 
2494 The function returns a callback id if OK, otherwise pigif_bad_malloc,
2495 pigif_duplicate_callback, or pigif_bad_callback.
2496 
2497 The callback is called with the GPIO, edge, tick, and user, whenever
2498 the GPIO has the identified edge.
2499 
2500 . .
2501 Parameter Value Meaning
2502 
2503 GPIO 0-31 The GPIO which has changed state
2504 
2505 edge 0-2 0 = change to low (a falling edge)
2506  1 = change to high (a rising edge)
2507  2 = no level change (a watchdog timeout)
2508 
2509 tick 32 bit The number of microseconds since boot
2510  WARNING: this wraps around from
2511  4294967295 to 0 roughly every 72 minutes
2512 
2513 userdata pointer Pointer to an arbitrary object
2514 . .
2515 D*/
2516 
2517 /*F*/
2518 int callback_cancel(unsigned callback_id);
2519 /*D
2520 This function cancels a callback identified by its id.
2521 
2522 . .
2523 callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*].
2524 . .
2525 
2526 The function returns 0 if OK, otherwise pigif_callback_not_found.
2527 D*/
2528 
2529 /*F*/
2530 int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout);
2531 /*D
2532 This function waits for edge on the GPIO for up to timeout
2533 seconds.
2534 
2535 . .
2536 user_gpio: 0-31.
2537  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
2538  timeout: >=0.
2539 . .
2540 
2541 The function returns 1 if the edge occurred, otherwise 0.
2542 
2543 The function returns when the edge occurs or after the timeout.
2544 D*/
2545 
2546 /*PARAMS
2547 
2548 active :: 0-1000000
2549 
2550 The number of microseconds level changes are reported for once
2551 a noise filter has been triggered (by [*steady*] microseconds of
2552 a stable level).
2553 
2554 *addrStr::
2555 A string specifying the host or IP address of the Pi running
2556 the pigpio daemon. It may be NULL in which case localhost
2557 is used unless overridden by the PIGPIO_ADDR environment
2558 variable.
2559 
2560 arg1::
2561 An unsigned argument passed to a user customised function. Its
2562 meaning is defined by the customiser.
2563 
2564 arg2::
2565 An unsigned argument passed to a user customised function. Its
2566 meaning is defined by the customiser.
2567 
2568 argc::
2569 The count of bytes passed to a user customised function.
2570 
2571 *argx::
2572 A pointer to an array of bytes passed to a user customised function.
2573 Its meaning and content is defined by the customiser.
2574 
2575 baud::
2576 The speed of serial communication (I2C, SPI, serial link, waves) in
2577 bits per second.
2578 
2579 bit::
2580 A value of 0 or 1.
2581 
2582 bits::
2583 A value used to select GPIO. If bit n of bits is set then GPIO n is
2584 selected.
2585 
2586 A convenient way to set bit n is to or in (1<<n).
2587 
2588 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
2589 
2590 *buf::
2591 A buffer to hold data being sent or being received.
2592 
2593 bufSize::
2594 The size in bytes of a buffer.
2595 
2596 
2597 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
2598 An 8-bit byte value.
2599 
2600 callback_id::
2601 A >=0, as returned by a call to [*callback*] or [*callback_ex*]. This is
2602 passed to [*callback_cancel*] to cancel the callback.
2603 
2604 CBFunc_t::
2605 . .
2606 typedef void (*CBFunc_t)
2607  (unsigned user_gpio, unsigned level, uint32_t tick);
2608 . .
2609 
2610 CBFuncEx_t::
2611 . .
2612 typedef void (*CBFuncEx_t)
2613  (unsigned user_gpio, unsigned level, uint32_t tick, void * user);
2614 . .
2615 
2616 char::
2617 A single character, an 8 bit quantity able to store 0-255.
2618 
2619 clkfreq::4689-250000000 (250M)
2620 The hardware clock frequency.
2621 
2622 count::
2623 The number of bytes to be transferred in an I2C, SPI, or Serial
2624 command.
2625 
2626 data_bits::1-32
2627 The number of data bits in each character of serial data.
2628 
2629 . .
2630 #define PI_MIN_WAVE_DATABITS 1
2631 #define PI_MAX_WAVE_DATABITS 32
2632 . .
2633 
2634 double::
2635 A floating point number.
2636 
2637 dutycycle::0-range
2638 A number representing the ratio of on time to off time for PWM.
2639 
2640 The number may vary between 0 and range (default 255) where
2641 0 is off and range is fully on.
2642 
2643 edge::
2644 Used to identify a GPIO level transition of interest. A rising edge is
2645 a level change from 0 to 1. A falling edge is a level change from 1 to 0.
2646 
2647 . .
2648 RISING_EDGE 0
2649 FALLING_EDGE 1
2650 EITHER_EDGE. 2
2651 . .
2652 
2653 errnum::
2654 A negative number indicating a function call failed and the nature
2655 of the error.
2656 
2657 f::
2658 A function.
2659 
2660 frequency::>=0
2661 The number of times a GPIO is swiched on and off per second. This
2662 can be set per GPIO and may be as little as 5Hz or as much as
2663 40KHz. The GPIO will be on for a proportion of the time as defined
2664 by its dutycycle.
2665 
2666 
2667 gpio::
2668 A Broadcom numbered GPIO, in the range 0-53.
2669 
2670 There are 54 General Purpose Input Outputs (GPIO) named gpio0 through
2671 gpio53.
2672 
2673 They are split into two banks. Bank 1 consists of gpio0 through
2674 gpio31. Bank 2 consists of gpio32 through gpio53.
2675 
2676 All the GPIO which are safe for the user to read and write are in
2677 bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards
2678 have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26.
2679 
2680 See [*get_hardware_revision*].
2681 
2682 The user GPIO are marked with an X in the following table.
2683 
2684 . .
2685  0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
2686 Type 1 X X - - X - - X X X X X - - X X
2687 Type 2 - - X X X - - X X X X X - - X X
2688 Type 3 X X X X X X X X X X X X X X
2689 
2690  16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
2691 Type 1 - X X - - X X X X X - - - - - -
2692 Type 2 - X X - - - X X X X - X X X X X
2693 Type 3 X X X X X X X X X X X X - - - -
2694 . .
2695 
2696 gpioPulse_t::
2697 . .
2698 typedef struct
2699 {
2700 uint32_t gpioOn;
2701 uint32_t gpioOff;
2702 uint32_t usDelay;
2703 } gpioPulse_t;
2704 . .
2705 
2706 gpioThreadFunc_t::
2707 . .
2708 typedef void *(gpioThreadFunc_t) (void *);
2709 . .
2710 
2711 handle::>=0
2712 A number referencing an object opened by one of [*i2c_open*], [*notify_open*],
2713 [*serial_open*], and [*spi_open*].
2714 
2715 i2c_addr:: 0-0x7F
2716 The address of a device on the I2C bus.
2717 
2718 i2c_bus::>=0
2719 An I2C bus number.
2720 
2721 i2c_flags::0
2722 Flags which modify an I2C open command. None are currently defined.
2723 
2724 i2c_reg:: 0-255
2725 A register of an I2C device.
2726 
2727 *inBuf::
2728 A buffer used to pass data to a function.
2729 
2730 inLen::
2731 The number of bytes of data in a buffer.
2732 
2733 int::
2734 A whole number, negative or positive.
2735 
2736 invert::
2737 A flag used to set normal or inverted bit bang serial data level logic.
2738 
2739 level::
2740 The level of a GPIO. Low or High.
2741 
2742 . .
2743 PI_OFF 0
2744 PI_ON 1
2745 
2746 PI_CLEAR 0
2747 PI_SET 1
2748 
2749 PI_LOW 0
2750 PI_HIGH 1
2751 . .
2752 
2753 There is one exception. If a watchdog expires on a GPIO the level will be
2754 reported as PI_TIMEOUT. See [*set_watchdog*].
2755 
2756 . .
2757 PI_TIMEOUT 2
2758 . .
2759 
2760 mode::0-7
2761 The operational mode of a GPIO, normally INPUT or OUTPUT.
2762 
2763 . .
2764 PI_INPUT 0
2765 PI_OUTPUT 1
2766 PI_ALT0 4
2767 PI_ALT1 5
2768 PI_ALT2 6
2769 PI_ALT3 7
2770 PI_ALT4 3
2771 PI_ALT5 2
2772 . .
2773 
2774 numBytes::
2775 The number of bytes used to store characters in a string. Depending
2776 on the number of bits per character there may be 1, 2, or 4 bytes
2777 per character.
2778 
2779 numPar:: 0-10
2780 The number of parameters passed to a script.
2781 
2782 numPulses::
2783 The number of pulses to be added to a waveform.
2784 
2785 offset::
2786 The associated data starts this number of microseconds from the start of
2787 the waveform.
2788 
2789 *outBuf::
2790 A buffer used to return data from a function.
2791 
2792 outLen::
2793 The size in bytes of an output buffer.
2794 
2795 *param::
2796 An array of script parameters.
2797 
2798 *portStr::
2799 A string specifying the port address used by the Pi running
2800 the pigpio daemon. It may be NULL in which case "8888"
2801 is used unless overridden by the PIGPIO_PORT environment
2802 variable.
2803 
2804 *pth::
2805 A thread identifier, returned by [*start_thread*].
2806 
2807 
2808 pthread_t::
2809 A thread identifier.
2810 
2811 pud::0-2
2812 The setting of the pull up/down resistor for a GPIO, which may be off,
2813 pull-up, or pull-down.
2814 . .
2815 PI_PUD_OFF 0
2816 PI_PUD_DOWN 1
2817 PI_PUD_UP 2
2818 . .
2819 
2820 pulseLen::
2821 1-100, the length of a trigger pulse in microseconds.
2822 
2823 *pulses::
2824 An array of pulses to be added to a waveform.
2825 
2826 pulsewidth::0, 500-2500
2827 . .
2828 PI_SERVO_OFF 0
2829 PI_MIN_SERVO_PULSEWIDTH 500
2830 PI_MAX_SERVO_PULSEWIDTH 2500
2831 . .
2832 
2833 PWMduty::0-1000000 (1M)
2834 The hardware PWM dutycycle.
2835 
2836 . .
2837 #define PI_HW_PWM_RANGE 1000000
2838 . .
2839 
2840 PWMfreq::1-125000000 (125M)
2841 The hardware PWM frequency.
2842 
2843 . .
2844 #define PI_HW_PWM_MIN_FREQ 1
2845 #define PI_HW_PWM_MAX_FREQ 125000000
2846 . .
2847 
2848 range::25-40000
2849 The permissible dutycycle values are 0-range.
2850 . .
2851 PI_MIN_DUTYCYCLE_RANGE 25
2852 PI_MAX_DUTYCYCLE_RANGE 40000
2853 . .
2854 
2855 *retBuf::
2856 A buffer to hold a number of bytes returned to a used customised function,
2857 
2858 retMax::
2859 The maximum number of bytes a user customised function should return.
2860 
2861 
2862 *rxBuf::
2863 A pointer to a buffer to receive data.
2864 
2865 SCL::
2866 The user GPIO to use for the clock when bit banging I2C.
2867 
2868 *script::
2869 A pointer to the text of a script.
2870 
2871 script_id::
2872 An id of a stored script as returned by [*store_script*].
2873 
2874 SDA::
2875 The user GPIO to use for data when bit banging I2C.
2876 
2877 seconds::
2878 The number of seconds.
2879 
2880 ser_flags::
2881 Flags which modify a serial open command. None are currently defined.
2882 
2883 *ser_tty::
2884 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
2885 
2886 size_t::
2887 A standard type used to indicate the size of an object in bytes.
2888 
2889 spi_channel::
2890 A SPI channel, 0-2.
2891 
2892 spi_flags::
2893 See [*spi_open*].
2894 
2895 steady :: 0-300000
2896 
2897 The number of microseconds level changes must be stable for
2898 before reporting the level changed ([*set_glitch_filter*]) or triggering
2899 the active part of a noise filter ([*set_noise_filter*]).
2900 
2901 stop_bits::2-8
2902 The number of (half) stop bits to be used when adding serial data
2903 to a waveform.
2904 
2905 . .
2906 #define PI_MIN_WAVE_HALFSTOPBITS 2
2907 #define PI_MAX_WAVE_HALFSTOPBITS 8
2908 . .
2909 
2910 *str::
2911  An array of characters.
2912 
2913 thread_func::
2914 A function of type gpioThreadFunc_t used as the main function of a
2915 thread.
2916 
2917 timeout::
2918 A GPIO watchdog timeout in milliseconds.
2919 . .
2920 PI_MIN_WDOG_TIMEOUT 0
2921 PI_MAX_WDOG_TIMEOUT 60000
2922 . .
2923 
2924 *txBuf::
2925 An array of bytes to transmit.
2926 
2927 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
2928 A 32-bit unsigned value.
2929 
2930 unsigned::
2931 A whole number >= 0.
2932 
2933 user_gpio::
2934 0-31, a Broadcom numbered GPIO.
2935 
2936 See [*gpio*].
2937 
2938 *userdata::
2939 A pointer to arbitrary user data. This may be used to identify the instance.
2940 
2941 void::
2942 Denoting no parameter is required
2943 
2944 wave_add_*::
2945 One of [*wave_add_new*], [*wave_add_generic*], [*wave_add_serial*].
2946 
2947 wave_id::
2948 A number representing a waveform created by [*wave_create*].
2949 
2950 wave_send_*::
2951 One of [*wave_send_once*], [*wave_send_repeat*].
2952 
2953 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
2954 A 16-bit word value.
2955 
2956 PARAMS*/
2957 
2958 /*DEF_S pigpiod_if Error Codes*/
2959 
2960 typedef enum
2961 {
2973 } pigifError_t;
2974 
2975 /*DEF_E*/
2976 
2977 #ifdef __cplusplus
2978 }
2979 #endif
2980 
2981 #endif
2982 
int wave_add_new(void)
Definition: pigpiod_if.c:677
int set_PWM_range(unsigned user_gpio, unsigned range)
Definition: pigpiod_if.c:589
int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud)
Definition: pigpiod_if.c:1256
int bb_i2c_close(unsigned SDA)
Definition: pigpiod_if.c:1275
int gpio_read(unsigned gpio)
Definition: pigpiod_if.c:577
int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned argc)
Definition: pigpiod_if.c:1469
int wave_get_high_cbs(void)
Definition: pigpiod_if.c:799
uint32_t get_current_tick(void)
Definition: pigpiod_if.c:665
int delete_script(unsigned script_id)
Definition: pigpiod_if.c:932
int wave_get_high_micros(void)
Definition: pigpiod_if.c:781
int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses)
Definition: pigpiod_if.c:680
void(* CBFunc_t)(unsigned user_gpio, unsigned level, uint32_t tick)
Definition: pigpiod_if.h:288
int notify_close(unsigned handle)
Definition: pigpiod_if.c:619
int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active)
Definition: pigpiod_if.c:827
int get_servo_pulsewidth(unsigned user_gpio)
Definition: pigpiod_if.c:607
int clear_bank_2(uint32_t bits)
Definition: pigpiod_if.c:634
int wave_get_pulses(void)
Definition: pigpiod_if.c:787
int hardware_clock(unsigned gpio, unsigned clkfreq)
Definition: pigpiod_if.c:643
int wave_send_once(unsigned wave_id)
Definition: pigpiod_if.c:747
int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize)
Definition: pigpiod_if.c:954
int spi_close(unsigned handle)
Definition: pigpiod_if.c:1331
int i2c_read_word_data(unsigned handle, unsigned i2c_reg)
Definition: pigpiod_if.c:1048
int serial_open(char *ser_tty, unsigned baud, unsigned ser_flags)
Definition: pigpiod_if.c:1399
int set_PWM_frequency(unsigned user_gpio, unsigned frequency)
Definition: pigpiod_if.c:598
int i2c_write_i2c_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1167
int i2c_write_device(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1203
handle
Definition: PCF8591.py:19
int wave_get_max_pulses(void)
Definition: pigpiod_if.c:793
int callback_ex(unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata)
Definition: pigpiod_if.c:1523
int i2c_read_device(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1187
int i2c_write_quick(unsigned handle, unsigned bit)
Definition: pigpiod_if.c:998
int get_PWM_frequency(unsigned user_gpio)
Definition: pigpiod_if.c:601
int script_status(unsigned script_id, uint32_t *param)
Definition: pigpiod_if.c:910
int clear_bank_1(uint32_t bits)
Definition: pigpiod_if.c:631
void(* CBFuncEx_t)(unsigned user_gpio, unsigned level, uint32_t tick, void *user)
Definition: pigpiod_if.h:291
int i2c_zip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if.c:1222
int custom_2(unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)
CBF_t f
Definition: pigpiod_if.c:67
int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth)
Definition: pigpiod_if.c:604
uint32_t get_pigpio_version(void)
Definition: pigpiod_if.c:671
int wave_send_repeat(unsigned wave_id)
Definition: pigpiod_if.c:750
int gpio_trigger(unsigned user_gpio, unsigned pulseLen, unsigned level)
int serial_data_available(unsigned handle)
Definition: pigpiod_if.c:1466
int spi_open(unsigned spi_channel, unsigned baud, unsigned spi_flags)
int i2c_read_block_data(unsigned handle, unsigned i2c_reg, char *buf)
Definition: pigpiod_if.c:1090
int i2c_open(unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags)
int i2c_write_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1070
int spi_read(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1334
int get_PWM_range(unsigned user_gpio)
Definition: pigpiod_if.c:592
int i2c_block_process_call(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1106
int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle)
Definition: pigpiod_if.c:583
int notify_begin(unsigned handle, uint32_t bits)
Definition: pigpiod_if.c:613
uint32_t read_bank_1(void)
Definition: pigpiod_if.c:625
int set_glitch_filter(unsigned user_gpio, unsigned steady)
Definition: pigpiod_if.c:824
uint32_t read_bank_2(void)
Definition: pigpiod_if.c:628
int serial_close(unsigned handle)
Definition: pigpiod_if.c:1421
int get_PWM_dutycycle(unsigned user_gpio)
Definition: pigpiod_if.c:586
int i2c_write_byte(unsigned handle, unsigned bVal)
Definition: pigpiod_if.c:1001
int set_watchdog(unsigned user_gpio, unsigned timeout)
Definition: pigpiod_if.c:622
int wave_get_max_micros(void)
Definition: pigpiod_if.c:784
int wave_add_serial(unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)
void pigpio_stop(void)
Definition: pigpiod_if.c:533
int serial_read(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1449
char * pigpio_error(int errnum)
Definition: pigpiod_if.c:410
pthread_t * start_thread(gpioThreadFunc_t thread_func, void *userdata)
Definition: pigpiod_if.c:450
void *( gpioThreadFunc_t)(void *)
Definition: pigpio.h:552
int set_bank_2(uint32_t bits)
Definition: pigpiod_if.c:640
int get_mode(unsigned gpio)
Definition: pigpiod_if.c:571
int bb_serial_invert(unsigned user_gpio, unsigned invert)
Definition: pigpiod_if.c:973
int wave_chain(char *buf, unsigned bufSize)
Definition: pigpiod_if.c:753
int wave_get_micros(void)
Definition: pigpiod_if.c:778
int gpio_write(unsigned gpio, unsigned level)
Definition: pigpiod_if.c:580
int wave_get_cbs(void)
Definition: pigpiod_if.c:796
int i2c_write_word_data(unsigned handle, unsigned i2c_reg, unsigned wVal)
uint32_t get_hardware_revision(void)
Definition: pigpiod_if.c:668
unsigned pigpiod_if_version(void)
Definition: pigpiod_if.c:445
void time_sleep(double seconds)
Definition: pigpio.c:8374
int pigpio_start(char *addrStr, char *portStr)
Definition: pigpiod_if.c:493
int bb_serial_read_close(unsigned user_gpio)
Definition: pigpiod_if.c:970
int i2c_write_byte_data(unsigned handle, unsigned i2c_reg, unsigned bVal)
int bb_i2c_zip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if.c:1278
double time_time(void)
Definition: pigpio.c:8360
int hardware_PWM(unsigned gpio, unsigned PWMfreq, uint32_t PWMduty)
Definition: pigpiod_if.c:646
int i2c_read_byte_data(unsigned handle, unsigned i2c_reg)
Definition: pigpiod_if.c:1045
int wave_clear(void)
Definition: pigpiod_if.c:674
int wave_tx_stop(void)
Definition: pigpiod_if.c:775
int callback(unsigned user_gpio, unsigned edge, CBFunc_t f)
Definition: pigpiod_if.c:1520
int serial_read_byte(unsigned handle)
Definition: pigpiod_if.c:1427
int spi_write(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1351
int set_mode(unsigned gpio, unsigned mode)
Definition: pigpiod_if.c:568
pigifError_t
Definition: pigpiod_if.h:2960
int wave_get_max_cbs(void)
Definition: pigpiod_if.c:802
int wave_tx_busy(void)
Definition: pigpiod_if.c:772
int i2c_process_call(unsigned handle, unsigned i2c_reg, unsigned wVal)
int set_pull_up_down(unsigned gpio, unsigned pud)
Definition: pigpiod_if.c:574
int serial_write_byte(unsigned handle, unsigned bVal)
Definition: pigpiod_if.c:1424
int wave_create(void)
Definition: pigpiod_if.c:735
int stop_script(unsigned script_id)
Definition: pigpiod_if.c:929
int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout)
Definition: pigpiod_if.c:1553
int serial_write(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1430
int wave_get_high_pulses(void)
Definition: pigpiod_if.c:790
int i2c_read_byte(unsigned handle)
Definition: pigpiod_if.c:1004
int wave_delete(unsigned wave_id)
Definition: pigpiod_if.c:738
int store_script(char *script)
Definition: pigpiod_if.c:846
int i2c_read_i2c_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
int bb_serial_read_open(unsigned user_gpio, unsigned baud, unsigned data_bits)
int get_PWM_real_range(unsigned user_gpio)
Definition: pigpiod_if.c:595
int callback_cancel(unsigned callback_id)
Definition: pigpiod_if.c:1526
int notify_open(void)
Definition: pigpiod_if.c:610
int i2c_close(unsigned handle)
Definition: pigpiod_if.c:995
int set_bank_1(uint32_t bits)
Definition: pigpiod_if.c:637
int notify_pause(unsigned handle)
Definition: pigpiod_if.c:616
int run_script(unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if.c:869
void stop_thread(pthread_t *pth)
Definition: pigpiod_if.c:483
int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if.c:1370


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