pigpiod_if2.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_IF2_H
29 #define PIGPIOD_IF2_H
30 
31 #include "pigpio.h"
32 
33 #define PIGPIOD_IF2_VERSION 13
34 
35 /*TEXT
36 
37 pigpiod_if2 is a C library for the Raspberry which allows control
38 of the GPIO via the socket interface to the pigpio daemon.
39 
40 *Features*
41 
42 o hardware timed PWM on any of GPIO 0-31
43 
44 o hardware timed servo pulses on any of GPIO 0-31
45 
46 o callbacks when any of GPIO 0-31 change state
47 
48 o callbacks at timed intervals
49 
50 o reading/writing all of the GPIO in a bank as one operation
51 
52 o individually setting GPIO modes, reading and writing
53 
54 o notifications when any of GPIO 0-31 change state
55 
56 o the construction of output waveforms with microsecond timing
57 
58 o rudimentary permission control over GPIO
59 
60 o a simple interface to start and stop new threads
61 
62 o I2C, SPI, and serial link wrappers
63 
64 o creating and running scripts on the pigpio daemon
65 
66 *GPIO*
67 
68 ALL GPIO are identified by their Broadcom number.
69 
70 *Notes*
71 
72 The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals.
73 
74 *Usage*
75 
76 Include <pigpiod_if2.h> in your source files.
77 
78 Assuming your source is in prog.c use the following command to build
79 
80 . .
81 gcc -Wall -pthread -o prog prog.c -lpigpiod_if2 -lrt
82 . .
83 
84 to run make sure the pigpio daemon is running
85 
86 . .
87 sudo pigpiod
88 
89  ./prog # sudo is not required to run programs linked to pigpiod_if2
90 . .
91 
92 For examples see x_pigpiod_if2.c within the pigpio archive file.
93 
94 *Notes*
95 
96 All the functions which return an int return < 0 on error
97 
98 TEXT*/
99 
100 /*OVERVIEW
101 
102 ESSENTIAL
103 
104 pigpio_start Connects to a pigpio daemon
105 pigpio_stop Disconnects from a pigpio daemon
106 
107 BEGINNER
108 
109 set_mode Set a GPIO mode
110 get_mode Get a GPIO mode
111 
112 set_pull_up_down Set/clear GPIO pull up/down resistor
113 
114 gpio_read Read a GPIO
115 gpio_write Write a GPIO
116 
117 set_PWM_dutycycle Start/stop PWM pulses on a GPIO
118 get_PWM_dutycycle Get the PWM dutycycle in use on a GPIO
119 
120 set_servo_pulsewidth Start/stop servo pulses on a GPIO
121 get_servo_pulsewidth Get the servo pulsewidth in use on a GPIO
122 
123 callback Create GPIO level change callback
124 callback_ex Create GPIO level change callback, extended
125 callback_cancel Cancel a callback
126 wait_for_edge Wait for GPIO level change
127 
128 INTERMEDIATE
129 
130 gpio_trigger Send a trigger pulse to a GPIO.
131 
132 set_watchdog Set a watchdog on a GPIO.
133 
134 set_PWM_range Configure PWM range for a GPIO
135 get_PWM_range Get configured PWM range for a GPIO
136 
137 set_PWM_frequency Configure PWM frequency for a GPIO
138 get_PWM_frequency Get configured PWM frequency for a GPIO
139 
140 read_bank_1 Read all GPIO in bank 1
141 read_bank_2 Read all GPIO in bank 2
142 
143 clear_bank_1 Clear selected GPIO in bank 1
144 clear_bank_2 Clear selected GPIO in bank 2
145 
146 set_bank_1 Set selected GPIO in bank 1
147 set_bank_2 Set selected GPIO in bank 2
148 
149 start_thread Start a new thread
150 stop_thread Stop a previously started thread
151 
152 ADVANCED
153 
154 get_PWM_real_range Get underlying PWM range for a GPIO
155 
156 notify_open Request a notification handle
157 notify_begin Start notifications for selected GPIO
158 notify_pause Pause notifications
159 notify_close Close a notification
160 
161 bb_serial_read_open Opens a GPIO for bit bang serial reads
162 bb_serial_read Reads bit bang serial data from a GPIO
163 bb_serial_read_close Closes a GPIO for bit bang serial reads
164 bb_serial_invert Invert serial logic (1 invert, 0 normal)
165 
166 hardware_clock Start hardware clock on supported GPIO
167 hardware_PWM Start hardware PWM on supported GPIO
168 
169 set_glitch_filter Set a glitch filter on a GPIO
170 set_noise_filter Set a noise filter on a GPIO
171 
172 get_pad_strength Gets a pads drive strength
173 set_pad_strength Sets a pads drive strength
174 
175 shell_ Executes a shell command
176 
177 SCRIPTS
178 
179 store_script Store a script
180 run_script Run a stored script
181 update_script Set a scripts parameters
182 script_status Get script status and parameters
183 stop_script Stop a running script
184 delete_script Delete a stored script
185 
186 WAVES
187 
188 wave_clear Deletes all waveforms
189 
190 wave_add_new Starts a new waveform
191 wave_add_generic Adds a series of pulses to the waveform
192 wave_add_serial Adds serial data to the waveform
193 
194 wave_create Creates a waveform from added data
195 wave_delete Deletes one or more waveforms
196 
197 wave_send_once Transmits a waveform once
198 wave_send_repeat Transmits a waveform repeatedly
199 wave_send_using_mode Transmits a waveform in the chosen mode
200 
201 wave_chain Transmits a chain of waveforms
202 
203 wave_tx_at Returns the current transmitting waveform
204 wave_tx_busy Checks to see if the waveform has ended
205 wave_tx_stop Aborts the current waveform
206 
207 wave_get_micros Length in microseconds of the current waveform
208 wave_get_high_micros Length of longest waveform so far
209 wave_get_max_micros Absolute maximum allowed micros
210 
211 wave_get_pulses Length in pulses of the current waveform
212 wave_get_high_pulses Length of longest waveform so far
213 wave_get_max_pulses Absolute maximum allowed pulses
214 
215 wave_get_cbs Length in cbs of the current waveform
216 wave_get_high_cbs Length of longest waveform so far
217 wave_get_max_cbs Absolute maximum allowed cbs
218 
219 I2C
220 
221 i2c_open Opens an I2C device
222 i2c_close Closes an I2C device
223 
224 i2c_write_quick smbus write quick
225 i2c_write_byte smbus write byte
226 i2c_read_byte smbus read byte
227 i2c_write_byte_data smbus write byte data
228 i2c_write_word_data smbus write word data
229 i2c_read_byte_data smbus read byte data
230 i2c_read_word_data smbus read word data
231 i2c_process_call smbus process call
232 i2c_write_block_data smbus write block data
233 i2c_read_block_data smbus read block data
234 i2c_block_process_call smbus block process call
235 
236 i2c_write_i2c_block_data smbus write I2C block data
237 i2c_read_i2c_block_data smbus read I2C block data
238 
239 i2c_read_device Reads the raw I2C device
240 i2c_write_device Writes the raw I2C device
241 
242 i2c_zip Performs multiple I2C transactions
243 
244 bb_i2c_open Opens GPIO for bit banging I2C
245 bb_i2c_close Closes GPIO for bit banging I2C
246 bb_i2c_zip Performs multiple bit banged I2C transactions
247 
248 SPI
249 
250 spi_open Opens a SPI device
251 spi_close Closes a SPI device
252 
253 spi_read Reads bytes from a SPI device
254 spi_write Writes bytes to a SPI device
255 spi_xfer Transfers bytes with a SPI device
256 
257 bb_spi_open Opens GPIO for bit banging SPI
258 bb_spi_close Closes GPIO for bit banging SPI
259 bb_spi_xfer Transfers bytes with bit banging SPI
260 
261 I2C/SPI_SLAVE
262 
263 bsc_xfer I2C/SPI as slave transfer
264 bsc_i2c I2C as slave transfer
265 
266 SERIAL
267 
268 serial_open Opens a serial device
269 serial_close Closes a serial device
270 
271 serial_write_byte Writes a byte to a serial device
272 serial_read_byte Reads a byte from a serial device
273 serial_write Writes bytes to a serial device
274 serial_read Reads bytes from a serial device
275 
276 serial_data_available Returns number of bytes ready to be read
277 
278 FILES
279 
280 file_open Opens a file
281 file_close Closes a file
282 file_read Reads bytes from a file
283 file_write Writes bytes to a file
284 file_seek Seeks to a position within a file
285 file_list List files which match a pattern
286 
287 EVENTS
288 
289 event_callback Sets a callback for an event
290 event_callback_ex Sets a callback for an event, extended
291 event_callback_cancel Cancel an event callback
292 event_trigger Triggers an event
293 wait_for_event Wait for an event
294 
295 CUSTOM
296 
297 custom_1 User custom function 1
298 custom_2 User custom function 2
299 
300 UTILITIES
301 
302 get_current_tick Get current tick (microseconds)
303 
304 get_hardware_revision Get hardware revision
305 get_pigpio_version Get the pigpio version
306 pigpiod_if_version Get the pigpiod_if2 version
307 
308 pigpio_error Get a text description of an error code.
309 
310 time_sleep Sleeps for a float number of seconds
311 time_time Float number of seconds since the epoch
312 
313 OVERVIEW*/
314 
315 #ifdef __cplusplus
316 extern "C" {
317 #endif
318 
319 typedef void (*CBFunc_t)
320  (int pi, unsigned user_gpio, unsigned level, uint32_t tick);
321 
322 typedef void (*CBFuncEx_t)
323  (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *userdata);
324 
325 typedef struct callback_s callback_t;
326 
327 typedef void (*evtCBFunc_t)
328  (int pi, unsigned event, uint32_t tick);
329 
330 typedef void (*evtCBFuncEx_t)
331  (int pi, unsigned event, uint32_t tick, void *userdata);
332 
334 
335 /*F*/
336 double time_time(void);
337 /*D
338 Return the current time in seconds since the Epoch.
339 D*/
340 
341 /*F*/
342 void time_sleep(double seconds);
343 /*D
344 Delay execution for a given number of seconds.
345 
346 . .
347 seconds: the number of seconds to delay.
348 . .
349 D*/
350 
351 /*F*/
352 char *pigpio_error(int errnum);
353 /*D
354 Return a text description for an error code.
355 
356 . .
357 errnum: the error code.
358 . .
359 D*/
360 
361 /*F*/
362 unsigned pigpiod_if_version(void);
363 /*D
364 Return the pigpiod_if2 version.
365 D*/
366 
367 /*F*/
368 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata);
369 /*D
370 Starts a new thread of execution with thread_func as the main routine.
371 
372 . .
373 thread_func: the main function for the new thread.
374  userdata: a pointer to an arbitrary argument.
375 . .
376 
377 Returns a pointer to pthread_t if OK, otherwise NULL.
378 
379 The function is passed the single argument userdata.
380 
381 The thread can be cancelled by passing the pointer to pthread_t to
382 [*stop_thread*].
383 D*/
384 
385 /*F*/
386 void stop_thread(pthread_t *pth);
387 /*D
388 Cancels the thread pointed at by pth.
389 
390 . .
391 pth: the thread to be stopped.
392 . .
393 
394 No value is returned.
395 
396 The thread to be stopped should have been started with [*start_thread*].
397 D*/
398 
399 /*F*/
400 int pigpio_start(char *addrStr, char *portStr);
401 /*D
402 Connect to the pigpio daemon. Reserving command and
403 notification streams.
404 
405 . .
406 addrStr: specifies the host or IP address of the Pi running the
407  pigpio daemon. It may be NULL in which case localhost
408  is used unless overridden by the PIGPIO_ADDR environment
409  variable.
410 
411 portStr: specifies the port address used by the Pi running the
412  pigpio daemon. It may be NULL in which case "8888"
413  is used unless overridden by the PIGPIO_PORT environment
414  variable.
415 . .
416 
417 Returns an integer value greater than or equal to zero if OK.
418 
419 This value is passed to the GPIO routines to specify the Pi
420 to be operated on.
421 D*/
422 
423 /*F*/
424 void pigpio_stop(int pi);
425 /*D
426 Terminates the connection to a pigpio daemon and releases
427 resources used by the library.
428 
429 . .
430 pi: >=0 (as returned by [*pigpio_start*]).
431 . .
432 D*/
433 
434 /*F*/
435 int set_mode(int pi, unsigned gpio, unsigned mode);
436 /*D
437 Set the GPIO mode.
438 
439 . .
440  pi: >=0 (as returned by [*pigpio_start*]).
441 gpio: 0-53.
442 mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1,
443  PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5.
444 . .
445 
446 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE,
447 or PI_NOT_PERMITTED.
448 D*/
449 
450 /*F*/
451 int get_mode(int pi, unsigned gpio);
452 /*D
453 Get the GPIO mode.
454 
455 . .
456  pi: >=0 (as returned by [*pigpio_start*]).
457 gpio: 0-53.
458 . .
459 
460 Returns the GPIO mode if OK, otherwise PI_BAD_GPIO.
461 D*/
462 
463 /*F*/
464 int set_pull_up_down(int pi, unsigned gpio, unsigned pud);
465 /*D
466 Set or clear the GPIO pull-up/down resistor.
467 
468 . .
469  pi: >=0 (as returned by [*pigpio_start*]).
470 gpio: 0-53.
471  pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF.
472 . .
473 
474 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD,
475 or PI_NOT_PERMITTED.
476 D*/
477 
478 /*F*/
479 int gpio_read(int pi, unsigned gpio);
480 /*D
481 Read the GPIO level.
482 
483 . .
484  pi: >=0 (as returned by [*pigpio_start*]).
485 gpio:0-53.
486 . .
487 
488 Returns the GPIO level if OK, otherwise PI_BAD_GPIO.
489 D*/
490 
491 /*F*/
492 int gpio_write(int pi, unsigned gpio, unsigned level);
493 /*D
494 Write the GPIO level.
495 
496 . .
497  pi: >=0 (as returned by [*pigpio_start*]).
498  gpio: 0-53.
499 level: 0, 1.
500 . .
501 
502 Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL,
503 or PI_NOT_PERMITTED.
504 
505 Notes
506 
507 If PWM or servo pulses are active on the GPIO they are switched off.
508 D*/
509 
510 /*F*/
511 int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle);
512 /*D
513 Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO.
514 
515 . .
516  pi: >=0 (as returned by [*pigpio_start*]).
517 user_gpio: 0-31.
518 dutycycle: 0-range (range defaults to 255).
519 . .
520 
521 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE,
522 or PI_NOT_PERMITTED.
523 Notes
524 
525 The [*set_PWM_range*] function may be used to change the
526 default range of 255.
527 D*/
528 
529 /*F*/
530 int get_PWM_dutycycle(int pi, unsigned user_gpio);
531 /*D
532 Return the PWM dutycycle in use on a GPIO.
533 
534 . .
535  pi: >=0 (as returned by [*pigpio_start*]).
536 user_gpio: 0-31.
537 . .
538 
539 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO.
540 
541 For normal PWM the dutycycle will be out of the defined range
542 for the GPIO (see [*get_PWM_range*]).
543 
544 If a hardware clock is active on the GPIO the reported dutycycle
545 will be 500000 (500k) out of 1000000 (1M).
546 
547 If hardware PWM is active on the GPIO the reported dutycycle
548 will be out of a 1000000 (1M).
549 D*/
550 
551 /*F*/
552 int set_PWM_range(int pi, unsigned user_gpio, unsigned range);
553 /*D
554 Set the range of PWM values to be used on the GPIO.
555 
556 . .
557  pi: >=0 (as returned by [*pigpio_start*]).
558 user_gpio: 0-31.
559  range: 25-40000.
560 . .
561 
562 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE,
563 or PI_NOT_PERMITTED.
564 
565 Notes
566 
567 If PWM is currently active on the GPIO its dutycycle will be
568 scaled to reflect the new range.
569 
570 The real range, the number of steps between fully off and fully on
571 for each of the 18 available GPIO frequencies is
572 
573 . .
574  25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6),
575  400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12),
576 2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18)
577 . .
578 
579 The real value set by set_PWM_range is (dutycycle * real range) / range.
580 D*/
581 
582 /*F*/
583 int get_PWM_range(int pi, unsigned user_gpio);
584 /*D
585 Get the range of PWM values being used on the GPIO.
586 
587 . .
588  pi: >=0 (as returned by [*pigpio_start*]).
589 user_gpio: 0-31.
590 . .
591 
592 Returns the dutycycle range used for the GPIO if OK,
593 otherwise PI_BAD_USER_GPIO.
594 
595 If a hardware clock or hardware PWM is active on the GPIO the
596 reported range will be 1000000 (1M).
597 D*/
598 
599 /*F*/
600 int get_PWM_real_range(int pi, unsigned user_gpio);
601 /*D
602 Get the real underlying range of PWM values being used on the GPIO.
603 
604 . .
605  pi: >=0 (as returned by [*pigpio_start*]).
606 user_gpio: 0-31.
607 . .
608 
609 Returns the real range used for the GPIO if OK,
610 otherwise PI_BAD_USER_GPIO.
611 
612 If a hardware clock is active on the GPIO the reported
613 real range will be 1000000 (1M).
614 
615 If hardware PWM is active on the GPIO the reported real range
616 will be approximately 250M divided by the set PWM frequency.
617 
618 D*/
619 
620 /*F*/
621 int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency);
622 /*D
623 Set the frequency (in Hz) of the PWM to be used on the GPIO.
624 
625 . .
626  pi: >=0 (as returned by [*pigpio_start*]).
627 user_gpio: 0-31.
628 frequency: >=0 (Hz).
629 . .
630 
631 Returns the numerically closest frequency if OK, otherwise
632 PI_BAD_USER_GPIO or PI_NOT_PERMITTED.
633 
634 If PWM is currently active on the GPIO it will be switched
635 off and then back on at the new frequency.
636 
637 Each GPIO can be independently set to one of 18 different
638 PWM frequencies.
639 
640 The selectable frequencies depend upon the sample rate which
641 may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The
642 sample rate is set when the pigpio daemon is started.
643 
644 The frequencies for each sample rate are:
645 
646 . .
647  Hertz
648 
649  1: 40000 20000 10000 8000 5000 4000 2500 2000 1600
650  1250 1000 800 500 400 250 200 100 50
651 
652  2: 20000 10000 5000 4000 2500 2000 1250 1000 800
653  625 500 400 250 200 125 100 50 25
654 
655  4: 10000 5000 2500 2000 1250 1000 625 500 400
656  313 250 200 125 100 63 50 25 13
657 sample
658  rate
659  (us) 5: 8000 4000 2000 1600 1000 800 500 400 320
660  250 200 160 100 80 50 40 20 10
661 
662  8: 5000 2500 1250 1000 625 500 313 250 200
663  156 125 100 63 50 31 25 13 6
664 
665  10: 4000 2000 1000 800 500 400 250 200 160
666  125 100 80 50 40 25 20 10 5
667 . .
668 D*/
669 
670 /*F*/
671 int get_PWM_frequency(int pi, unsigned user_gpio);
672 /*D
673 Get the frequency of PWM being used on the GPIO.
674 
675 . .
676  pi: >=0 (as returned by [*pigpio_start*]).
677 user_gpio: 0-31.
678 . .
679 
680 For normal PWM the frequency will be that defined for the GPIO by
681 [*set_PWM_frequency*].
682 
683 If a hardware clock is active on the GPIO the reported frequency
684 will be that set by [*hardware_clock*].
685 
686 If hardware PWM is active on the GPIO the reported frequency
687 will be that set by [*hardware_PWM*].
688 
689 Returns the frequency (in hertz) used for the GPIO if OK,
690 otherwise PI_BAD_USER_GPIO.
691 D*/
692 
693 /*F*/
694 int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth);
695 /*D
696 Start (500-2500) or stop (0) servo pulses on the GPIO.
697 
698 . .
699  pi: >=0 (as returned by [*pigpio_start*]).
700  user_gpio: 0-31.
701 pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise).
702 . .
703 
704 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or
705 PI_NOT_PERMITTED.
706 
707 The selected pulsewidth will continue to be transmitted until
708 changed by a subsequent call to set_servo_pulsewidth.
709 
710 The pulsewidths supported by servos varies and should probably be
711 determined by experiment. A value of 1500 should always be safe and
712 represents the mid-point of rotation.
713 
714 You can DAMAGE a servo if you command it to move beyond its limits.
715 
716 OTHER UPDATE RATES:
717 
718 This function updates servos at 50Hz. If you wish to use a different
719 update frequency you will have to use the PWM functions.
720 
721 . .
722 Update Rate (Hz) 50 100 200 400 500
723 1E6/Hz 20000 10000 5000 2500 2000
724 . .
725 
726 Firstly set the desired PWM frequency using [*set_PWM_frequency*].
727 
728 Then set the PWM range using [*set_PWM_range*] to 1E6/Hz.
729 Doing this allows you to use units of microseconds when setting
730 the servo pulsewidth.
731 
732 E.g. If you want to update a servo connected to GPIO 25 at 400Hz
733 
734 . .
735 set_PWM_frequency(25, 400);
736 set_PWM_range(25, 2500);
737 . .
738 
739 Thereafter use the [*set_PWM_dutycycle*] function to move the servo,
740 e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse.
741 D*/
742 
743 /*F*/
744 int get_servo_pulsewidth(int pi, unsigned user_gpio);
745 /*D
746 Return the servo pulsewidth in use on a GPIO.
747 
748 . .
749  pi: >=0 (as returned by [*pigpio_start*]).
750 user_gpio: 0-31.
751 . .
752 
753 Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO.
754 D*/
755 
756 /*F*/
757 int notify_open(int pi);
758 /*D
759 Get a free notification handle.
760 
761 . .
762 pi: >=0 (as returned by [*pigpio_start*]).
763 . .
764 
765 Returns a handle greater than or equal to zero if OK,
766 otherwise PI_NO_HANDLE.
767 
768 A notification is a method for being notified of GPIO state
769 changes via a pipe.
770 
771 Pipes are only accessible from the local machine so this function
772 serves no purpose if you are using the library from a remote machine.
773 The in-built (socket) notifications provided by [*callback*]
774 should be used instead.
775 
776 Notifications for handle x will be available at the pipe
777 named /dev/pigpiox (where x is the handle number).
778 E.g. if the function returns 15 then the notifications must be
779 read from /dev/pigpio15.
780 D*/
781 
782 /*F*/
783 int notify_begin(int pi, unsigned handle, uint32_t bits);
784 /*D
785 Start notifications on a previously opened handle.
786 
787 . .
788  pi: >=0 (as returned by [*pigpio_start*]).
789 handle: 0-31 (as returned by [*notify_open*])
790  bits: a mask indicating the GPIO to be notified.
791 . .
792 
793 Returns 0 if OK, otherwise PI_BAD_HANDLE.
794 
795 The notification sends state changes for each GPIO whose
796 corresponding bit in bits is set.
797 
798 Each notification occupies 12 bytes in the fifo as follows:
799 
800 . .
801 typedef struct
802 {
803  uint16_t seqno;
804  uint16_t flags;
805  uint32_t tick;
806  uint32_t level;
807 } gpioReport_t;
808 . .
809 
810 seqno: starts at 0 each time the handle is opened and then increments
811 by one for each report.
812 
813 flags: three flags are defined, PI_NTFY_FLAGS_WDOG,
814 PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT.
815 
816 If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags
817 indicate a GPIO which has had a watchdog timeout.
818 
819 If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive
820 signal on the pipe/socket and is sent once a minute in the absence
821 of other notification activity.
822 
823 If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags
824 indicate an event which has been triggered.
825 
826 tick: the number of microseconds since system boot. It wraps around
827 after 1h12m.
828 
829 level: indicates the level of each GPIO. If bit 1<<x is set then
830 GPIO x is high.
831 D*/
832 
833 /*F*/
834 int notify_pause(int pi, unsigned handle);
835 /*D
836 Pause notifications on a previously opened handle.
837 
838 . .
839  pi: >=0 (as returned by [*pigpio_start*]).
840 handle: 0-31 (as returned by [*notify_open*])
841 . .
842 
843 Returns 0 if OK, otherwise PI_BAD_HANDLE.
844 
845 Notifications for the handle are suspended until
846 [*notify_begin*] is called again.
847 D*/
848 
849 /*F*/
850 int notify_close(int pi, unsigned handle);
851 /*D
852 Stop notifications on a previously opened handle and
853 release the handle for reuse.
854 
855 . .
856  pi: >=0 (as returned by [*pigpio_start*]).
857 handle: 0-31 (as returned by [*notify_open*])
858 . .
859 
860 Returns 0 if OK, otherwise PI_BAD_HANDLE.
861 D*/
862 
863 /*F*/
864 int set_watchdog(int pi, unsigned user_gpio, unsigned timeout);
865 /*D
866 Sets a watchdog for a GPIO.
867 
868 . .
869  pi: >=0 (as returned by [*pigpio_start*]).
870 user_gpio: 0-31.
871  timeout: 0-60000.
872 . .
873 
874 Returns 0 if OK, otherwise PI_BAD_USER_GPIO
875 or PI_BAD_WDOG_TIMEOUT.
876 
877 The watchdog is nominally in milliseconds.
878 
879 Only one watchdog may be registered per GPIO.
880 
881 The watchdog may be cancelled by setting timeout to 0.
882 
883 Once a watchdog has been started callbacks for the GPIO will be
884 triggered every timeout interval after the last GPIO activity.
885 
886 The callback will receive the special level PI_TIMEOUT.
887 D*/
888 
889 /*F*/
890 int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady);
891 /*D
892 Sets a glitch filter on a GPIO.
893 
894 Level changes on the GPIO are not reported unless the level
895 has been stable for at least [*steady*] microseconds. The
896 level is then reported. Level changes of less than
897 [*steady*] microseconds are ignored.
898 
899 . .
900  pi: >=0 (as returned by [*pigpio_start*]).
901 user_gpio: 0-31
902  steady: 0-300000
903 . .
904 
905 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
906 
907 This filter affects the GPIO samples returned to callbacks set up
908 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
909 
910 It does not affect levels read by [*gpio_read*],
911 [*read_bank_1*], or [*read_bank_2*].
912 
913 Each (stable) edge will be timestamped [*steady*] microseconds
914 after it was first detected.
915 D*/
916 
917 /*F*/
918 int set_noise_filter(
919  int pi, unsigned user_gpio, unsigned steady, unsigned active);
920 /*D
921 Sets a noise filter on a GPIO.
922 
923 Level changes on the GPIO are ignored until a level which has
924 been stable for [*steady*] microseconds is detected. Level changes
925 on the GPIO are then reported for [*active*] microseconds after
926 which the process repeats.
927 
928 . .
929  pi: >=0 (as returned by [*pigpio_start*]).
930 user_gpio: 0-31
931  steady: 0-300000
932  active: 0-1000000
933 . .
934 
935 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER.
936 
937 This filter affects the GPIO samples returned to callbacks set up
938 with [*callback*], [*callback_ex*] and [*wait_for_edge*].
939 
940 It does not affect levels read by [*gpio_read*],
941 [*read_bank_1*], or [*read_bank_2*].
942 
943 Level changes before and after the active period may
944 be reported. Your software must be designed to cope with
945 such reports.
946 D*/
947 
948 /*F*/
949 uint32_t read_bank_1(int pi);
950 /*D
951 Read the levels of the bank 1 GPIO (GPIO 0-31).
952 
953 . .
954 pi: >=0 (as returned by [*pigpio_start*]).
955 . .
956 
957 The returned 32 bit integer has a bit set if the corresponding
958 GPIO is logic 1. GPIO n has bit value (1<<n).
959 D*/
960 
961 /*F*/
962 uint32_t read_bank_2(int pi);
963 /*D
964 Read the levels of the bank 2 GPIO (GPIO 32-53).
965 
966 . .
967 pi: >=0 (as returned by [*pigpio_start*]).
968 . .
969 
970 The returned 32 bit integer has a bit set if the corresponding
971 GPIO is logic 1. GPIO n has bit value (1<<(n-32)).
972 D*/
973 
974 /*F*/
975 int clear_bank_1(int pi, uint32_t bits);
976 /*D
977 Clears GPIO 0-31 if the corresponding bit in bits is set.
978 
979 . .
980  pi: >=0 (as returned by [*pigpio_start*]).
981 bits: a bit mask with 1 set if the corresponding GPIO is
982  to be cleared.
983 . .
984 
985 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
986 
987 A status of PI_SOME_PERMITTED indicates that the user is not
988 allowed to write to one or more of the GPIO.
989 D*/
990 
991 /*F*/
992 int clear_bank_2(int pi, uint32_t bits);
993 /*D
994 Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set.
995 
996 . .
997  pi: >=0 (as returned by [*pigpio_start*]).
998 bits: a bit mask with 1 set if the corresponding GPIO is
999  to be cleared.
1000 . .
1001 
1002 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
1003 
1004 A status of PI_SOME_PERMITTED indicates that the user is not
1005 allowed to write to one or more of the GPIO.
1006 D*/
1007 
1008 /*F*/
1009 int set_bank_1(int pi, uint32_t bits);
1010 /*D
1011 Sets GPIO 0-31 if the corresponding bit in bits is set.
1012 
1013 . .
1014  pi: >=0 (as returned by [*pigpio_start*]).
1015 bits: a bit mask with 1 set if the corresponding GPIO is
1016  to be set.
1017 . .
1018 
1019 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
1020 
1021 A status of PI_SOME_PERMITTED indicates that the user is not
1022 allowed to write to one or more of the GPIO.
1023 D*/
1024 
1025 /*F*/
1026 int set_bank_2(int pi, uint32_t bits);
1027 /*D
1028 Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set.
1029 
1030 . .
1031  pi: >=0 (as returned by [*pigpio_start*]).
1032 bits: a bit mask with 1 set if the corresponding GPIO is
1033  to be set.
1034 . .
1035 
1036 Returns 0 if OK, otherwise PI_SOME_PERMITTED.
1037 
1038 A status of PI_SOME_PERMITTED indicates that the user is not
1039 allowed to write to one or more of the GPIO.
1040 D*/
1041 
1042 
1043 /*F*/
1044 int hardware_clock(int pi, unsigned gpio, unsigned clkfreq);
1045 /*D
1046 Starts a hardware clock on a GPIO at the specified frequency.
1047 Frequencies above 30MHz are unlikely to work.
1048 
1049 . .
1050  pi: >=0 (as returned by [*pigpio_start*]).
1051  gpio: see description
1052 frequency: 0 (off) or 4689-250000000 (250M)
1053 . .
1054 
1055 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
1056 PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS.
1057 
1058 The same clock is available on multiple GPIO. The latest
1059 frequency setting will be used by all GPIO which share a clock.
1060 
1061 The GPIO must be one of the following.
1062 
1063 . .
1064 4 clock 0 All models
1065 5 clock 1 All models but A and B (reserved for system use)
1066 6 clock 2 All models but A and B
1067 20 clock 0 All models but A and B
1068 21 clock 1 All models but A and Rev.2 B (reserved for system use)
1069 
1070 32 clock 0 Compute module only
1071 34 clock 0 Compute module only
1072 42 clock 1 Compute module only (reserved for system use)
1073 43 clock 2 Compute module only
1074 44 clock 1 Compute module only (reserved for system use)
1075 . .
1076 
1077 Access to clock 1 is protected by a password as its use will likely
1078 crash the Pi. The password is given by or'ing 0x5A000000 with the
1079 GPIO number.
1080 D*/
1081 
1082 
1083 /*F*/
1084 int hardware_PWM(int pi, unsigned gpio, unsigned PWMfreq, uint32_t PWMduty);
1085 /*D
1086 Starts hardware PWM on a GPIO at the specified frequency and dutycycle.
1087 Frequencies above 30MHz are unlikely to work.
1088 
1089 NOTE: Any waveform started by [*wave_send_**] or [*wave_chain*]
1090 will be cancelled.
1091 
1092 This function is only valid if the pigpio main clock is PCM. The
1093 main clock defaults to PCM but may be overridden when the pigpio
1094 daemon is started (option -t).
1095 
1096 . .
1097  pi: >=0 (as returned by [*pigpio_start*]).
1098  gpio: see descripton
1099 PWMfreq: 0 (off) or 1-125000000 (125M)
1100 PWMduty: 0 (off) to 1000000 (1M)(fully on)
1101 . .
1102 
1103 Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO,
1104 PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ,
1105 or PI_HPWM_ILLEGAL.
1106 
1107 The same PWM channel is available on multiple GPIO. The latest
1108 frequency and dutycycle setting will be used by all GPIO which
1109 share a PWM channel.
1110 
1111 The GPIO must be one of the following.
1112 
1113 . .
1114 12 PWM channel 0 All models but A and B
1115 13 PWM channel 1 All models but A and B
1116 18 PWM channel 0 All models
1117 19 PWM channel 1 All models but A and B
1118 
1119 40 PWM channel 0 Compute module only
1120 41 PWM channel 1 Compute module only
1121 45 PWM channel 1 Compute module only
1122 52 PWM channel 0 Compute module only
1123 53 PWM channel 1 Compute module only
1124 . .
1125 
1126 The actual number of steps beween off and fully on is the
1127 integral part of 250 million divided by PWMfreq.
1128 
1129 The actual frequency set is 250 million / steps.
1130 
1131 There will only be a million steps for a PWMfreq of 250.
1132 Lower frequencies will have more steps and higher
1133 frequencies will have fewer steps. PWMduty is
1134 automatically scaled to take this into account.
1135 D*/
1136 
1137 
1138 /*F*/
1139 uint32_t get_current_tick(int pi);
1140 /*D
1141 Gets the current system tick.
1142 
1143 . .
1144 pi: >=0 (as returned by [*pigpio_start*]).
1145 . .
1146 
1147 Tick is the number of microseconds since system boot.
1148 
1149 As tick is an unsigned 32 bit quantity it wraps around after
1150 2**32 microseconds, which is approximately 1 hour 12 minutes.
1151 
1152 D*/
1153 
1154 /*F*/
1155 uint32_t get_hardware_revision(int pi);
1156 /*D
1157 Get the Pi's hardware revision number.
1158 
1159 . .
1160 pi: >=0 (as returned by [*pigpio_start*]).
1161 . .
1162 
1163 The hardware revision is the last few characters on the Revision line
1164 of /proc/cpuinfo.
1165 
1166 If the hardware revision can not be found or is not a valid
1167 hexadecimal number the function returns 0.
1168 
1169 The revision number can be used to determine the assignment of GPIO
1170 to pins (see [*gpio*]).
1171 
1172 There are at least three types of board.
1173 
1174 Type 1 boards have hardware revision numbers of 2 and 3.
1175 
1176 Type 2 boards have hardware revision numbers of 4, 5, 6, and 15.
1177 
1178 Type 3 boards have hardware revision numbers of 16 or greater.
1179 D*/
1180 
1181 /*F*/
1182 uint32_t get_pigpio_version(int pi);
1183 /*D
1184 Returns the pigpio version.
1185 
1186 . .
1187 pi: >=0 (as returned by [*pigpio_start*]).
1188 . .
1189 D*/
1190 
1191 
1192 /*F*/
1193 int wave_clear(int pi);
1194 /*D
1195 This function clears all waveforms and any data added by calls to the
1196 [*wave_add_**] functions.
1197 
1198 . .
1199 pi: >=0 (as returned by [*pigpio_start*]).
1200 . .
1201 
1202 Returns 0 if OK.
1203 D*/
1204 
1205 /*F*/
1206 int wave_add_new(int pi);
1207 /*D
1208 This function starts a new empty waveform. You wouldn't normally need
1209 to call this function as it is automatically called after a waveform is
1210 created with the [*wave_create*] function.
1211 
1212 . .
1213 pi: >=0 (as returned by [*pigpio_start*]).
1214 . .
1215 
1216 Returns 0 if OK.
1217 D*/
1218 
1219 /*F*/
1220 int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses);
1221 /*D
1222 This function adds a number of pulses to the current waveform.
1223 
1224 . .
1225  pi: >=0 (as returned by [*pigpio_start*]).
1226 numPulses: the number of pulses.
1227  pulses: an array of pulses.
1228 . .
1229 
1230 Returns the new total number of pulses in the current waveform if OK,
1231 otherwise PI_TOO_MANY_PULSES.
1232 
1233 The pulses are interleaved in time order within the existing waveform
1234 (if any).
1235 
1236 Merging allows the waveform to be built in parts, that is the settings
1237 for GPIO#1 can be added, and then GPIO#2 etc.
1238 
1239 If the added waveform is intended to start after or within the existing
1240 waveform then the first pulse should consist solely of a delay.
1241 D*/
1242 
1243 /*F*/
1244 int wave_add_serial
1245  (int pi, unsigned user_gpio, unsigned baud, unsigned data_bits,
1246  unsigned stop_bits, unsigned offset, unsigned numBytes, char *str);
1247 /*D
1248 This function adds a waveform representing serial data to the
1249 existing waveform (if any). The serial data starts offset
1250 microseconds from the start of the waveform.
1251 
1252 . .
1253  pi: >=0 (as returned by [*pigpio_start*]).
1254 user_gpio: 0-31.
1255  baud: 50-1000000
1256 data_bits: number of data bits (1-32)
1257 stop_bits: number of stop half bits (2-8)
1258  offset: >=0
1259  numBytes: >=1
1260  str: an array of chars.
1261 . .
1262 
1263 Returns the new total number of pulses in the current waveform if OK,
1264 otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS,
1265 PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET,
1266 or PI_TOO_MANY_PULSES.
1267 
1268 NOTES:
1269 
1270 The serial data is formatted as one start bit, [*data_bits*] data bits,
1271 and [*stop_bits*]/2 stop bits.
1272 
1273 It is legal to add serial data streams with different baud rates to
1274 the same waveform.
1275 
1276 [*numBytes*] is the number of bytes of data in str.
1277 
1278 The bytes required for each character depend upon [*data_bits*].
1279 
1280 For [*data_bits*] 1-8 there will be one byte per character.
1281 For [*data_bits*] 9-16 there will be two bytes per character.
1282 For [*data_bits*] 17-32 there will be four bytes per character.
1283 D*/
1284 
1285 /*F*/
1286 int wave_create(int pi);
1287 /*D
1288 This function creates a waveform from the data provided by the prior
1289 calls to the [*wave_add_**] functions. Upon success a wave id
1290 greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM,
1291 PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID.
1292 
1293 . .
1294 pi: >=0 (as returned by [*pigpio_start*]).
1295 . .
1296 
1297 The data provided by the [*wave_add_**] functions is consumed by this
1298 function.
1299 
1300 As many waveforms may be created as there is space available. The
1301 wave id is passed to [*wave_send_**] to specify the waveform to transmit.
1302 
1303 Normal usage would be
1304 
1305 Step 1. [*wave_clear*] to clear all waveforms and added data.
1306 
1307 Step 2. [*wave_add_**] calls to supply the waveform data.
1308 
1309 Step 3. [*wave_create*] to create the waveform and get a unique id
1310 
1311 Repeat steps 2 and 3 as needed.
1312 
1313 Step 4. [*wave_send_**] with the id of the waveform to transmit.
1314 
1315 A waveform comprises one or more pulses. Each pulse consists of a
1316 [*gpioPulse_t*] structure.
1317 
1318 . .
1319 typedef struct
1320 {
1321  uint32_t gpioOn;
1322  uint32_t gpioOff;
1323  uint32_t usDelay;
1324 } gpioPulse_t;
1325 . .
1326 
1327 The fields specify
1328 
1329 1) the GPIO to be switched on at the start of the pulse.
1330 2) the GPIO to be switched off at the start of the pulse.
1331 3) the delay in microseconds before the next pulse.
1332 
1333 Any or all the fields can be zero. It doesn't make any sense to
1334 set all the fields to zero (the pulse will be ignored).
1335 
1336 When a waveform is started each pulse is executed in order with the
1337 specified delay between the pulse and the next.
1338 
1339 Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM,
1340 PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL.
1341 D*/
1342 
1343 
1344 /*F*/
1345 int wave_delete(int pi, unsigned wave_id);
1346 /*D
1347 This function deletes the waveform with id wave_id.
1348 
1349 . .
1350  pi: >=0 (as returned by [*pigpio_start*]).
1351 wave_id: >=0, as returned by [*wave_create*].
1352 . .
1353 
1354 Wave ids are allocated in order, 0, 1, 2, etc.
1355 
1356 The wave is flagged for deletion. The resources used by the wave
1357 will only be reused when either of the following apply.
1358 
1359 - all waves with higher numbered wave ids have been deleted or have
1360 been flagged for deletion.
1361 
1362 - a new wave is created which uses exactly the same resources as
1363 the current wave (see the C source for gpioWaveCreate for details).
1364 
1365 Returns 0 if OK, otherwise PI_BAD_WAVE_ID.
1366 D*/
1367 
1368 
1369 /*F*/
1370 int wave_send_once(int pi, unsigned wave_id);
1371 /*D
1372 This function transmits the waveform with id wave_id. The waveform
1373 is sent once.
1374 
1375 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1376 
1377 . .
1378  pi: >=0 (as returned by [*pigpio_start*]).
1379 wave_id: >=0, as returned by [*wave_create*].
1380 . .
1381 
1382 Returns the number of DMA control blocks in the waveform if OK,
1383 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
1384 D*/
1385 
1386 
1387 /*F*/
1388 int wave_send_repeat(int pi, unsigned wave_id);
1389 /*D
1390 This function transmits the waveform with id wave_id. The waveform
1391 cycles until cancelled (either by the sending of a new waveform or
1392 by [*wave_tx_stop*]).
1393 
1394 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1395 
1396 . .
1397  pi: >=0 (as returned by [*pigpio_start*]).
1398 wave_id: >=0, as returned by [*wave_create*].
1399 . .
1400 
1401 Returns the number of DMA control blocks in the waveform if OK,
1402 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
1403 D*/
1404 
1405 
1406 /*F*/
1407 int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode);
1408 /*D
1409 Transmits the waveform with id wave_id using mode mode.
1410 
1411 . .
1412  pi: >=0 (as returned by [*pigpio_start*]).
1413 wave_id: >=0, as returned by [*wave_create*].
1414  mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT,
1415  PI_WAVE_MODE_ONE_SHOT_SYNC, or PI_WAVE_MODE_REPEAT_SYNC.
1416 . .
1417 
1418 PI_WAVE_MODE_ONE_SHOT: same as [*wave_send_once*].
1419 
1420 PI_WAVE_MODE_REPEAT same as [*wave_send_repeat*].
1421 
1422 PI_WAVE_MODE_ONE_SHOT_SYNC same as [*wave_send_once*] but tries
1423 to sync with the previous waveform.
1424 
1425 PI_WAVE_MODE_REPEAT_SYNC same as [*wave_send_repeat*] but tries
1426 to sync with the previous waveform.
1427 
1428 WARNING: bad things may happen if you delete the previous
1429 waveform before it has been synced to the new waveform.
1430 
1431 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1432 
1433 Returns the number of DMA control blocks in the waveform if OK,
1434 otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE.
1435 D*/
1436 
1437 /*F*/
1438 int wave_chain(int pi, char *buf, unsigned bufSize);
1439 /*D
1440 This function transmits a chain of waveforms.
1441 
1442 NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled.
1443 
1444 The waves to be transmitted are specified by the contents of buf
1445 which contains an ordered list of [*wave_id*]s and optional command
1446 codes and related data.
1447 
1448 . .
1449  pi: >=0 (as returned by [*pigpio_start*]).
1450  buf: pointer to the wave_ids and optional command codes
1451 bufSize: the number of bytes in buf
1452 . .
1453 
1454 Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER,
1455 PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID.
1456 
1457 Each wave is transmitted in the order specified. A wave may
1458 occur multiple times per chain.
1459 
1460 A blocks of waves may be transmitted multiple times by using
1461 the loop commands. The block is bracketed by loop start and
1462 end commands. Loops may be nested.
1463 
1464 Delays between waves may be added with the delay command.
1465 
1466 The following command codes are supported:
1467 
1468 Name @ Cmd & Data @ Meaning
1469 Loop Start @ 255 0 @ Identify start of a wave block
1470 Loop Repeat @ 255 1 x y @ loop x + y*256 times
1471 Delay @ 255 2 x y @ delay x + y*256 microseconds
1472 Loop Forever @ 255 3 @ loop forever
1473 
1474 If present Loop Forever must be the last entry in the chain.
1475 
1476 The code is currently dimensioned to support a chain with roughly
1477 600 entries and 20 loop counters.
1478 
1479 ...
1480 #include <stdio.h>
1481 #include <pigpiod_if2.h>
1482 
1483 #define WAVES 5
1484 #define GPIO 4
1485 
1486 int main(int argc, char *argv[])
1487 {
1488  int i, pi, wid[WAVES];
1489 
1490  pi = pigpio_start(0, 0);
1491  if (pi<0) return -1;
1492 
1493  set_mode(pi, GPIO, PI_OUTPUT);
1494 
1495  for (i=0; i<WAVES; i++)
1496  {
1497  wave_add_generic(pi, 2, (gpioPulse_t[])
1498  {{1<<GPIO, 0, 20},
1499  {0, 1<<GPIO, (i+1)*200}});
1500 
1501  wid[i] = wave_create(pi);
1502  }
1503 
1504  wave_chain(pi, (char []) {
1505  wid[4], wid[3], wid[2], // transmit waves 4+3+2
1506  255, 0, // loop start
1507  wid[0], wid[0], wid[0], // transmit waves 0+0+0
1508  255, 0, // loop start
1509  wid[0], wid[1], // transmit waves 0+1
1510  255, 2, 0x88, 0x13, // delay 5000us
1511  255, 1, 30, 0, // loop end (repeat 30 times)
1512  255, 0, // loop start
1513  wid[2], wid[3], wid[0], // transmit waves 2+3+0
1514  wid[3], wid[1], wid[2], // transmit waves 3+1+2
1515  255, 1, 10, 0, // loop end (repeat 10 times)
1516  255, 1, 5, 0, // loop end (repeat 5 times)
1517  wid[4], wid[4], wid[4], // transmit waves 4+4+4
1518  255, 2, 0x20, 0x4E, // delay 20000us
1519  wid[0], wid[0], wid[0], // transmit waves 0+0+0
1520 
1521  }, 46);
1522 
1523  while (wave_tx_busy(pi)) time_sleep(0.1);
1524 
1525  for (i=0; i<WAVES; i++) wave_delete(pi, wid[i]);
1526 
1527  pigpio_stop(pi);
1528 }
1529 ...
1530 D*/
1531 
1532 
1533 /*F*/
1534 int wave_tx_at(int pi);
1535 /*D
1536 This function returns the id of the waveform currently being
1537 transmitted.
1538 
1539 . .
1540 pi: >=0 (as returned by [*pigpio_start*]).
1541 . .
1542 
1543 Returns the waveform id or one of the following special values:
1544 
1545 PI_WAVE_NOT_FOUND (9998) - transmitted wave not found.
1546 PI_NO_TX_WAVE (9999) - no wave being transmitted.
1547 D*/
1548 
1549 /*F*/
1550 int wave_tx_busy(int pi);
1551 /*D
1552 This function checks to see if a waveform is currently being
1553 transmitted.
1554 
1555 . .
1556 pi: >=0 (as returned by [*pigpio_start*]).
1557 . .
1558 
1559 Returns 1 if a waveform is currently being transmitted, otherwise 0.
1560 D*/
1561 
1562 /*F*/
1563 int wave_tx_stop(int pi);
1564 /*D
1565 This function stops the transmission of the current waveform.
1566 
1567 . .
1568 pi: >=0 (as returned by [*pigpio_start*]).
1569 . .
1570 
1571 Returns 0 if OK.
1572 
1573 This function is intended to stop a waveform started with the repeat mode.
1574 D*/
1575 
1576 /*F*/
1577 int wave_get_micros(int pi);
1578 /*D
1579 This function returns the length in microseconds of the current
1580 waveform.
1581 
1582 . .
1583 pi: >=0 (as returned by [*pigpio_start*]).
1584 . .
1585 D*/
1586 
1587 /*F*/
1588 int wave_get_high_micros(int pi);
1589 /*D
1590 This function returns the length in microseconds of the longest waveform
1591 created since the pigpio daemon was started.
1592 
1593 . .
1594 pi: >=0 (as returned by [*pigpio_start*]).
1595 . .
1596 D*/
1597 
1598 /*F*/
1599 int wave_get_max_micros(int pi);
1600 /*D
1601 This function returns the maximum possible size of a waveform in
1602 microseconds.
1603 
1604 . .
1605 pi: >=0 (as returned by [*pigpio_start*]).
1606 . .
1607 D*/
1608 
1609 /*F*/
1610 int wave_get_pulses(int pi);
1611 /*D
1612 This function returns the length in pulses of the current waveform.
1613 
1614 . .
1615 pi: >=0 (as returned by [*pigpio_start*]).
1616 . .
1617 D*/
1618 
1619 /*F*/
1620 int wave_get_high_pulses(int pi);
1621 /*D
1622 This function returns the length in pulses of the longest waveform
1623 created since the pigpio daemon was started.
1624 
1625 . .
1626 pi: >=0 (as returned by [*pigpio_start*]).
1627 . .
1628 D*/
1629 
1630 /*F*/
1631 int wave_get_max_pulses(int pi);
1632 /*D
1633 This function returns the maximum possible size of a waveform in pulses.
1634 
1635 . .
1636 pi: >=0 (as returned by [*pigpio_start*]).
1637 . .
1638 D*/
1639 
1640 /*F*/
1641 int wave_get_cbs(int pi);
1642 /*D
1643 This function returns the length in DMA control blocks of the current
1644 waveform.
1645 
1646 . .
1647 pi: >=0 (as returned by [*pigpio_start*]).
1648 . .
1649 D*/
1650 
1651 /*F*/
1652 int wave_get_high_cbs(int pi);
1653 /*D
1654 This function returns the length in DMA control blocks of the longest
1655 waveform created since the pigpio daemon was started.
1656 
1657 . .
1658 pi: >=0 (as returned by [*pigpio_start*]).
1659 . .
1660 D*/
1661 
1662 /*F*/
1663 int wave_get_max_cbs(int pi);
1664 /*D
1665 This function returns the maximum possible size of a waveform in DMA
1666 control blocks.
1667 
1668 . .
1669 pi: >=0 (as returned by [*pigpio_start*]).
1670 . .
1671 D*/
1672 
1673 /*F*/
1674 int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, unsigned level);
1675 /*D
1676 This function sends a trigger pulse to a GPIO. The GPIO is set to
1677 level for pulseLen microseconds and then reset to not level.
1678 
1679 . .
1680  pi: >=0 (as returned by [*pigpio_start*]).
1681 user_gpio: 0-31.
1682  pulseLen: 1-100.
1683  level: 0,1.
1684 . .
1685 
1686 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL,
1687 PI_BAD_PULSELEN, or PI_NOT_PERMITTED.
1688 D*/
1689 
1690 /*F*/
1691 int store_script(int pi, char *script);
1692 /*D
1693 This function stores a script for later execution.
1694 
1695 See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details.
1696 
1697 . .
1698  pi: >=0 (as returned by [*pigpio_start*]).
1699 script: the text of the script.
1700 . .
1701 
1702 The function returns a script id if the script is valid,
1703 otherwise PI_BAD_SCRIPT.
1704 D*/
1705 
1706 /*F*/
1707 int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param);
1708 /*D
1709 This function runs a stored script.
1710 
1711 . .
1712  pi: >=0 (as returned by [*pigpio_start*]).
1713 script_id: >=0, as returned by [*store_script*].
1714  numPar: 0-10, the number of parameters.
1715  param: an array of parameters.
1716 . .
1717 
1718 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
1719 PI_TOO_MANY_PARAM
1720 
1721 param is an array of up to 10 parameters which may be referenced in
1722 the script as p0 to p9.
1723 D*/
1724 
1725 /*F*/
1726 int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param);
1727 /*D
1728 This function sets the parameters of a script. The script may or
1729 may not be running. The first numPar parameters of the script are
1730 overwritten with the new values.
1731 
1732 . .
1733  pi: >=0 (as returned by [*pigpio_start*]).
1734 script_id: >=0, as returned by [*store_script*].
1735  numPar: 0-10, the number of parameters.
1736  param: an array of parameters.
1737 . .
1738 
1739 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or
1740 PI_TOO_MANY_PARAM.
1741 
1742 param is an array of up to 10 parameters which may be referenced in
1743 the script as p0 to p9.
1744 D*/
1745 
1746 /*F*/
1747 int script_status(int pi, unsigned script_id, uint32_t *param);
1748 /*D
1749 This function returns the run status of a stored script as well
1750 as the current values of parameters 0 to 9.
1751 
1752 . .
1753  pi: >=0 (as returned by [*pigpio_start*]).
1754 script_id: >=0, as returned by [*store_script*].
1755  param: an array to hold the returned 10 parameters.
1756 . .
1757 
1758 The function returns greater than or equal to 0 if OK,
1759 otherwise PI_BAD_SCRIPT_ID.
1760 
1761 The run status may be
1762 
1763 . .
1764 PI_SCRIPT_INITING
1765 PI_SCRIPT_HALTED
1766 PI_SCRIPT_RUNNING
1767 PI_SCRIPT_WAITING
1768 PI_SCRIPT_FAILED
1769 . .
1770 
1771 The current value of script parameters 0 to 9 are returned in param.
1772 D*/
1773 
1774 /*F*/
1775 int stop_script(int pi, unsigned script_id);
1776 /*D
1777 This function stops a running script.
1778 
1779 . .
1780  pi: >=0 (as returned by [*pigpio_start*]).
1781 script_id: >=0, as returned by [*store_script*].
1782 . .
1783 
1784 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
1785 D*/
1786 
1787 /*F*/
1788 int delete_script(int pi, unsigned script_id);
1789 /*D
1790 This function deletes a stored script.
1791 
1792 . .
1793  pi: >=0 (as returned by [*pigpio_start*]).
1794 script_id: >=0, as returned by [*store_script*].
1795 . .
1796 
1797 The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID.
1798 D*/
1799 
1800 /*F*/
1801 int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits);
1802 /*D
1803 This function opens a GPIO for bit bang reading of serial data.
1804 
1805 . .
1806  pi: >=0 (as returned by [*pigpio_start*]).
1807 user_gpio: 0-31.
1808  baud: 50-250000
1809 data_bits: 1-32
1810 . .
1811 
1812 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD,
1813 or PI_GPIO_IN_USE.
1814 
1815 The serial data is returned in a cyclic buffer and is read using
1816 bb_serial_read.
1817 
1818 It is the caller's responsibility to read data from the cyclic buffer
1819 in a timely fashion.
1820 D*/
1821 
1822 /*F*/
1823 int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize);
1824 /*D
1825 This function copies up to bufSize bytes of data read from the
1826 bit bang serial cyclic buffer to the buffer starting at buf.
1827 
1828 . .
1829  pi: >=0 (as returned by [*pigpio_start*]).
1830 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1831  buf: an array to receive the read bytes.
1832  bufSize: >=0
1833 . .
1834 
1835 Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO
1836 or PI_NOT_SERIAL_GPIO.
1837 
1838 The bytes returned for each character depend upon the number of
1839 data bits [*data_bits*] specified in the [*bb_serial_read_open*] command.
1840 
1841 For [*data_bits*] 1-8 there will be one byte per character.
1842 For [*data_bits*] 9-16 there will be two bytes per character.
1843 For [*data_bits*] 17-32 there will be four bytes per character.
1844 D*/
1845 
1846 /*F*/
1847 int bb_serial_read_close(int pi, unsigned user_gpio);
1848 /*D
1849 This function closes a GPIO for bit bang reading of serial data.
1850 
1851 . .
1852  pi: >=0 (as returned by [*pigpio_start*]).
1853 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1854 . .
1855 
1856 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO.
1857 D*/
1858 
1859 /*F*/
1860 int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert);
1861 /*D
1862 This function inverts serial logic for big bang serial reads.
1863 
1864 . .
1865  pi: >=0 (as returned by [*pigpio_start*]).
1866 user_gpio: 0-31, previously opened with [*bb_serial_read_open*].
1867  invert: 0-1, 1 invert, 0 normal.
1868 . .
1869 
1870 Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT.
1871 D*/
1872 
1873 /*F*/
1874 int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags);
1875 /*D
1876 This returns a handle for the device at address i2c_addr on bus i2c_bus.
1877 
1878 . .
1879  pi: >=0 (as returned by [*pigpio_start*]).
1880  i2c_bus: >=0.
1881  i2c_addr: 0-0x7F.
1882 i2c_flags: 0.
1883 . .
1884 
1885 No flags are currently defined. This parameter should be set to zero.
1886 
1887 Physically buses 0 and 1 are available on the Pi. Higher numbered buses
1888 will be available if a kernel supported bus multiplexor is being used.
1889 
1890 Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR,
1891 PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED.
1892 
1893 For the SMBus commands the low level transactions are shown at the end
1894 of the function description. The following abbreviations are used.
1895 
1896 . .
1897 S (1 bit) : Start bit
1898 P (1 bit) : Stop bit
1899 Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0.
1900 A, NA (1 bit) : Accept and not accept bit.
1901 Addr (7 bits): I2C 7 bit address.
1902 i2c_reg (8 bits): A byte which often selects a register.
1903 Data (8 bits): A data byte.
1904 Count (8 bits): A byte defining the length of a block operation.
1905 
1906 [..]: Data sent by the device.
1907 . .
1908 D*/
1909 
1910 /*F*/
1911 int i2c_close(int pi, unsigned handle);
1912 /*D
1913 This closes the I2C device associated with the handle.
1914 
1915 . .
1916  pi: >=0 (as returned by [*pigpio_start*]).
1917 handle: >=0, as returned by a call to [*i2c_open*].
1918 . .
1919 
1920 Returns 0 if OK, otherwise PI_BAD_HANDLE.
1921 D*/
1922 
1923 /*F*/
1924 int i2c_write_quick(int pi, unsigned handle, unsigned bit);
1925 /*D
1926 This sends a single bit (in the Rd/Wr bit) to the device associated
1927 with handle.
1928 
1929 . .
1930  pi: >=0 (as returned by [*pigpio_start*]).
1931 handle: >=0, as returned by a call to [*i2c_open*].
1932  bit: 0-1, the value to write.
1933 . .
1934 
1935 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1936 PI_I2C_WRITE_FAILED.
1937 
1938 Quick command. SMBus 2.0 5.5.1
1939 . .
1940 S Addr bit [A] P
1941 . .
1942 D*/
1943 
1944 /*F*/
1945 int i2c_write_byte(int pi, unsigned handle, unsigned bVal);
1946 /*D
1947 This sends a single byte to the device associated with handle.
1948 
1949 . .
1950  pi: >=0 (as returned by [*pigpio_start*]).
1951 handle: >=0, as returned by a call to [*i2c_open*].
1952  bVal: 0-0xFF, the value to write.
1953 . .
1954 
1955 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1956 PI_I2C_WRITE_FAILED.
1957 
1958 Send byte. SMBus 2.0 5.5.2
1959 . .
1960 S Addr Wr [A] bVal [A] P
1961 . .
1962 D*/
1963 
1964 /*F*/
1965 int i2c_read_byte(int pi, unsigned handle);
1966 /*D
1967 This reads a single byte from the device associated with handle.
1968 
1969 . .
1970  pi: >=0 (as returned by [*pigpio_start*]).
1971 handle: >=0, as returned by a call to [*i2c_open*].
1972 . .
1973 
1974 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
1975 or PI_I2C_READ_FAILED.
1976 
1977 Receive byte. SMBus 2.0 5.5.3
1978 . .
1979 S Addr Rd [A] [Data] NA P
1980 . .
1981 D*/
1982 
1983 /*F*/
1985  int pi, unsigned handle, unsigned i2c_reg, unsigned bVal);
1986 /*D
1987 This writes a single byte to the specified register of the device
1988 associated with handle.
1989 
1990 . .
1991  pi: >=0 (as returned by [*pigpio_start*]).
1992  handle: >=0, as returned by a call to [*i2c_open*].
1993 i2c_reg: 0-255, the register to write.
1994  bVal: 0-0xFF, the value to write.
1995 . .
1996 
1997 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
1998 PI_I2C_WRITE_FAILED.
1999 
2000 Write byte. SMBus 2.0 5.5.4
2001 . .
2002 S Addr Wr [A] i2c_reg [A] bVal [A] P
2003 . .
2004 D*/
2005 
2006 /*F*/
2008  int pi, unsigned handle, unsigned i2c_reg, unsigned wVal);
2009 /*D
2010 This writes a single 16 bit word to the specified register of the device
2011 associated with handle.
2012 
2013 . .
2014  pi: >=0 (as returned by [*pigpio_start*]).
2015  handle: >=0, as returned by a call to [*i2c_open*].
2016 i2c_reg: 0-255, the register to write.
2017  wVal: 0-0xFFFF, the value to write.
2018 . .
2019 
2020 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2021 PI_I2C_WRITE_FAILED.
2022 
2023 Write word. SMBus 2.0 5.5.4
2024 . .
2025 S Addr Wr [A] i2c_reg [A] wval_Low [A] wVal_High [A] P
2026 . .
2027 D*/
2028 
2029 /*F*/
2030 int i2c_read_byte_data(int pi, unsigned handle, unsigned i2c_reg);
2031 /*D
2032 This reads a single byte from the specified register of the device
2033 associated with handle.
2034 
2035 . .
2036  pi: >=0 (as returned by [*pigpio_start*]).
2037  handle: >=0, as returned by a call to [*i2c_open*].
2038 i2c_reg: 0-255, the register to read.
2039 . .
2040 
2041 Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE,
2042 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2043 
2044 Read byte. SMBus 2.0 5.5.5
2045 . .
2046 S Addr Wr [A] i2c_reg [A] S Addr Rd [A] [Data] NA P
2047 . .
2048 D*/
2049 
2050 /*F*/
2051 int i2c_read_word_data(int pi, unsigned handle, unsigned i2c_reg);
2052 /*D
2053 This reads a single 16 bit word from the specified register of the device
2054 associated with handle.
2055 
2056 . .
2057  pi: >=0 (as returned by [*pigpio_start*]).
2058  handle: >=0, as returned by a call to [*i2c_open*].
2059 i2c_reg: 0-255, the register to read.
2060 . .
2061 
2062 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
2063 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2064 
2065 Read word. SMBus 2.0 5.5.5
2066 . .
2067 S Addr Wr [A] i2c_reg [A]
2068  S Addr Rd [A] [DataLow] A [DataHigh] NA P
2069 . .
2070 D*/
2071 
2072 /*F*/
2073 int i2c_process_call(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal);
2074 /*D
2075 This writes 16 bits of data to the specified register of the device
2076 associated with handle and and reads 16 bits of data in return.
2077 
2078 . .
2079  pi: >=0 (as returned by [*pigpio_start*]).
2080  handle: >=0, as returned by a call to [*i2c_open*].
2081 i2c_reg: 0-255, the register to write/read.
2082  wVal: 0-0xFFFF, the value to write.
2083 . .
2084 
2085 Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE,
2086 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2087 
2088 Process call. SMBus 2.0 5.5.6
2089 . .
2090 S Addr Wr [A] i2c_reg [A] wVal_Low [A] wVal_High [A]
2091  S Addr Rd [A] [DataLow] A [DataHigh] NA P
2092 . .
2093 D*/
2094 
2095 /*F*/
2097  int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
2098 /*D
2099 This writes up to 32 bytes to the specified register of the device
2100 associated with handle.
2101 
2102 . .
2103  pi: >=0 (as returned by [*pigpio_start*]).
2104  handle: >=0, as returned by a call to [*i2c_open*].
2105 i2c_reg: 0-255, the register to write.
2106  buf: an array with the data to send.
2107  count: 1-32, the number of bytes to write.
2108 . .
2109 
2110 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2111 PI_I2C_WRITE_FAILED.
2112 
2113 Block write. SMBus 2.0 5.5.7
2114 . .
2115 S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] buf1 [A] ...
2116  [A] bufn [A] P
2117 . .
2118 D*/
2119 
2120 /*F*/
2121 int i2c_read_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf);
2122 /*D
2123 This reads a block of up to 32 bytes from the specified register of
2124 the device associated with handle.
2125 
2126 . .
2127  pi: >=0 (as returned by [*pigpio_start*]).
2128  handle: >=0, as returned by a call to [*i2c_open*].
2129 i2c_reg: 0-255, the register to read.
2130  buf: an array to receive the read data.
2131 . .
2132 
2133 The amount of returned data is set by the device.
2134 
2135 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
2136 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2137 
2138 Block read. SMBus 2.0 5.5.7
2139 . .
2140 S Addr Wr [A] i2c_reg [A]
2141  S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P
2142 . .
2143 D*/
2144 
2145 /*F*/
2147  int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
2148 /*D
2149 This writes data bytes to the specified register of the device
2150 associated with handle and reads a device specified number
2151 of bytes of data in return.
2152 
2153 . .
2154  pi: >=0 (as returned by [*pigpio_start*]).
2155  handle: >=0, as returned by a call to [*i2c_open*].
2156 i2c_reg: 0-255, the register to write/read.
2157  buf: an array with the data to send and to receive the read data.
2158  count: 1-32, the number of bytes to write.
2159 . .
2160 
2161 
2162 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
2163 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2164 
2165 The smbus 2.0 documentation states that a minimum of 1 byte may be
2166 sent and a minimum of 1 byte may be received. The total number of
2167 bytes sent/received must be 32 or less.
2168 
2169 Block write-block read. SMBus 2.0 5.5.8
2170 . .
2171 S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] ...
2172  S Addr Rd [A] [Count] A [Data] ... A P
2173 . .
2174 D*/
2175 
2176 /*F*/
2178  int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
2179 /*D
2180 This reads count bytes from the specified register of the device
2181 associated with handle . The count may be 1-32.
2182 
2183 . .
2184  pi: >=0 (as returned by [*pigpio_start*]).
2185  handle: >=0, as returned by a call to [*i2c_open*].
2186 i2c_reg: 0-255, the register to read.
2187  buf: an array to receive the read data.
2188  count: 1-32, the number of bytes to read.
2189 . .
2190 
2191 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE,
2192 PI_BAD_PARAM, or PI_I2C_READ_FAILED.
2193 
2194 . .
2195 S Addr Wr [A] i2c_reg [A]
2196  S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
2197 . .
2198 D*/
2199 
2200 
2201 /*F*/
2203  int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count);
2204 /*D
2205 This writes 1 to 32 bytes to the specified register of the device
2206 associated with handle.
2207 
2208 . .
2209  pi: >=0 (as returned by [*pigpio_start*]).
2210  handle: >=0, as returned by a call to [*i2c_open*].
2211 i2c_reg: 0-255, the register to write.
2212  buf: the data to write.
2213  count: 1-32, the number of bytes to write.
2214 . .
2215 
2216 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2217 PI_I2C_WRITE_FAILED.
2218 
2219 . .
2220 S Addr Wr [A] i2c_reg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
2221 . .
2222 D*/
2223 
2224 /*F*/
2225 int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count);
2226 /*D
2227 This reads count bytes from the raw device into buf.
2228 
2229 . .
2230  pi: >=0 (as returned by [*pigpio_start*]).
2231 handle: >=0, as returned by a call to [*i2c_open*].
2232  buf: an array to receive the read data bytes.
2233  count: >0, the number of bytes to read.
2234 . .
2235 
2236 Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2237 PI_I2C_READ_FAILED.
2238 
2239 . .
2240 S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P
2241 . .
2242 D*/
2243 
2244 /*F*/
2245 int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count);
2246 /*D
2247 This writes count bytes from buf to the raw device.
2248 
2249 . .
2250  pi: >=0 (as returned by [*pigpio_start*]).
2251 handle: >=0, as returned by a call to [*i2c_open*].
2252  buf: an array containing the data bytes to write.
2253  count: >0, the number of bytes to write.
2254 . .
2255 
2256 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2257 PI_I2C_WRITE_FAILED.
2258 
2259 . .
2260 S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P
2261 . .
2262 D*/
2263 
2264 /*F*/
2265 int i2c_zip(
2266  int pi,
2267  unsigned handle,
2268  char *inBuf,
2269  unsigned inLen,
2270  char *outBuf,
2271  unsigned outLen);
2272 /*D
2273 This function executes a sequence of I2C operations. The
2274 operations to be performed are specified by the contents of inBuf
2275 which contains the concatenated command codes and associated data.
2276 
2277 . .
2278  pi: >=0 (as returned by [*pigpio_start*]).
2279 handle: >=0, as returned by a call to [*i2cOpen*]
2280  inBuf: pointer to the concatenated I2C commands, see below
2281  inLen: size of command buffer
2282 outBuf: pointer to buffer to hold returned data
2283 outLen: size of output buffer
2284 . .
2285 
2286 Returns >= 0 if OK (the number of bytes read), otherwise
2287 PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN.
2288 PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG.
2289 
2290 The following command codes are supported:
2291 
2292 Name @ Cmd & Data @ Meaning
2293 End @ 0 @ No more commands
2294 Escape @ 1 @ Next P is two bytes
2295 On @ 2 @ Switch combined flag on
2296 Off @ 3 @ Switch combined flag off
2297 Address @ 4 P @ Set I2C address to P
2298 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2299 Read @ 6 P @ Read P bytes of data
2300 Write @ 7 P ... @ Write P bytes of data
2301 
2302 The address, read, and write commands take a parameter P.
2303 Normally P is one byte (0-255). If the command is preceded by
2304 the Escape command then P is two bytes (0-65535, least significant
2305 byte first).
2306 
2307 The address defaults to that associated with the handle.
2308 The flags default to 0. The address and flags maintain their
2309 previous value until updated.
2310 
2311 The returned I2C data is stored in consecutive locations of outBuf.
2312 
2313 ...
2314 Set address 0x53, write 0x32, read 6 bytes
2315 Set address 0x1E, write 0x03, read 6 bytes
2316 Set address 0x68, write 0x1B, read 8 bytes
2317 End
2318 
2319 0x04 0x53 0x07 0x01 0x32 0x06 0x06
2320 0x04 0x1E 0x07 0x01 0x03 0x06 0x06
2321 0x04 0x68 0x07 0x01 0x1B 0x06 0x08
2322 0x00
2323 ...
2324 
2325 D*/
2326 
2327 /*F*/
2328 int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud);
2329 /*D
2330 This function selects a pair of GPIO for bit banging I2C at a
2331 specified baud rate.
2332 
2333 Bit banging I2C allows for certain operations which are not possible
2334 with the standard I2C driver.
2335 
2336 o baud rates as low as 50
2337 o repeated starts
2338 o clock stretching
2339 o I2C on any pair of spare GPIO
2340 
2341 . .
2342  pi: >=0 (as returned by [*pigpio_start*]).
2343  SDA: 0-31
2344  SCL: 0-31
2345 baud: 50-500000
2346 . .
2347 
2348 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or
2349 PI_GPIO_IN_USE.
2350 
2351 NOTE:
2352 
2353 The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As
2354 a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value.
2355 D*/
2356 
2357 /*F*/
2358 int bb_i2c_close(int pi, unsigned SDA);
2359 /*D
2360 This function stops bit banging I2C on a pair of GPIO previously
2361 opened with [*bb_i2c_open*].
2362 
2363 . .
2364  pi: >=0 (as returned by [*pigpio_start*]).
2365 SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*]
2366 . .
2367 
2368 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO.
2369 D*/
2370 
2371 /*F*/
2372 int bb_i2c_zip(
2373  int pi,
2374  unsigned SDA,
2375  char *inBuf,
2376  unsigned inLen,
2377  char *outBuf,
2378  unsigned outLen);
2379 /*D
2380 This function executes a sequence of bit banged I2C operations. The
2381 operations to be performed are specified by the contents of inBuf
2382 which contains the concatenated command codes and associated data.
2383 
2384 . .
2385  pi: >=0 (as returned by [*pigpio_start*]).
2386  SDA: 0-31 (as used in a prior call to [*bb_i2c_open*])
2387  inBuf: pointer to the concatenated I2C commands, see below
2388  inLen: size of command buffer
2389 outBuf: pointer to buffer to hold returned data
2390 outLen: size of output buffer
2391 . .
2392 
2393 Returns >= 0 if OK (the number of bytes read), otherwise
2394 PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER,
2395 PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN,
2396 PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED.
2397 
2398 The following command codes are supported:
2399 
2400 Name @ Cmd & Data @ Meaning
2401 End @ 0 @ No more commands
2402 Escape @ 1 @ Next P is two bytes
2403 Start @ 2 @ Start condition
2404 Stop @ 3 @ Stop condition
2405 Address @ 4 P @ Set I2C address to P
2406 Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8)
2407 Read @ 6 P @ Read P bytes of data
2408 Write @ 7 P ... @ Write P bytes of data
2409 
2410 The address, read, and write commands take a parameter P.
2411 Normally P is one byte (0-255). If the command is preceded by
2412 the Escape command then P is two bytes (0-65535, least significant
2413 byte first).
2414 
2415 The address and flags default to 0. The address and flags maintain
2416 their previous value until updated.
2417 
2418 No flags are currently defined.
2419 
2420 The returned I2C data is stored in consecutive locations of outBuf.
2421 
2422 ...
2423 Set address 0x53
2424 start, write 0x32, (re)start, read 6 bytes, stop
2425 Set address 0x1E
2426 start, write 0x03, (re)start, read 6 bytes, stop
2427 Set address 0x68
2428 start, write 0x1B, (re)start, read 8 bytes, stop
2429 End
2430 
2431 0x04 0x53
2432 0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03
2433 
2434 0x04 0x1E
2435 0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03
2436 
2437 0x04 0x68
2438 0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03
2439 
2440 0x00
2441 ...
2442 D*/
2443 
2444 /*F*/
2445 int bb_spi_open(
2446  int pi,
2447  unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK,
2448  unsigned baud, unsigned spi_flags);
2449 /*D
2450 This function selects a set of GPIO for bit banging SPI at a
2451 specified baud rate.
2452 
2453 . .
2454  pi: >=0 (as returned by [*pigpio_start*]).
2455  CS: 0-31
2456  MISO: 0-31
2457  MOSI: 0-31
2458  SCLK: 0-31
2459  baud: 50-250000
2460 spi_flags: see below
2461 . .
2462 
2463 spi_flags consists of the least significant 22 bits.
2464 
2465 . .
2466 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
2467  0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m
2468 . .
2469 
2470 mm defines the SPI mode, defaults to 0
2471 
2472 . .
2473 Mode CPOL CPHA
2474  0 0 0
2475  1 0 1
2476  2 1 0
2477  3 1 1
2478 . .
2479 
2480 p is 0 if CS is active low (default) and 1 for active high.
2481 
2482 T is 1 if the least significant bit is transmitted on MOSI first, the
2483 default (0) shifts the most significant bit out first.
2484 
2485 R is 1 if the least significant bit is received on MISO first, the
2486 default (0) receives the most significant bit first.
2487 
2488 The other bits in flags should be set to zero.
2489 
2490 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or
2491 PI_GPIO_IN_USE.
2492 
2493 If more than one device is connected to the SPI bus (defined by
2494 SCLK, MOSI, and MISO) each must have its own CS.
2495 
2496 ...
2497 bb_spi_open(pi,10, MISO, MOSI, SCLK, 10000, 0); // device 1
2498 bb_spi_open(pi,11, MISO, MOSI, SCLK, 20000, 3); // device 2
2499 ...
2500 D*/
2501 
2502 /*F*/
2503 int bb_spi_close(int pi, unsigned CS);
2504 /*D
2505 This function stops bit banging SPI on a set of GPIO
2506 opened with [*bbSPIOpen*].
2507 
2508 . .
2509 pi: >=0 (as returned by [*pigpio_start*]).
2510 CS: 0-31, the CS GPIO used in a prior call to [*bb_spi_open*]
2511 . .
2512 
2513 Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO.
2514 D*/
2515 
2516 /*F*/
2517 int bb_spi_xfer(
2518  int pi,
2519  unsigned CS,
2520  char *txBuf,
2521  char *rxBuf,
2522  unsigned count);
2523 /*D
2524 This function executes a bit banged SPI transfer.
2525 
2526 . .
2527  pi: >=0 (as returned by [*pigpio_start*]).
2528  CS: 0-31 (as used in a prior call to [*bb_spi_open*])
2529 txBuf: pointer to buffer to hold data to be sent
2530 rxBuf: pointer to buffer to hold returned data
2531 count: size of data transfer
2532 . .
2533 
2534 Returns >= 0 if OK (the number of bytes read), otherwise
2535 PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER.
2536 
2537 ...
2538 // gcc -Wall -pthread -o bb_spi_x_test bb_spi_x_test.c -lpigpiod_if2
2539 // ./bb_spi_x_test
2540 
2541 #include <stdio.h>
2542 
2543 #include "pigpiod_if2.h"
2544 
2545 #define CE0 5
2546 #define CE1 6
2547 #define MISO 13
2548 #define MOSI 19
2549 #define SCLK 12
2550 
2551 int main(int argc, char *argv[])
2552 {
2553  int i, pi, count, set_val, read_val;
2554  unsigned char inBuf[3];
2555  char cmd1[] = {0, 0};
2556  char cmd2[] = {12, 0};
2557  char cmd3[] = {1, 128, 0};
2558 
2559  if ((pi = pigpio_start(0, 0)) < 0)
2560  {
2561  fprintf(stderr, "pigpio initialisation failed (%d).\n", pi);
2562  return 1;
2563  }
2564 
2565  bb_spi_open(pi, CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC
2566  bb_spi_open(pi, CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC
2567 
2568  for (i=0; i<256; i++)
2569  {
2570  cmd1[1] = i;
2571 
2572  count = bb_spi_xfer(pi, CE0, cmd1, (char *)inBuf, 2); // > DAC
2573 
2574  if (count == 2)
2575  {
2576  count = bb_spi_xfer(pi, CE0, cmd2, (char *)inBuf, 2); // < DAC
2577 
2578  if (count == 2)
2579  {
2580  set_val = inBuf[1];
2581 
2582  count = bb_spi_xfer(pi, CE1, cmd3, (char *)inBuf, 3); // < ADC
2583 
2584  if (count == 3)
2585  {
2586  read_val = ((inBuf[1]&3)<<8) | inBuf[2];
2587  printf("%d %d\n", set_val, read_val);
2588  }
2589  }
2590  }
2591  }
2592 
2593  bb_spi_close(pi, CE0);
2594  bb_spi_close(pi, CE1);
2595 
2596  pigpio_stop(pi);
2597 }
2598 ...
2599 D*/
2600 
2601 /*F*/
2602 int spi_open(int pi, unsigned spi_channel, unsigned baud, unsigned spi_flags);
2603 /*D
2604 This function returns a handle for the SPI device on channel.
2605 Data will be transferred at baud bits per second. The flags may
2606 be used to modify the default behaviour of 4-wire operation, mode 0,
2607 active low chip select.
2608 
2609 An auxiliary SPI device is available on all models but the
2610 A and B and may be selected by setting the A bit in the
2611 flags. The auxiliary device has 3 chip selects and a
2612 selectable word size in bits.
2613 
2614 . .
2615  pi: >=0 (as returned by [*pigpio_start*]).
2616 spi_channel: 0-1 (0-2 for the auxiliary device).
2617  baud: 32K-125M (values above 30M are unlikely to work).
2618  spi_flags: see below.
2619 . .
2620 
2621 Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL,
2622 PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED.
2623 
2624 spi_flags consists of the least significant 22 bits.
2625 
2626 . .
2627 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
2628  b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m
2629 . .
2630 
2631 mm defines the SPI mode.
2632 
2633 Warning: modes 1 and 3 do not appear to work on the auxiliary device.
2634 
2635 . .
2636 Mode POL PHA
2637  0 0 0
2638  1 0 1
2639  2 1 0
2640  3 1 1
2641 . .
2642 
2643 px is 0 if CEx is active low (default) and 1 for active high.
2644 
2645 ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise.
2646 
2647 A is 0 for the standard SPI device, 1 for the auxiliary SPI.
2648 
2649 W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Standard
2650 SPI device only.
2651 
2652 nnnn defines the number of bytes (0-15) to write before switching
2653 the MOSI line to MISO to read data. This field is ignored
2654 if W is not set. Standard SPI device only.
2655 
2656 T is 1 if the least significant bit is transmitted on MOSI first, the
2657 default (0) shifts the most significant bit out first. Auxiliary SPI
2658 device only.
2659 
2660 R is 1 if the least significant bit is received on MISO first, the
2661 default (0) receives the most significant bit first. Auxiliary SPI
2662 device only.
2663 
2664 bbbbbb defines the word size in bits (0-32). The default (0)
2665 sets 8 bits per word. Auxiliary SPI device only.
2666 
2667 The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions
2668 transfer data packed into 1, 2, or 4 bytes according to
2669 the word size in bits.
2670 
2671 For bits 1-8 there will be one byte per character.
2672 For bits 9-16 there will be two bytes per character.
2673 For bits 17-32 there will be four bytes per character.
2674 
2675 Multi-byte transfers are made in least significant byte first order.
2676 
2677 E.g. to transfer 32 11-bit words buf should contain 64 bytes
2678 and count should be 64.
2679 
2680 E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed
2681 by 0x1A.
2682 
2683 The other bits in flags should be set to zero.
2684 D*/
2685 
2686 /*F*/
2687 int spi_close(int pi, unsigned handle);
2688 /*D
2689 This functions closes the SPI device identified by the handle.
2690 
2691 . .
2692  pi: >=0 (as returned by [*pigpio_start*]).
2693 handle: >=0, as returned by a call to [*spi_open*].
2694 . .
2695 
2696 Returns 0 if OK, otherwise PI_BAD_HANDLE.
2697 D*/
2698 
2699 /*F*/
2700 int spi_read(int pi, unsigned handle, char *buf, unsigned count);
2701 /*D
2702 This function reads count bytes of data from the SPI
2703 device associated with the handle.
2704 
2705 . .
2706  pi: >=0 (as returned by [*pigpio_start*]).
2707 handle: >=0, as returned by a call to [*spi_open*].
2708  buf: an array to receive the read data bytes.
2709  count: the number of bytes to read.
2710 . .
2711 
2712 Returns the number of bytes transferred if OK, otherwise
2713 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2714 D*/
2715 
2716 /*F*/
2717 int spi_write(int pi, unsigned handle, char *buf, unsigned count);
2718 /*D
2719 This function writes count bytes of data from buf to the SPI
2720 device associated with the handle.
2721 
2722 . .
2723  pi: >=0 (as returned by [*pigpio_start*]).
2724 handle: >=0, as returned by a call to [*spi_open*].
2725  buf: the data bytes to write.
2726  count: the number of bytes to write.
2727 . .
2728 
2729 Returns the number of bytes transferred if OK, otherwise
2730 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2731 D*/
2732 
2733 /*F*/
2734 int spi_xfer(
2735  int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count);
2736 /*D
2737 This function transfers count bytes of data from txBuf to the SPI
2738 device associated with the handle. Simultaneously count bytes of
2739 data are read from the device and placed in rxBuf.
2740 
2741 . .
2742  pi: >=0 (as returned by [*pigpio_start*]).
2743 handle: >=0, as returned by a call to [*spi_open*].
2744  txBuf: the data bytes to write.
2745  rxBuf: the received data bytes.
2746  count: the number of bytes to transfer.
2747 . .
2748 
2749 Returns the number of bytes transferred if OK, otherwise
2750 PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED.
2751 D*/
2752 
2753 /*F*/
2754 int serial_open(int pi, char *ser_tty, unsigned baud, unsigned ser_flags);
2755 /*D
2756 This function opens a serial device at a specified baud rate
2757 with specified flags. The device name must start with
2758 /dev/tty or /dev/serial.
2759 
2760 
2761 . .
2762  pi: >=0 (as returned by [*pigpio_start*]).
2763  ser_tty: the serial device to open.
2764  baud: the baud rate in bits per second, see below.
2765 ser_flags: 0.
2766 . .
2767 
2768 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or
2769 PI_SER_OPEN_FAILED.
2770 
2771 The baud rate must be one of 50, 75, 110, 134, 150,
2772 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200,
2773 38400, 57600, 115200, or 230400.
2774 
2775 No flags are currently defined. This parameter should be set to zero.
2776 D*/
2777 
2778 /*F*/
2779 int serial_close(int pi, unsigned handle);
2780 /*D
2781 This function closes the serial device associated with handle.
2782 
2783 . .
2784  pi: >=0 (as returned by [*pigpio_start*]).
2785 handle: >=0, as returned by a call to [*serial_open*].
2786 . .
2787 
2788 Returns 0 if OK, otherwise PI_BAD_HANDLE.
2789 D*/
2790 
2791 /*F*/
2792 int serial_write_byte(int pi, unsigned handle, unsigned bVal);
2793 /*D
2794 This function writes bVal to the serial port associated with handle.
2795 
2796 . .
2797  pi: >=0 (as returned by [*pigpio_start*]).
2798 handle: >=0, as returned by a call to [*serial_open*].
2799 . .
2800 
2801 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2802 PI_SER_WRITE_FAILED.
2803 D*/
2804 
2805 /*F*/
2806 int serial_read_byte(int pi, unsigned handle);
2807 /*D
2808 This function reads a byte from the serial port associated with handle.
2809 
2810 . .
2811  pi: >=0 (as returned by [*pigpio_start*]).
2812 handle: >=0, as returned by a call to [*serial_open*].
2813 . .
2814 
2815 Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE,
2816 PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED.
2817 
2818 If no data is ready PI_SER_READ_NO_DATA is returned.
2819 D*/
2820 
2821 /*F*/
2822 int serial_write(int pi, unsigned handle, char *buf, unsigned count);
2823 /*D
2824 This function writes count bytes from buf to the the serial port
2825 associated with handle.
2826 
2827 . .
2828  pi: >=0 (as returned by [*pigpio_start*]).
2829 handle: >=0, as returned by a call to [*serial_open*].
2830  buf: the array of bytes to write.
2831  count: the number of bytes to write.
2832 . .
2833 
2834 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or
2835 PI_SER_WRITE_FAILED.
2836 D*/
2837 
2838 /*F*/
2839 int serial_read(int pi, unsigned handle, char *buf, unsigned count);
2840 /*D
2841 This function reads up to count bytes from the the serial port
2842 associated with handle and writes them to buf.
2843 
2844 . .
2845  pi: >=0 (as returned by [*pigpio_start*]).
2846 handle: >=0, as returned by a call to [*serial_open*].
2847  buf: an array to receive the read data.
2848  count: the maximum number of bytes to read.
2849 . .
2850 
2851 Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE,
2852 PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED.
2853 
2854 If no data is ready zero is returned.
2855 D*/
2856 
2857 /*F*/
2858 int serial_data_available(int pi, unsigned handle);
2859 /*D
2860 Returns the number of bytes available to be read from the
2861 device associated with handle.
2862 
2863 . .
2864  pi: >=0 (as returned by [*pigpio_start*]).
2865 handle: >=0, as returned by a call to [*serial_open*].
2866 . .
2867 
2868 Returns the number of bytes of data available (>=0) if OK,
2869 otherwise PI_BAD_HANDLE.
2870 D*/
2871 
2872 /*F*/
2873 int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned argc);
2874 /*D
2875 This function is available for user customisation.
2876 
2877 It returns a single integer value.
2878 
2879 . .
2880  pi: >=0 (as returned by [*pigpio_start*]).
2881 arg1: >=0
2882 arg2: >=0
2883 argx: extra (byte) arguments
2884 argc: number of extra arguments
2885 . .
2886 
2887 Returns >= 0 if OK, less than 0 indicates a user defined error.
2888 D*/
2889 
2890 
2891 /*F*/
2892 int custom_2(int pi, unsigned arg1, char *argx, unsigned argc,
2893  char *retBuf, unsigned retMax);
2894 /*D
2895 This function is available for user customisation.
2896 
2897 It differs from custom_1 in that it returns an array of bytes
2898 rather than just an integer.
2899 
2900 The return value is an integer indicating the number of returned bytes.
2901 . .
2902  pi: >=0 (as returned by [*pigpio_start*]).
2903  arg1: >=0
2904  argc: extra (byte) arguments
2905  count: number of extra arguments
2906 retBuf: buffer for returned data
2907 retMax: maximum number of bytes to return
2908 . .
2909 
2910 Returns >= 0 if OK, less than 0 indicates a user defined error.
2911 
2912 Note, the number of returned bytes will be retMax or less.
2913 D*/
2914 
2915 /*F*/
2916 int get_pad_strength(int pi, unsigned pad);
2917 /*D
2918 This function returns the pad drive strength in mA.
2919 
2920 . .
2921  pi: >=0 (as returned by [*pigpio_start*]).
2922 pad: 0-2, the pad to get.
2923 . .
2924 
2925 Returns the pad drive strength if OK, otherwise PI_BAD_PAD.
2926 
2927 Pad @ GPIO
2928 0 @ 0-27
2929 1 @ 28-45
2930 2 @ 46-53
2931 
2932 ...
2933 strength = get_pad_strength(pi, 0); // get pad 0 strength
2934 ...
2935 D*/
2936 
2937 
2938 /*F*/
2939 int set_pad_strength(int pi, unsigned pad, unsigned padStrength);
2940 /*D
2941 This function sets the pad drive strength in mA.
2942 
2943 . .
2944  pi: >=0 (as returned by [*pigpio_start*]).
2945  pad: 0-2, the pad to set.
2946 padStrength: 1-16 mA.
2947 . .
2948 
2949 Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH.
2950 
2951 Pad @ GPIO
2952 0 @ 0-27
2953 1 @ 28-45
2954 2 @ 46-53
2955 
2956 ...
2957 set_pad_strength(pi, 0, 10); // set pad 0 strength to 10 mA
2958 ...
2959 D*/
2960 
2961 
2962 /*F*/
2963 int shell_(int pi, char *scriptName, char *scriptString);
2964 /*D
2965 This function uses the system call to execute a shell script
2966 with the given string as its parameter.
2967 
2968 . .
2969  pi: >=0 (as returned by [*pigpio_start*]).
2970  scriptName: the name of the script, only alphanumeric characters,
2971  '-' and '_' are allowed in the name.
2972 scriptString: the string to pass to the script.
2973 . .
2974 
2975 The exit status of the system call is returned if OK, otherwise
2976 PI_BAD_SHELL_STATUS.
2977 
2978 scriptName must exist in /opt/pigpio/cgi and must be executable.
2979 
2980 The returned exit status is normally 256 times that set by the
2981 shell script exit function. If the script can't be found 32512 will
2982 be returned.
2983 
2984 The following table gives some example returned statuses.
2985 
2986 Script exit status @ Returned system call status
2987 1 @ 256
2988 5 @ 1280
2989 10 @ 2560
2990 200 @ 51200
2991 script not found @ 32512
2992 
2993 ...
2994 // pass two parameters, hello and world
2995 status = shell_(pi, "scr1", "hello world");
2996 
2997 // pass three parameters, hello, string with spaces, and world
2998 status = shell_(pi, "scr1", "hello 'string with spaces' world");
2999 
3000 // pass one parameter, hello string with spaces world
3001 status = shell_(pi, "scr1", "\"hello string with spaces world\"");
3002 ...
3003 D*/
3004 
3005 #pragma GCC diagnostic push
3006 
3007 #pragma GCC diagnostic ignored "-Wcomment"
3008 
3009 /*F*/
3010 int file_open(int pi, char *file, unsigned mode);
3011 /*D
3012 This function returns a handle to a file opened in a specified mode.
3013 
3014 . .
3015  pi: >=0 (as returned by [*pigpio_start*]).
3016 file: the file to open.
3017 mode: the file open mode.
3018 . .
3019 
3020 Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS,
3021 PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR.
3022 
3023 File
3024 
3025 A file may only be opened if permission is granted by an entry in
3026 /opt/pigpio/access. This is intended to allow remote access to files
3027 in a more or less controlled manner.
3028 
3029 Each entry in /opt/pigpio/access takes the form of a file path
3030 which may contain wildcards followed by a single letter permission.
3031 The permission may be R for read, W for write, U for read/write,
3032 and N for no access.
3033 
3034 Where more than one entry matches a file the most specific rule
3035 applies. If no entry matches a file then access is denied.
3036 
3037 Suppose /opt/pigpio/access contains the following entries
3038 
3039 . .
3040 /home/* n
3041 /home/pi/shared/dir_1/* w
3042 /home/pi/shared/dir_2/* r
3043 /home/pi/shared/dir_3/* u
3044 /home/pi/shared/dir_1/file.txt n
3045 . .
3046 
3047 Files may be written in directory dir_1 with the exception
3048 of file.txt.
3049 
3050 Files may be read in directory dir_2.
3051 
3052 Files may be read and written in directory dir_3.
3053 
3054 If a directory allows read, write, or read/write access then files may
3055 be created in that directory.
3056 
3057 In an attempt to prevent risky permissions the following paths are
3058 ignored in /opt/pigpio/access.
3059 
3060 . .
3061 a path containing ..
3062 a path containing only wildcards (*?)
3063 a path containing less than two non-wildcard parts
3064 . .
3065 
3066 Mode
3067 
3068 The mode may have the following values.
3069 
3070 Macro @ Value @ Meaning
3071 PI_FILE_READ @ 1 @ open file for reading
3072 PI_FILE_WRITE @ 2 @ open file for writing
3073 PI_FILE_RW @ 3 @ open file for reading and writing
3074 
3075 The following values may be or'd into the mode.
3076 
3077 Macro @ Value @ Meaning
3078 PI_FILE_APPEND @ 4 @ Writes append data to the end of the file
3079 PI_FILE_CREATE @ 8 @ The file is created if it doesn't exist
3080 PI_FILE_TRUNC @ 16 @ The file is truncated
3081 
3082 Newly created files are owned by root with permissions owner read and write.
3083 
3084 ...
3085 #include <stdio.h>
3086 #include <pigpiod_if2.h>
3087 
3088 int main(int argc, char *argv[])
3089 {
3090  int pi, handle, c;
3091  char buf[60000];
3092 
3093  pi = pigpio_start(NULL, NULL);
3094 
3095  if (pi < 0) return 1;
3096 
3097  // assumes /opt/pigpio/access contains the following line
3098  // /ram/*.c r
3099 
3100  handle = file_open(pi, "/ram/pigpio.c", PI_FILE_READ);
3101 
3102  if (handle >= 0)
3103  {
3104  while ((c=file_read(pi, handle, buf, sizeof(buf)-1)))
3105  {
3106  buf[c] = 0;
3107  printf("%s", buf);
3108  }
3109 
3110  file_close(pi, handle);
3111  }
3112 
3113  pigpio_stop(pi);
3114 }
3115 ...
3116 D*/
3117 
3118 #pragma GCC diagnostic pop
3119 
3120 /*F*/
3121 int file_close(int pi, unsigned handle);
3122 /*D
3123 This function closes the file associated with handle.
3124 
3125 . .
3126  pi: >=0 (as returned by [*pigpio_start*]).
3127 handle: >=0 (as returned by [*file_open*]).
3128 . .
3129 
3130 Returns 0 if OK, otherwise PI_BAD_HANDLE.
3131 
3132 ...
3133 file_close(pi, handle);
3134 ...
3135 D*/
3136 
3137 
3138 /*F*/
3139 int file_write(int pi, unsigned handle, char *buf, unsigned count);
3140 /*D
3141 This function writes count bytes from buf to the the file
3142 associated with handle.
3143 
3144 . .
3145  pi: >=0 (as returned by [*pigpio_start*]).
3146 handle: >=0 (as returned by [*file_open*]).
3147  buf: the array of bytes to write.
3148  count: the number of bytes to write.
3149 . .
3150 
3151 Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM,
3152 PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE.
3153 
3154 ...
3155 if (file_write(pi, handle, buf, 100) == 0)
3156 {
3157  // file written okay
3158 }
3159 else
3160 {
3161  // error
3162 }
3163 ...
3164 D*/
3165 
3166 
3167 /*F*/
3168 int file_read(int pi, unsigned handle, char *buf, unsigned count);
3169 /*D
3170 This function reads up to count bytes from the the file
3171 associated with handle and writes them to buf.
3172 
3173 . .
3174  pi: >=0 (as returned by [*pigpio_start*]).
3175 handle: >=0 (as returned by [*file_open*]).
3176  buf: an array to receive the read data.
3177  count: the maximum number of bytes to read.
3178 . .
3179 
3180 Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE.
3181 
3182 ...
3183  bytes = file_read(pi, handle, buf, sizeof(buf));
3184 
3185  if (bytes >= 0)
3186  {
3187  // process read data
3188  }
3189 ...
3190 D*/
3191 
3192 
3193 /*F*/
3194 int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom);
3195 /*D
3196 This function seeks to a position within the file associated
3197 with handle.
3198 
3199 . .
3200  pi: >=0 (as returned by [*pigpio_start*]).
3201  handle: >=0 (as returned by [*file_open*]).
3202 seekOffset: the number of bytes to move. Positive offsets
3203  move forward, negative offsets backwards.
3204  seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1),
3205  or PI_FROM_END (2).
3206 . .
3207 
3208 Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK.
3209 
3210 ...
3211 file_seek(pi, handle, 123, PI_FROM_START); // Start plus 123
3212 
3213 size = file_seek(pi, handle, 0, PI_FROM_END); // End, return size
3214 
3215 pos = file_seek(pi, handle, 0, PI_FROM_CURRENT); // Current position
3216 ...
3217 D*/
3218 
3219 #pragma GCC diagnostic push
3220 
3221 #pragma GCC diagnostic ignored "-Wcomment"
3222 
3223 /*F*/
3224 int file_list(int pi, char *fpat, char *buf, unsigned count);
3225 /*D
3226 This function returns a list of files which match a pattern.
3227 
3228 . .
3229  pi: >=0 (as returned by [*pigpio_start*]).
3230  fpat: file pattern to match.
3231  buf: an array to receive the matching file names.
3232 count: the maximum number of bytes to read.
3233 . .
3234 
3235 Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS,
3236 or PI_NO_FILE_MATCH.
3237 
3238 The pattern must match an entry in /opt/pigpio/access. The pattern
3239 may contain wildcards. See [*file_open*].
3240 
3241 NOTE
3242 
3243 The returned value is not the number of files, it is the number
3244 of bytes in the buffer. The file names are separated by newline
3245 characters.
3246 
3247 ...
3248 #include <stdio.h>
3249 #include <pigpiod_if2.h>
3250 
3251 int main(int argc, char *argv[])
3252 {
3253  int pi, handle, c;
3254  char buf[60000];
3255 
3256  pi = pigpio_start(NULL, NULL);
3257 
3258  if (pi < 0) return 1;
3259 
3260  // assumes /opt/pigpio/access contains the following line
3261  // /ram/*.c r
3262 
3263  c = file_list(pi, "/ram/p*.c", buf, sizeof(buf));
3264 
3265  if (c >= 0)
3266  {
3267  buf[c] = 0;
3268  printf("%s", buf);
3269  }
3270 
3271  pigpio_stop(pi);
3272 }
3273 ...
3274 D*/
3275 
3276 #pragma GCC diagnostic pop
3277 
3278 
3279 /*F*/
3280 int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f);
3281 /*D
3282 This function initialises a new callback.
3283 
3284 . .
3285  pi: >=0 (as returned by [*pigpio_start*]).
3286 user_gpio: 0-31.
3287  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
3288  f: the callback function.
3289 . .
3290 
3291 The function returns a callback id if OK, otherwise pigif_bad_malloc,
3292 pigif_duplicate_callback, or pigif_bad_callback.
3293 
3294 The callback is called with the GPIO, edge, and tick, whenever the
3295 GPIO has the identified edge.
3296 
3297 . .
3298 Parameter Value Meaning
3299 
3300 GPIO 0-31 The GPIO which has changed state
3301 
3302 edge 0-2 0 = change to low (a falling edge)
3303  1 = change to high (a rising edge)
3304  2 = no level change (a watchdog timeout)
3305 
3306 tick 32 bit The number of microseconds since boot
3307  WARNING: this wraps around from
3308  4294967295 to 0 roughly every 72 minutes
3309 . .
3310 D*/
3311 
3312 /*F*/
3313 int callback_ex
3314  (int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata);
3315 /*D
3316 This function initialises a new callback.
3317 
3318 . .
3319  pi: >=0 (as returned by [*pigpio_start*]).
3320 user_gpio: 0-31.
3321  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
3322  f: the callback function.
3323  userdata: a pointer to arbitrary user data.
3324 . .
3325 
3326 The function returns a callback id if OK, otherwise pigif_bad_malloc,
3327 pigif_duplicate_callback, or pigif_bad_callback.
3328 
3329 The callback is called with the GPIO, edge, tick, and the userdata
3330 pointer, whenever the GPIO has the identified edge.
3331 
3332 . .
3333 Parameter Value Meaning
3334 
3335 GPIO 0-31 The GPIO which has changed state
3336 
3337 edge 0-2 0 = change to low (a falling edge)
3338  1 = change to high (a rising edge)
3339  2 = no level change (a watchdog timeout)
3340 
3341 tick 32 bit The number of microseconds since boot
3342  WARNING: this wraps around from
3343  4294967295 to 0 roughly every 72 minutes
3344 
3345 userdata pointer Pointer to an arbitrary object
3346 . .
3347 D*/
3348 
3349 /*F*/
3350 int callback_cancel(unsigned callback_id);
3351 /*D
3352 This function cancels a callback identified by its id.
3353 
3354 . .
3355 callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*].
3356 . .
3357 
3358 The function returns 0 if OK, otherwise pigif_callback_not_found.
3359 D*/
3360 
3361 /*F*/
3362 int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout);
3363 /*D
3364 This function waits for an edge on the GPIO for up to timeout
3365 seconds.
3366 
3367 . .
3368  pi: >=0 (as returned by [*pigpio_start*]).
3369 user_gpio: 0-31.
3370  edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE.
3371  timeout: >=0.
3372 . .
3373 
3374 The function returns when the edge occurs or after the timeout.
3375 
3376 Do not use this function for precise timing purposes,
3377 the edge is only checked 20 times a second. Whenever
3378 you need to know the accurate time of GPIO events use
3379 a [*callback*] function.
3380 
3381 The function returns 1 if the edge occurred, otherwise 0.
3382 D*/
3383 
3384 /*F*/
3385 int bsc_xfer(int pi, bsc_xfer_t *bscxfer);
3386 /*D
3387 This function provides a low-level interface to the
3388 SPI/I2C Slave peripheral. This peripheral allows the
3389 Pi to act as a slave device on an I2C or SPI bus.
3390 
3391 I can't get SPI to work properly. I tried with a
3392 control word of 0x303 and swapped MISO and MOSI.
3393 
3394 The function sets the BSC mode, writes any data in
3395 the transmit buffer to the BSC transmit FIFO, and
3396 copies any data in the BSC receive FIFO to the
3397 receive buffer.
3398 
3399 . .
3400  pi: >=0 (as returned by [*pigpio_start*]).
3401 bscxfer: a structure defining the transfer.
3402 
3403 typedef struct
3404 {
3405  uint32_t control; // Write
3406  int rxCnt; // Read only
3407  char rxBuf[BSC_FIFO_SIZE]; // Read only
3408  int txCnt; // Write
3409  char txBuf[BSC_FIFO_SIZE]; // Write
3410 } bsc_xfer_t;
3411 . .
3412 
3413 To start a transfer set control (see below) and copy the bytes to
3414 be sent (if any) to txBuf and set the byte count in txCnt.
3415 
3416 Upon return rxCnt will be set to the number of received bytes placed
3417 in rxBuf.
3418 
3419 The returned function value is the status of the transfer (see below).
3420 
3421 If there was an error the status will be less than zero
3422 (and will contain the error code).
3423 
3424 The most significant word of the returned status contains the number
3425 of bytes actually copied from txBuf to the BSC transmit FIFO (may be
3426 less than requested if the FIFO already contained untransmitted data).
3427 
3428 Note that the control word sets the BSC mode. The BSC will stay in
3429 that mode until a different control word is sent.
3430 
3431 The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode
3432 and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You
3433 need to swap MISO/MOSI between master and slave.
3434 
3435 When a zero control word is received GPIO 18-21 will be reset
3436 to INPUT mode.
3437 
3438 control consists of the following bits.
3439 
3440 . .
3441 22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
3442  a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN
3443 . .
3444 
3445 Bits 0-13 are copied unchanged to the BSC CR register. See
3446 pages 163-165 of the Broadcom peripherals document for full
3447 details.
3448 
3449 aaaaaaa @ defines the I2C slave address (only relevant in I2C mode)
3450 IT @ invert transmit status flags
3451 HC @ enable host control
3452 TF @ enable test FIFO
3453 IR @ invert receive status flags
3454 RE @ enable receive
3455 TE @ enable transmit
3456 BK @ abort operation and clear FIFOs
3457 EC @ send control register as first I2C byte
3458 ES @ send status register as first I2C byte
3459 PL @ set SPI polarity high
3460 PH @ set SPI phase high
3461 I2 @ enable I2C mode
3462 SP @ enable SPI mode
3463 EN @ enable BSC peripheral
3464 
3465 The returned status has the following format
3466 
3467 . .
3468 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
3469  S S S S S R R R R R T T T T T RB TE RF TF RE TB
3470 . .
3471 
3472 Bits 0-15 are copied unchanged from the BSC FR register. See
3473 pages 165-166 of the Broadcom peripherals document for full
3474 details.
3475 
3476 SSSSS @ number of bytes successfully copied to transmit FIFO
3477 RRRRR @ number of bytes in receieve FIFO
3478 TTTTT @ number of bytes in transmit FIFO
3479 RB @ receive busy
3480 TE @ transmit FIFO empty
3481 RF @ receive FIFO full
3482 TF @ transmit FIFO full
3483 RE @ receive FIFO empty
3484 TB @ transmit busy
3485 
3486 The following example shows how to configure the BSC peripheral as
3487 an I2C slave with address 0x13 and send four bytes.
3488 
3489 ...
3490 bsc_xfer_t xfer;
3491 
3492 xfer.control = (0x13<<16) | 0x305;
3493 
3494 memcpy(xfer.txBuf, "ABCD", 4);
3495 xfer.txCnt = 4;
3496 
3497 status = bsc_xfer(pi, &xfer);
3498 
3499 if (status >= 0)
3500 {
3501  // process transfer
3502 }
3503 ...
3504 D*/
3505 
3506 /*F*/
3507 int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer);
3508 /*D
3509 This function allows the Pi to act as a slave I2C device.
3510 
3511 The data bytes (if any) are written to the BSC transmit
3512 FIFO and the bytes in the BSC receive FIFO are returned.
3513 
3514 . .
3515  pi: >=0 (as returned by [*pigpio_start*]).
3516 i2c_addr: 0-0x7F.
3517  bscxfer: a structure defining the transfer.
3518 
3519 typedef struct
3520 {
3521  uint32_t control; // N/A
3522  int rxCnt; // Read only
3523  char rxBuf[BSC_FIFO_SIZE]; // Read only
3524  int txCnt; // Write
3525  char txBuf[BSC_FIFO_SIZE]; // Write
3526 } bsc_xfer_t;
3527 . .
3528 
3529 txCnt is set to the number of bytes to be transmitted, possibly
3530 zero. The data itself should be copied to txBuf.
3531 
3532 Any received data will be written to rxBuf with rxCnt set.
3533 
3534 See [*bsc_xfer*] for details of the returned status value.
3535 
3536 If there was an error the status will be less than zero
3537 (and will contain the error code).
3538 
3539 Note that an i2c_address of 0 may be used to close
3540 the BSC device and reassign the used GPIO (18/19)
3541 as inputs.
3542 D*/
3543 
3544 /*F*/
3545 int event_callback(int pi, unsigned event, evtCBFunc_t f);
3546 /*D
3547 This function initialises an event callback.
3548 
3549 . .
3550  pi: >=0 (as returned by [*pigpio_start*]).
3551 event: 0-31.
3552  f: the callback function.
3553 . .
3554 
3555 The function returns a callback id if OK, otherwise pigif_bad_malloc,
3556 pigif_duplicate_callback, or pigif_bad_callback.
3557 
3558 The callback is called with the event id, and tick, whenever the
3559 event occurs.
3560 D*/
3561 
3562 /*F*/
3563 int event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *userdata);
3564 /*D
3565 This function initialises an event callback.
3566 
3567 . .
3568  pi: >=0 (as returned by [*pigpio_start*]).
3569  event: 0-31.
3570  f: the callback function.
3571 userdata: a pointer to arbitrary user data.
3572 . .
3573 
3574 The function returns a callback id if OK, otherwise pigif_bad_malloc,
3575 pigif_duplicate_callback, or pigif_bad_callback.
3576 
3577 The callback is called with the event id, the tick, and the userdata
3578 pointer whenever the event occurs.
3579 D*/
3580 
3581 /*F*/
3582 int event_callback_cancel(unsigned callback_id);
3583 /*D
3584 This function cancels an event callback identified by its id.
3585 
3586 . .
3587 callback_id: >=0, as returned by a call to [*event_callback*] or
3588 [*event_callback_ex*].
3589 . .
3590 
3591 The function returns 0 if OK, otherwise pigif_callback_not_found.
3592 D*/
3593 
3594 /*F*/
3595 int wait_for_event(int pi, unsigned event, double timeout);
3596 /*D
3597 This function waits for an event for up to timeout seconds.
3598 
3599 . .
3600  pi: >=0 (as returned by [*pigpio_start*]).
3601  event: 0-31.
3602 timeout: >=0.
3603 . .
3604 
3605 The function returns when the event occurs or after the timeout.
3606 
3607 The function returns 1 if the event occurred, otherwise 0.
3608 D*/
3609 
3610 /*F*/
3611 int event_trigger(int pi, unsigned event);
3612 /*D
3613 This function signals the occurrence of an event.
3614 
3615 . .
3616  pi: >=0 (as returned by [*pigpio_start*]).
3617 event: 0-31.
3618 . .
3619 
3620 Returns 0 if OK, otherwise PI_BAD_EVENT_ID.
3621 
3622 An event is a signal used to inform one or more consumers
3623 to start an action. Each consumer which has registered an interest
3624 in the event (e.g. by calling [*event_callback*]) will be informed by
3625 a callback.
3626 
3627 One event, PI_EVENT_BSC (31) is predefined. This event is
3628 auto generated on BSC slave activity.
3629 
3630 The meaning of other events is arbitrary.
3631 
3632 Note that other than its id and its tick there is no data associated
3633 with an event.
3634 D*/
3635 
3636 /*PARAMS
3637 
3638 active :: 0-1000000
3639 
3640 The number of microseconds level changes are reported for once
3641 a noise filter has been triggered (by [*steady*] microseconds of
3642 a stable level).
3643 
3644 *addrStr::
3645 A string specifying the host or IP address of the Pi running
3646 the pigpio daemon. It may be NULL in which case localhost
3647 is used unless overridden by the PIGPIO_ADDR environment
3648 variable.
3649 
3650 arg1::
3651 An unsigned argument passed to a user customised function. Its
3652 meaning is defined by the customiser.
3653 
3654 arg2::
3655 An unsigned argument passed to a user customised function. Its
3656 meaning is defined by the customiser.
3657 
3658 argc::
3659 The count of bytes passed to a user customised function.
3660 
3661 *argx::
3662 A pointer to an array of bytes passed to a user customised function.
3663 Its meaning and content is defined by the customiser.
3664 
3665 baud::
3666 The speed of serial communication (I2C, SPI, serial link, waves) in
3667 bits per second.
3668 
3669 bit::
3670 A value of 0 or 1.
3671 
3672 bits::
3673 A value used to select GPIO. If bit n of bits is set then GPIO n is
3674 selected.
3675 
3676 A convenient way to set bit n is to or in (1<<n).
3677 
3678 e.g. to select bits 5, 9, 23 you could use (1<<5) | (1<<9) | (1<<23).
3679 
3680 bsc_xfer_t::
3681 
3682 . .
3683 typedef struct
3684 {
3685  uint32_t control; // Write
3686  int rxCnt; // Read only
3687  char rxBuf[BSC_FIFO_SIZE]; // Read only
3688  int txCnt; // Write
3689  char txBuf[BSC_FIFO_SIZE]; // Write
3690 } bsc_xfer_t;
3691 . .
3692 
3693 *bscxfer::
3694 A pointer to a [*bsc_xfer_t*] object used to control a BSC transfer.
3695 
3696 *buf::
3697 A buffer to hold data being sent or being received.
3698 
3699 bufSize::
3700 The size in bytes of a buffer.
3701 
3702 
3703 bVal::0-255 (Hex 0x0-0xFF, Octal 0-0377)
3704 An 8-bit byte value.
3705 
3706 callback_id::
3707 A value >=0, as returned by a call to a callback function, one of
3708 
3709 [*callback*]
3710 [*callback_ex*]
3711 [*event_callback*]
3712 [*event_callback_ex*]
3713 
3714 The id is passed to [*callback_cancel*] or [*event_callback_cancel*]
3715 to cancel the callback.
3716 
3717 CBFunc_t::
3718 . .
3719 typedef void (*CBFunc_t)
3720  (int pi, unsigned user_gpio, unsigned level, uint32_t tick);
3721 . .
3722 
3723 CBFuncEx_t::
3724 . .
3725 typedef void (*CBFuncEx_t)
3726  (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void * userdata);
3727 . .
3728 
3729 char::
3730 A single character, an 8 bit quantity able to store 0-255.
3731 
3732 clkfreq::4689-250000000 (250M)
3733 The hardware clock frequency.
3734 
3735 count::
3736 The number of bytes to be transferred in a file, I2C, SPI, or serial
3737 command.
3738 
3739 CS::
3740 The GPIO used for the slave select signal when bit banging SPI.
3741 
3742 data_bits::1-32
3743 The number of data bits in each character of serial data.
3744 
3745 . .
3746 #define PI_MIN_WAVE_DATABITS 1
3747 #define PI_MAX_WAVE_DATABITS 32
3748 . .
3749 
3750 double::
3751 A floating point number.
3752 
3753 dutycycle::0-range
3754 A number representing the ratio of on time to off time for PWM.
3755 
3756 The number may vary between 0 and range (default 255) where
3757 0 is off and range is fully on.
3758 
3759 edge::
3760 Used to identify a GPIO level transition of interest. A rising edge is
3761 a level change from 0 to 1. A falling edge is a level change from 1 to 0.
3762 
3763 . .
3764 RISING_EDGE 0
3765 FALLING_EDGE 1
3766 EITHER_EDGE. 2
3767 . .
3768 
3769 errnum::
3770 A negative number indicating a function call failed and the nature
3771 of the error.
3772 
3773 event::0-31
3774 An event is a signal used to inform one or more consumers
3775 to start an action.
3776 
3777 evtCBFunc_t::
3778 
3779 . .
3780 typedef void (*evtCBFunc_t)
3781  (int pi, unsigned event, uint32_t tick);
3782 . .
3783 
3784 evtCBFuncEx_t::
3785 
3786 . .
3787 typedef void (*evtCBFuncEx_t)
3788  (int pi, unsigned event, uint32_t tick, void *userdata);
3789 . .
3790 
3791 f::
3792 A function.
3793 
3794 *file::
3795 A full file path. To be accessible the path must match an entry in
3796 /opt/pigpio/access.
3797 
3798 *fpat::
3799 A file path which may contain wildcards. To be accessible the path
3800 must match an entry in /opt/pigpio/access.
3801 
3802 frequency::>=0
3803 The number of times a GPIO is swiched on and off per second. This
3804 can be set per GPIO and may be as little as 5Hz or as much as
3805 40KHz. The GPIO will be on for a proportion of the time as defined
3806 by its dutycycle.
3807 
3808 gpio::
3809 A Broadcom numbered GPIO, in the range 0-53.
3810 
3811 There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through
3812 GPIO53.
3813 
3814 They are split into two banks. Bank 1 consists of GPIO0 through
3815 GPIO31. Bank 2 consists of GPIO32 through GPIO53.
3816 
3817 All the GPIO which are safe for the user to read and write are in
3818 bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards
3819 have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26.
3820 
3821 See [*get_hardware_revision*].
3822 
3823 The user GPIO are marked with an X in the following table.
3824 
3825 . .
3826  0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
3827 Type 1 X X - - X - - X X X X X - - X X
3828 Type 2 - - X X X - - X X X X X - - X X
3829 Type 3 X X X X X X X X X X X X X X
3830 
3831  16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
3832 Type 1 - X X - - X X X X X - - - - - -
3833 Type 2 - X X - - - X X X X - X X X X X
3834 Type 3 X X X X X X X X X X X X - - - -
3835 . .
3836 
3837 gpioPulse_t::
3838 . .
3839 typedef struct
3840 {
3841  uint32_t gpioOn;
3842  uint32_t gpioOff;
3843  uint32_t usDelay;
3844 } gpioPulse_t;
3845 . .
3846 
3847 gpioThreadFunc_t::
3848 . .
3849 typedef void *(gpioThreadFunc_t) (void *);
3850 . .
3851 
3852 handle::>=0
3853 A number referencing an object opened by one of
3854 
3855 [*file_open*]
3856 [*i2c_open*]
3857 [*notify_open*]
3858 [*serial_open*]
3859 [*spi_open*]
3860 
3861 i2c_addr::0-0x7F
3862 The address of a device on the I2C bus.
3863 
3864 i2c_bus::>=0
3865 An I2C bus number.
3866 
3867 i2c_flags::0
3868 Flags which modify an I2C open command. None are currently defined.
3869 
3870 i2c_reg:: 0-255
3871 A register of an I2C device.
3872 
3873 *inBuf::
3874 A buffer used to pass data to a function.
3875 
3876 inLen::
3877 The number of bytes of data in a buffer.
3878 
3879 int::
3880 A whole number, negative or positive.
3881 
3882 int32_t::
3883 A 32-bit signed value.
3884 
3885 invert::
3886 A flag used to set normal or inverted bit bang serial data level logic.
3887 
3888 level::
3889 The level of a GPIO. Low or High.
3890 
3891 . .
3892 PI_OFF 0
3893 PI_ON 1
3894 
3895 PI_CLEAR 0
3896 PI_SET 1
3897 
3898 PI_LOW 0
3899 PI_HIGH 1
3900 . .
3901 
3902 There is one exception. If a watchdog expires on a GPIO the level will be
3903 reported as PI_TIMEOUT. See [*set_watchdog*].
3904 
3905 . .
3906 PI_TIMEOUT 2
3907 . .
3908 
3909 MISO::
3910 The GPIO used for the MISO signal when bit banging SPI.
3911 
3912 mode::
3913 1. The operational mode of a GPIO, normally INPUT or OUTPUT.
3914 
3915 . .
3916 PI_INPUT 0
3917 PI_OUTPUT 1
3918 PI_ALT0 4
3919 PI_ALT1 5
3920 PI_ALT2 6
3921 PI_ALT3 7
3922 PI_ALT4 3
3923 PI_ALT5 2
3924 . .
3925 
3926 2. The mode of waveform transmission.
3927 
3928 . .
3929 PI_WAVE_MODE_ONE_SHOT 0
3930 PI_WAVE_MODE_REPEAT 1
3931 PI_WAVE_MODE_ONE_SHOT_SYNC 2
3932 PI_WAVE_MODE_REPEAT_SYNC 3
3933 . .
3934 
3935 3. A file open mode.
3936 
3937 . .
3938 PI_FILE_READ 1
3939 PI_FILE_WRITE 2
3940 PI_FILE_RW 3
3941 . .
3942 
3943 The following values can be or'd into the mode.
3944 
3945 . .
3946 PI_FILE_APPEND 4
3947 PI_FILE_CREATE 8
3948 PI_FILE_TRUNC 16
3949 . .
3950 
3951 MOSI::
3952 The GPIO used for the MOSI signal when bit banging SPI.
3953 
3954 numBytes::
3955 The number of bytes used to store characters in a string. Depending
3956 on the number of bits per character there may be 1, 2, or 4 bytes
3957 per character.
3958 
3959 numPar:: 0-10
3960 The number of parameters passed to a script.
3961 
3962 numPulses::
3963 The number of pulses to be added to a waveform.
3964 
3965 offset::
3966 The associated data starts this number of microseconds from the start of
3967 the waveform.
3968 
3969 *outBuf::
3970 A buffer used to return data from a function.
3971 
3972 outLen::
3973 The size in bytes of an output buffer.
3974 
3975 pad:: 0-2
3976 A set of GPIO which share common drivers.
3977 
3978 Pad @ GPIO
3979 0 @ 0-27
3980 1 @ 28-45
3981 2 @ 46-53
3982 
3983 padStrength:: 1-16
3984 The mA which may be drawn from each GPIO whilst still guaranteeing the
3985 high and low levels.
3986 
3987 *param::
3988 An array of script parameters.
3989 
3990 pi::
3991 An integer defining a connected Pi. The value is returned by
3992 [*pigpio_start*] upon success.
3993 
3994 *portStr::
3995 A string specifying the port address used by the Pi running
3996 the pigpio daemon. It may be NULL in which case "8888"
3997 is used unless overridden by the PIGPIO_PORT environment
3998 variable.
3999 
4000 *pth::
4001 A thread identifier, returned by [*start_thread*].
4002 
4003 
4004 pthread_t::
4005 A thread identifier.
4006 
4007 pud::0-2
4008 The setting of the pull up/down resistor for a GPIO, which may be off,
4009 pull-up, or pull-down.
4010 . .
4011 PI_PUD_OFF 0
4012 PI_PUD_DOWN 1
4013 PI_PUD_UP 2
4014 . .
4015 
4016 pulseLen::
4017 1-100, the length of a trigger pulse in microseconds.
4018 
4019 *pulses::
4020 An array of pulses to be added to a waveform.
4021 
4022 pulsewidth::0, 500-2500
4023 . .
4024 PI_SERVO_OFF 0
4025 PI_MIN_SERVO_PULSEWIDTH 500
4026 PI_MAX_SERVO_PULSEWIDTH 2500
4027 . .
4028 
4029 PWMduty::0-1000000 (1M)
4030 The hardware PWM dutycycle.
4031 
4032 . .
4033 #define PI_HW_PWM_RANGE 1000000
4034 . .
4035 
4036 PWMfreq::1-125000000 (125M)
4037 The hardware PWM frequency.
4038 
4039 . .
4040 #define PI_HW_PWM_MIN_FREQ 1
4041 #define PI_HW_PWM_MAX_FREQ 125000000
4042 . .
4043 
4044 range::25-40000
4045 The permissible dutycycle values are 0-range.
4046 
4047 . .
4048 PI_MIN_DUTYCYCLE_RANGE 25
4049 PI_MAX_DUTYCYCLE_RANGE 40000
4050 . .
4051 
4052 *retBuf::
4053 A buffer to hold a number of bytes returned to a used customised function,
4054 
4055 retMax::
4056 The maximum number of bytes a user customised function should return.
4057 
4058 
4059 *rxBuf::
4060 A pointer to a buffer to receive data.
4061 
4062 SCL::
4063 The user GPIO to use for the clock when bit banging I2C.
4064 
4065 SCLK::
4066 The GPIO used for the SCLK signal when bit banging SPI.
4067 
4068 *script::
4069 A pointer to the text of a script.
4070 
4071 script_id::
4072 An id of a stored script as returned by [*store_script*].
4073 
4074 *scriptName::
4075 The name of a [*shell_*] script to be executed. The script must be present in
4076 /opt/pigpio/cgi and must have execute permission.
4077 
4078 *scriptString::
4079 The string to be passed to a [*shell_*] script to be executed.
4080 
4081 SDA::
4082 The user GPIO to use for data when bit banging I2C.
4083 
4084 seconds::
4085 The number of seconds.
4086 
4087 seekFrom::
4088 
4089 . .
4090 PI_FROM_START 0
4091 PI_FROM_CURRENT 1
4092 PI_FROM_END 2
4093 . .
4094 
4095 seekOffset::
4096 The number of bytes to move forward (positive) or backwards (negative)
4097 from the seek position (start, current, or end of file).
4098 
4099 ser_flags::
4100 Flags which modify a serial open command. None are currently defined.
4101 
4102 *ser_tty::
4103 The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1.
4104 
4105 size_t::
4106 A standard type used to indicate the size of an object in bytes.
4107 
4108 spi_channel::
4109 A SPI channel, 0-2.
4110 
4111 spi_flags::
4112 See [*spi_open*] and [*bb_spi_open*].
4113 
4114 steady:: 0-300000
4115 
4116 The number of microseconds level changes must be stable for
4117 before reporting the level changed ([*set_glitch_filter*]) or triggering
4118 the active part of a noise filter ([*set_noise_filter*]).
4119 
4120 stop_bits::2-8
4121 The number of (half) stop bits to be used when adding serial data
4122 to a waveform.
4123 
4124 . .
4125 #define PI_MIN_WAVE_HALFSTOPBITS 2
4126 #define PI_MAX_WAVE_HALFSTOPBITS 8
4127 . .
4128 
4129 *str::
4130  An array of characters.
4131 
4132 thread_func::
4133 A function of type gpioThreadFunc_t used as the main function of a
4134 thread.
4135 
4136 timeout::
4137 A GPIO watchdog timeout in milliseconds.
4138 
4139 . .
4140 PI_MIN_WDOG_TIMEOUT 0
4141 PI_MAX_WDOG_TIMEOUT 60000
4142 . .
4143 
4144 *txBuf::
4145 An array of bytes to transmit.
4146 
4147 uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)
4148 A 32-bit unsigned value.
4149 
4150 unsigned::
4151 A whole number >= 0.
4152 
4153 user_gpio::
4154 0-31, a Broadcom numbered GPIO.
4155 
4156 See [*gpio*].
4157 
4158 *userdata::
4159 
4160 A pointer to arbitrary user data. This may be used to identify the instance.
4161 
4162 You must ensure that the pointer is in scope at the time it is processed. If
4163 it is a pointer to a global this is automatic. Do not pass the address of a
4164 local variable. If you want to pass a transient object then use the
4165 following technique.
4166 
4167 In the calling function:
4168 
4169 . .
4170 user_type *userdata;
4171 user_type my_userdata;
4172 
4173 userdata = malloc(sizeof(user_type));
4174 *userdata = my_userdata;
4175 . .
4176 
4177 In the receiving function:
4178 
4179 . .
4180 user_type my_userdata = *(user_type*)userdata;
4181 
4182 free(userdata);
4183 . .
4184 
4185 void::
4186 Denoting no parameter is required
4187 
4188 wave_add_*::
4189 One of
4190 
4191 [*wave_add_new*]
4192 [*wave_add_generic*]
4193 [*wave_add_serial*]
4194 
4195 wave_id::
4196 A number representing a waveform created by [*wave_create*].
4197 
4198 wave_send_*::
4199 One of
4200 
4201 [*wave_send_once*]
4202 [*wave_send_repeat*]
4203 
4204 wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)
4205 A 16-bit word value.
4206 
4207 PARAMS*/
4208 
4209 /*DEF_S pigpiod_if2 Error Codes*/
4210 
4211 typedef enum
4212 {
4226 } pigifError_t;
4227 
4228 /*DEF_E*/
4229 
4230 #ifdef __cplusplus
4231 }
4232 #endif
4233 
4234 #endif
4235 
void(* CBFunc_t)(int pi, unsigned user_gpio, unsigned level, uint32_t tick)
Definition: pigpiod_if2.h:320
int i2c_write_word_data(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal)
int hardware_PWM(int pi, unsigned gpio, unsigned PWMfreq, uint32_t PWMduty)
Definition: pigpiod_if2.c:872
uint32_t read_bank_2(int pi)
Definition: pigpiod_if2.c:854
int callback_cancel(unsigned callback_id)
Definition: pigpiod_if.c:1526
int bb_spi_close(int pi, unsigned CS)
Definition: pigpiod_if2.c:1576
int wave_send_once(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:973
int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1416
int spi_xfer(int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if2.c:1671
int wave_get_high_cbs(int pi)
Definition: pigpiod_if2.c:1031
int wave_tx_at(int pi)
Definition: pigpiod_if2.c:1001
int set_pull_up_down(int pi, unsigned gpio, unsigned pud)
Definition: pigpiod_if2.c:800
int get_pad_strength(int pi, unsigned pad)
Definition: pigpiod_if2.c:1820
void pigpio_stop(int pi)
Definition: pigpiod_if2.c:763
void stop_thread(pthread_t *pth)
Definition: pigpiod_if.c:483
pigifError_t
Definition: pigpiod_if2.h:4211
int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode)
Definition: pigpiod_if2.c:979
int file_list(int pi, char *fpat, char *buf, unsigned count)
Definition: pigpiod_if2.c:1931
int i2c_block_process_call(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1335
int serial_data_available(int pi, unsigned handle)
Definition: pigpiod_if2.c:1767
int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency)
Definition: pigpiod_if2.c:824
uint32_t get_current_tick(int pi)
Definition: pigpiod_if2.c:891
int shell_(int pi, char *scriptName, char *scriptString)
Definition: pigpiod_if2.c:1826
int i2c_read_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf)
Definition: pigpiod_if2.c:1319
int serial_read_byte(int pi, unsigned handle)
Definition: pigpiod_if2.c:1728
int i2c_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1224
int bb_spi_xfer(int pi, unsigned CS, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if2.c:1579
int get_servo_pulsewidth(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:833
int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert)
Definition: pigpiod_if2.c:1202
int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, unsigned level)
int bb_spi_open(int pi, unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spi_flags)
Definition: pigpiod_if2.c:1543
int wave_get_high_micros(int pi)
Definition: pigpiod_if2.c:1013
int spi_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1635
int notify_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:845
int store_script(int pi, char *script)
Definition: pigpiod_if2.c:1078
int file_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1895
int get_PWM_real_range(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:821
int clear_bank_2(int pi, uint32_t bits)
Definition: pigpiod_if2.c:860
int wave_send_repeat(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:976
int i2c_write_quick(int pi, unsigned handle, unsigned bit)
Definition: pigpiod_if2.c:1227
int pigpio_start(char *addrStr, char *portStr)
Definition: pigpiod_if.c:493
int wave_add_new(int pi)
Definition: pigpiod_if2.c:903
int delete_script(int pi, unsigned script_id)
Definition: pigpiod_if2.c:1161
int i2c_read_i2c_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
handle
Definition: PCF8591.py:19
int i2c_write_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1299
int callback_ex(int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata)
Definition: pigpiod_if2.c:1965
uint32_t get_hardware_revision(int pi)
Definition: pigpiod_if2.c:894
int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f)
Definition: pigpiod_if2.c:1962
int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth)
Definition: pigpiod_if2.c:830
int wave_tx_stop(int pi)
Definition: pigpiod_if2.c:1007
int wave_get_max_cbs(int pi)
Definition: pigpiod_if2.c:1034
int gpio_read(int pi, unsigned gpio)
Definition: pigpiod_if2.c:803
int script_status(int pi, unsigned script_id, uint32_t *param)
Definition: pigpiod_if2.c:1139
void(* evtCBFunc_t)(int pi, unsigned event, uint32_t tick)
Definition: pigpiod_if2.h:328
int wave_create(int pi)
Definition: pigpiod_if2.c:961
int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits)
int clear_bank_1(int pi, uint32_t bits)
Definition: pigpiod_if2.c:857
int bb_i2c_close(int pi, unsigned SDA)
Definition: pigpiod_if2.c:1505
int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer)
Definition: pigpiod_if2.c:2060
int get_mode(int pi, unsigned gpio)
Definition: pigpiod_if2.c:797
void time_sleep(double seconds)
Definition: pigpio.c:8374
int gpio_write(int pi, unsigned gpio, unsigned level)
Definition: pigpiod_if2.c:806
int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle)
Definition: pigpiod_if2.c:809
int wave_clear(int pi)
Definition: pigpiod_if2.c:900
int wave_get_high_pulses(int pi)
Definition: pigpiod_if2.c:1022
int serial_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1750
int notify_open(int pi)
Definition: pigpiod_if2.c:836
int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady)
Definition: pigpiod_if2.c:1056
int notify_begin(int pi, unsigned handle, uint32_t bits)
Definition: pigpiod_if2.c:839
void(* evtCBFuncEx_t)(int pi, unsigned event, uint32_t tick, void *userdata)
Definition: pigpiod_if2.h:331
int wave_add_serial(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)
int wave_tx_busy(int pi)
Definition: pigpiod_if2.c:1004
int bb_serial_read_close(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:1199
int wait_for_event(int pi, unsigned event, double timeout)
Definition: pigpiod_if2.c:2107
int stop_script(int pi, unsigned script_id)
Definition: pigpiod_if2.c:1158
int wave_get_micros(int pi)
Definition: pigpiod_if2.c:1010
int event_callback_cancel(unsigned callback_id)
Definition: pigpiod_if2.c:2077
int i2c_read_word_data(int pi, unsigned handle, unsigned i2c_reg)
Definition: pigpiod_if2.c:1277
int set_mode(int pi, unsigned gpio, unsigned mode)
Definition: pigpiod_if2.c:794
int i2c_process_call(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal)
unsigned pigpiod_if_version(void)
Definition: pigpiod_if.c:445
int spi_open(int pi, unsigned spi_channel, unsigned baud, unsigned spi_flags)
int event_callback(int pi, unsigned event, evtCBFunc_t f)
Definition: pigpiod_if2.c:2070
int serial_write(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1731
void *( gpioThreadFunc_t)(void *)
Definition: pigpio.h:552
int custom_2(int pi, unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)
int set_noise_filter(int pi, unsigned user_gpio, unsigned steady, unsigned active)
Definition: pigpiod_if2.c:1059
int get_PWM_frequency(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:827
int notify_pause(int pi, unsigned handle)
Definition: pigpiod_if2.c:842
int get_PWM_range(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:818
int i2c_zip(int pi, unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if2.c:1451
int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if2.c:1101
int set_watchdog(int pi, unsigned user_gpio, unsigned timeout)
Definition: pigpiod_if2.c:848
int wave_get_max_pulses(int pi)
Definition: pigpiod_if2.c:1025
int bsc_xfer(int pi, bsc_xfer_t *bscxfer)
Definition: pigpiod_if2.c:2021
int serial_write_byte(int pi, unsigned handle, unsigned bVal)
Definition: pigpiod_if2.c:1725
int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud)
Definition: pigpiod_if2.c:1486
int wave_get_cbs(int pi)
Definition: pigpiod_if2.c:1028
int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags)
int i2c_read_byte(int pi, unsigned handle)
Definition: pigpiod_if2.c:1233
int set_bank_2(int pi, uint32_t bits)
Definition: pigpiod_if2.c:866
int get_PWM_dutycycle(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:812
uint32_t get_pigpio_version(int pi)
Definition: pigpiod_if2.c:897
int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize)
Definition: pigpiod_if2.c:1183
int i2c_read_byte_data(int pi, unsigned handle, unsigned i2c_reg)
Definition: pigpiod_if2.c:1274
int file_open(int pi, char *file, unsigned mode)
Definition: pigpiod_if2.c:1851
pi
Definition: dht11.py:156
pthread_t * start_thread(gpioThreadFunc_t thread_func, void *userdata)
Definition: pigpiod_if.c:450
int bb_i2c_zip(int pi, unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if2.c:1508
int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom)
Definition: pigpiod_if2.c:1912
int wave_get_pulses(int pi)
Definition: pigpiod_if2.c:1019
int file_write(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1876
int event_trigger(int pi, unsigned event)
Definition: pigpiod_if2.c:2129
int spi_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1632
int wave_get_max_micros(int pi)
Definition: pigpiod_if2.c:1016
int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if2.c:1120
int wave_chain(int pi, char *buf, unsigned bufSize)
Definition: pigpiod_if2.c:982
uint32_t read_bank_1(int pi)
Definition: pigpiod_if2.c:851
int spi_write(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1652
int i2c_write_byte(int pi, unsigned handle, unsigned bVal)
Definition: pigpiod_if2.c:1230
double time_time(void)
Definition: pigpio.c:8360
int serial_open(int pi, char *ser_tty, unsigned baud, unsigned ser_flags)
Definition: pigpiod_if2.c:1700
int set_pad_strength(int pi, unsigned pad, unsigned padStrength)
Definition: pigpiod_if2.c:1823
int i2c_write_byte_data(int pi, unsigned handle, unsigned i2c_reg, unsigned bVal)
char * pigpio_error(int errnum)
Definition: pigpiod_if.c:410
int hardware_clock(int pi, unsigned gpio, unsigned clkfreq)
Definition: pigpiod_if2.c:869
int set_PWM_range(int pi, unsigned user_gpio, unsigned range)
Definition: pigpiod_if2.c:815
int wave_delete(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:964
int serial_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1722
int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1432
int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses)
Definition: pigpiod_if2.c:906
int file_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1873
int i2c_write_i2c_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1396
int set_bank_1(int pi, uint32_t bits)
Definition: pigpiod_if2.c:863
int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout)
Definition: pigpiod_if2.c:1999
int event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *userdata)
Definition: pigpiod_if2.c:2073
int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned argc)
Definition: pigpiod_if2.c:1770
void(* CBFuncEx_t)(int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *userdata)
Definition: pigpiod_if2.h:323


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