pigpiod_if2.c
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 /* PIGPIOD_IF2_VERSION 13 */
29 
30 #include <stdio.h>
31 #include <stdlib.h>
32 #include <stdint.h>
33 #include <string.h>
34 #include <fcntl.h>
35 #include <unistd.h>
36 #include <errno.h>
37 #include <time.h>
38 #include <netdb.h>
39 #include <pthread.h>
40 
41 #include <sys/types.h>
42 #include <sys/stat.h>
43 #include <sys/time.h>
44 #include <sys/socket.h>
45 #include <netinet/tcp.h>
46 #include <sys/select.h>
47 
48 #include <arpa/inet.h>
49 
50 #include "pigpio.h"
51 #include "command.h"
52 
53 #include "pigpiod_if2.h"
54 
55 #define PI_MAX_REPORTS_PER_READ 4096
56 
57 #define STACK_SIZE (256*1024)
58 
59 #define MAX_PI 32
60 
61 typedef void (*CBF_t) ();
62 
63 struct callback_s
64 {
65 
66  int id;
67  int pi;
68  int gpio;
69  int edge;
70  CBF_t f;
71  void * user;
72  int ex;
75 };
76 
78 {
79 
80  int id;
81  int pi;
82  int event;
84  void * user;
85  int ex;
88 };
89 
90 /* GLOBALS ---------------------------------------------------------------- */
91 
92 static int gPiInUse [MAX_PI];
93 
94 static int gPigCommand [MAX_PI];
95 static int gPigHandle [MAX_PI];
96 static int gPigNotify [MAX_PI];
97 
98 static uint32_t gEventBits [MAX_PI];
99 static uint32_t gNotifyBits [MAX_PI];
100 static uint32_t gLastLevel [MAX_PI];
101 
102 static pthread_t *gPthNotify [MAX_PI];
103 
104 static pthread_mutex_t gCmdMutex [MAX_PI];
105 static int gCancelState [MAX_PI];
106 
109 
112 
113 /* PRIVATE ---------------------------------------------------------------- */
114 
115 static void _pml(int pi)
116 {
117  int cancelState;
118 
119  pthread_setcancelstate(PTHREAD_CANCEL_DISABLE, &cancelState);
120  pthread_mutex_lock(&gCmdMutex[pi]);
121  gCancelState[pi] = cancelState;
122 }
123 
124 static void _pmu(int pi)
125 {
126  int cancelState;
127 
128  cancelState = gCancelState[pi];
129  pthread_mutex_unlock(&gCmdMutex[pi]);
130  pthread_setcancelstate(cancelState, NULL);
131 }
132 
133 static int pigpio_command(int pi, int command, int p1, int p2, int rl)
134 {
135  cmdCmd_t cmd;
136 
137  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi])
138  return pigif_unconnected_pi;
139 
140  cmd.cmd = command;
141  cmd.p1 = p1;
142  cmd.p2 = p2;
143  cmd.res = 0;
144 
145  _pml(pi);
146 
147  if (send(gPigCommand[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd))
148  {
149  _pmu(pi);
150  return pigif_bad_send;
151  }
152 
153  if (recv(gPigCommand[pi], &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd))
154  {
155  _pmu(pi);
156  return pigif_bad_recv;
157  }
158 
159  if (rl) _pmu(pi);
160 
161  return cmd.res;
162 }
163 
164 static int pigpio_notify(int pi)
165 {
166  cmdCmd_t cmd;
167 
168  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi])
169  return pigif_unconnected_pi;
170 
171  cmd.cmd = PI_CMD_NOIB;
172  cmd.p1 = 0;
173  cmd.p2 = 0;
174  cmd.res = 0;
175 
176  _pml(pi);
177 
178  if (send(gPigNotify[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd))
179  {
180  _pmu(pi);
181  return pigif_bad_send;
182  }
183 
184  if (recv(gPigNotify[pi], &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd))
185  {
186  _pmu(pi);
187  return pigif_bad_recv;
188  }
189 
190  _pmu(pi);
191 
192  return cmd.res;
193 }
194 
195 static int pigpio_command_ext
196  (int pi, int command, int p1, int p2, int p3,
197  int extents, gpioExtent_t *ext, int rl)
198 {
199  int i;
200  cmdCmd_t cmd;
201 
202  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi])
203  return pigif_unconnected_pi;
204 
205  cmd.cmd = command;
206  cmd.p1 = p1;
207  cmd.p2 = p2;
208  cmd.p3 = p3;
209 
210  _pml(pi);
211 
212  if (send(gPigCommand[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd))
213  {
214  _pmu(pi);
215  return pigif_bad_send;
216  }
217 
218  for (i=0; i<extents; i++)
219  {
220  if (send(gPigCommand[pi], ext[i].ptr, ext[i].size, 0) != ext[i].size)
221  {
222  _pmu(pi);
223  return pigif_bad_send;
224  }
225  }
226 
227  if (recv(gPigCommand[pi], &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd))
228  {
229  _pmu(pi);
230  return pigif_bad_recv;
231  }
232  if (rl) _pmu(pi);
233 
234  return cmd.res;
235 }
236 
237 static int pigpioOpenSocket(char *addr, char *port)
238 {
239  int sock, err, opt;
240  struct addrinfo hints, *res, *rp;
241  const char *addrStr, *portStr;
242 
243  if (!addr)
244  {
245  addrStr = getenv(PI_ENVADDR);
246 
247  if ((!addrStr) || (!strlen(addrStr)))
248  {
249  addrStr = PI_DEFAULT_SOCKET_ADDR_STR;
250  }
251  }
252  else addrStr = addr;
253 
254  if (!port)
255  {
256  portStr = getenv(PI_ENVPORT);
257 
258  if ((!portStr) || (!strlen(portStr)))
259  {
260  portStr = PI_DEFAULT_SOCKET_PORT_STR;
261  }
262  }
263  else portStr = port;
264 
265  memset (&hints, 0, sizeof (hints));
266 
267  hints.ai_family = PF_UNSPEC;
268  hints.ai_socktype = SOCK_STREAM;
269  hints.ai_flags |= AI_CANONNAME;
270 
271  err = getaddrinfo (addrStr, portStr, &hints, &res);
272 
273  if (err) return pigif_bad_getaddrinfo;
274 
275  for (rp=res; rp!=NULL; rp=rp->ai_next)
276  {
277  sock = socket(rp->ai_family, rp->ai_socktype, rp->ai_protocol);
278 
279  if (sock == -1) continue;
280 
281  /* Disable the Nagle algorithm. */
282  opt = 1;
283  setsockopt(sock, IPPROTO_TCP, TCP_NODELAY, (char*)&opt, sizeof(int));
284 
285  if (connect(sock, rp->ai_addr, rp->ai_addrlen) != -1) break;
286  }
287 
288  freeaddrinfo(res);
289 
290  if (rp == NULL) return pigif_bad_connect;
291 
292  return sock;
293 }
294 
295 static void dispatch_notification(int pi, gpioReport_t *r)
296 {
297  callback_t *p;
298  evtCallback_t *ep;
299  uint32_t changed;
300  int l, g;
301 
302 /*
303  printf("s=%4x f=%4x t=%10u l=%8x\n",
304  r->seqno, r->flags, r->tick, r->level);
305 */
306 
307  if (r->flags == 0)
308  {
309  changed = (r->level ^ gLastLevel[pi]) & gNotifyBits[pi];
310 
311  gLastLevel[pi] = r->level;
312 
313  p = gCallBackFirst;
314 
315  while (p)
316  {
317  if (((p->pi) == pi) && (changed & (1<<(p->gpio))))
318  {
319  if ((r->level) & (1<<(p->gpio))) l = 1; else l = 0;
320  if ((p->edge) ^ l)
321  {
322  if (p->ex) (p->f)(pi, p->gpio, l, r->tick, p->user);
323  else (p->f)(pi, p->gpio, l, r->tick);
324  }
325  }
326  p = p->next;
327  }
328  }
329  else
330  {
331  if ((r->flags) & PI_NTFY_FLAGS_WDOG)
332  {
333  g = (r->flags) & 31;
334 
335  p = gCallBackFirst;
336 
337  while (p)
338  {
339  if (((p->pi) == pi) && ((p->gpio) == g))
340  {
341  if (p->ex) (p->f)(pi, g, PI_TIMEOUT, r->tick, p->user);
342  else (p->f)(pi, g, PI_TIMEOUT, r->tick);
343  }
344  p = p->next;
345  }
346  }
347  else if ((r->flags) & PI_NTFY_FLAGS_EVENT)
348  {
349  g = (r->flags) & 31;
350 
351  ep = geCallBackFirst;
352 
353  while (ep)
354  {
355  if (((ep->pi) == pi) && ((ep->event) == g))
356  {
357  if (ep->ex) (ep->f)(pi, g, r->tick, ep->user);
358  else (ep->f)(pi, g, r->tick);
359  }
360  ep = ep->next;
361  }
362  }
363  }
364 }
365 
366 static void *pthNotifyThread(void *x)
367 {
368  static int got = 0;
369  int pi;
370  int bytes, r;
372 
373  pi = *((int*)x);
374  free(x); /* memory allocated in pigpio_start */
375 
376  while (1)
377  {
378  bytes = read(gPigNotify[pi], (char*)&report+got, sizeof(report)-got);
379 
380  if (bytes > 0) got += bytes;
381  else break;
382 
383  r = 0;
384 
385  while (got >= sizeof(gpioReport_t))
386  {
387  dispatch_notification(pi, &report[r]);
388 
389  r++;
390 
391  got -= sizeof(gpioReport_t);
392  }
393 
394  /* copy any partial report to start of array */
395 
396  if (got && r) report[0] = report[r];
397  }
398 
399  fprintf(stderr, "notify thread for pi %d broke with read error %d\n",
400  pi, bytes);
401 
402  while (1) sleep(1);
403 
404  return NULL;
405 }
406 
407 static void findNotifyBits(int pi)
408 {
409  callback_t *p;
410  uint32_t bits = 0;
411 
412  p = gCallBackFirst;
413 
414  while (p)
415  {
416  if (p->pi == pi) bits |= (1<<(p->gpio));
417  p = p->next;
418  }
419 
420  if (bits != gNotifyBits[pi])
421  {
422  gNotifyBits[pi] = bits;
424  }
425 }
426 
427 static void _wfe(
428  int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *user)
429 {
430  *(int *)user = 1;
431 }
432 
433 static int intCallback(
434  int pi, unsigned user_gpio, unsigned edge, void *f, void *user, int ex)
435 {
436  static int id = 0;
437  callback_t *p;
438 
439  if ((user_gpio >=0) && (user_gpio < 32) && (edge >=0) && (edge <= 2) && f)
440  {
441  /* prevent duplicates */
442 
443  p = gCallBackFirst;
444 
445  while (p)
446  {
447  if ((p->pi == pi) &&
448  (p->gpio == user_gpio) &&
449  (p->edge == edge) &&
450  (p->f == f))
451  {
453  }
454  p = p->next;
455  }
456 
457  p = malloc(sizeof(callback_t));
458 
459  if (p)
460  {
461  if (!gCallBackFirst) gCallBackFirst = p;
462 
463  p->id = id++;
464  p->pi = pi;
465  p->gpio = user_gpio;
466  p->edge = edge;
467  p->f = f;
468  p->user = user;
469  p->ex = ex;
470  p->next = 0;
471  p->prev = gCallBackLast;
472 
473  if (p->prev) (p->prev)->next = p;
474  gCallBackLast = p;
475 
476  findNotifyBits(pi);
477 
478  return p->id;
479  }
480 
481  return pigif_bad_malloc;
482  }
483 
484  return pigif_bad_callback;
485 }
486 
487 static void findEventBits(int pi)
488 {
489  evtCallback_t *ep;
490  uint32_t bits = 0;
491 
492  ep = geCallBackFirst;
493 
494  while (ep)
495  {
496  if (ep->pi == pi) bits |= (1<<(ep->event));
497  ep = ep->next;
498  }
499 
500  if (bits != gEventBits[pi])
501  {
502  gEventBits[pi] = bits;
504  }
505 }
506 
507 static void _ewfe(
508  int pi, unsigned event, uint32_t tick, void *user)
509 {
510  *(int *)user = 1;
511 }
512 
513 static int intEventCallback(
514  int pi, unsigned event, void *f, void *user, int ex)
515 {
516  static int id = 0;
517  evtCallback_t *ep;
518 
519  if ((event >=0) && (event < 32) && f)
520  {
521  /* prevent duplicates */
522 
523  ep = geCallBackFirst;
524 
525  while (ep)
526  {
527  if ((ep->pi == pi) &&
528  (ep->event == event) &&
529  (ep->f == f))
530  {
532  }
533  ep = ep->next;
534  }
535 
536  ep = malloc(sizeof(evtCallback_t));
537 
538  if (ep)
539  {
540  if (!geCallBackFirst) geCallBackFirst = ep;
541 
542  ep->id = id++;
543  ep->pi = pi;
544  ep->event = event;
545  ep->f = f;
546  ep->user = user;
547  ep->ex = ex;
548  ep->next = 0;
549  ep->prev = geCallBackLast;
550 
551  if (ep->prev) (ep->prev)->next = ep;
552  geCallBackLast = ep;
553 
554  findEventBits(pi);
555 
556  return ep->id;
557  }
558 
559  return pigif_bad_malloc;
560  }
561 
562  return pigif_bad_callback;
563 }
564 
565 static int recvMax(int pi, void *buf, int bufsize, int sent)
566 {
567  /*
568  Copy at most bufSize bytes from the receieved message to
569  buf. Discard the rest of the message.
570  */
571  uint8_t scratch[4096];
572  int remaining, fetch, count;
573 
574  if (sent < bufsize) count = sent; else count = bufsize;
575 
576  if (count) recv(gPigCommand[pi], buf, count, MSG_WAITALL);
577 
578  remaining = sent - count;
579 
580  while (remaining)
581  {
582  fetch = remaining;
583  if (fetch > sizeof(scratch)) fetch = sizeof(scratch);
584  recv(gPigCommand[pi], scratch, fetch, MSG_WAITALL);
585  remaining -= fetch;
586  }
587 
588  return count;
589 }
590 
591 /* PUBLIC ----------------------------------------------------------------- */
592 
593 double time_time(void)
594 {
595  struct timeval tv;
596  double t;
597 
598  gettimeofday(&tv, 0);
599 
600  t = (double)tv.tv_sec + ((double)tv.tv_usec / 1E6);
601 
602  return t;
603 }
604 
605 void time_sleep(double seconds)
606 {
607  struct timespec ts, rem;
608 
609  if (seconds > 0.0)
610  {
611  ts.tv_sec = seconds;
612  ts.tv_nsec = (seconds-(double)ts.tv_sec) * 1E9;
613 
614  while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem))
615  {
616  /* copy remaining time to ts */
617  ts.tv_sec = rem.tv_sec;
618  ts.tv_nsec = rem.tv_nsec;
619  }
620  }
621 }
622 
623 char *pigpio_error(int errnum)
624 {
625  if (errnum > -1000) return cmdErrStr(errnum);
626  else
627  {
628  switch(errnum)
629  {
630  case pigif_bad_send:
631  return "failed to send to pigpiod";
632  case pigif_bad_recv:
633  return "failed to receive from pigpiod";
635  return "failed to find address of pigpiod";
636  case pigif_bad_connect:
637  return "failed to connect to pigpiod";
638  case pigif_bad_socket:
639  return "failed to create socket";
640  case pigif_bad_noib:
641  return "failed to open notification in band";
643  return "identical callback exists";
644  case pigif_bad_malloc:
645  return "failed to malloc";
646  case pigif_bad_callback:
647  return "bad callback parameter";
648  case pigif_notify_failed:
649  return "failed to create notification thread";
651  return "callback not found";
653  return "not connected to Pi";
654  case pigif_too_many_pis:
655  return "too many connected Pis";
656 
657  default:
658  return "unknown error";
659  }
660  }
661 }
662 
663 unsigned pigpiod_if_version(void)
664 {
665  return PIGPIOD_IF2_VERSION;
666 }
667 
668 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata)
669 {
670  pthread_t *pth;
671  pthread_attr_t pthAttr;
672 
673  pth = malloc(sizeof(pthread_t));
674 
675  if (pth)
676  {
677  if (pthread_attr_init(&pthAttr))
678  {
679  perror("pthread_attr_init failed");
680  free(pth);
681  return NULL;
682  }
683 
684  if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE))
685  {
686  perror("pthread_attr_setstacksize failed");
687  free(pth);
688  return NULL;
689  }
690 
691  if (pthread_create(pth, &pthAttr, thread_func, userdata))
692  {
693  perror("pthread_create socket failed");
694  free(pth);
695  return NULL;
696  }
697  }
698  return pth;
699 }
700 
701 void stop_thread(pthread_t *pth)
702 {
703  if (pth)
704  {
705  pthread_cancel(*pth);
706  pthread_join(*pth, NULL);
707  free(pth);
708  }
709 }
710 
711 int pigpio_start(char *addrStr, char *portStr)
712 {
713  int pi;
714  int *userdata;
715 
716  if ((!addrStr) || (strlen(addrStr) == 0))
717  {
718  addrStr = "localhost";
719  }
720 
721  for (pi=0; pi<MAX_PI; pi++)
722  {
723  if (!gPiInUse[pi]) break;
724  }
725 
726  if (pi >= MAX_PI) return pigif_too_many_pis;
727 
728  gPiInUse[pi] = 1;
729 
730  pthread_mutex_init(&gCmdMutex[pi], NULL);
731 
732  gPigCommand[pi] = pigpioOpenSocket(addrStr, portStr);
733 
734  if (gPigCommand[pi] >= 0)
735  {
736  gPigNotify[pi] = pigpioOpenSocket(addrStr, portStr);
737 
738  if (gPigNotify[pi] >= 0)
739  {
740  gPigHandle[pi] = pigpio_notify(pi);
741 
742  if (gPigHandle[pi] < 0) return pigif_bad_noib;
743  else
744  {
745  gLastLevel[pi] = read_bank_1(pi);
746 
747  /* must be freed by pthNotifyThread */
748  userdata = malloc(sizeof(*userdata));
749  *userdata = pi;
750 
752 
753  if (gPthNotify[pi]) return pi;
754  else return pigif_notify_failed;
755 
756  }
757  }
758  else return gPigNotify[pi];
759  }
760  else return gPigCommand[pi];
761 }
762 
763 void pigpio_stop(int pi)
764 {
765  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) return;
766 
767  if (gPthNotify[pi])
768  {
769  stop_thread(gPthNotify[pi]);
770  gPthNotify[pi] = 0;
771  }
772 
773  if (gPigCommand[pi] >= 0)
774  {
775  if (gPigHandle[pi] >= 0)
776  {
777  pigpio_command(pi, PI_CMD_NC, gPigHandle[pi], 0, 1);
778  gPigHandle[pi] = -1;
779  }
780 
781  close(gPigCommand[pi]);
782  gPigCommand[pi] = -1;
783  }
784 
785  if (gPigNotify[pi] >= 0)
786  {
787  close(gPigNotify[pi]);
788  gPigNotify[pi] = -1;
789  }
790 
791  gPiInUse[pi] = 0;
792 }
793 
794 int set_mode(int pi, unsigned gpio, unsigned mode)
795  {return pigpio_command(pi, PI_CMD_MODES, gpio, mode, 1);}
796 
797 int get_mode(int pi, unsigned gpio)
798  {return pigpio_command(pi, PI_CMD_MODEG, gpio, 0, 1);}
799 
800 int set_pull_up_down(int pi, unsigned gpio, unsigned pud)
801  {return pigpio_command(pi, PI_CMD_PUD, gpio, pud, 1);}
802 
803 int gpio_read(int pi, unsigned gpio)
804  {return pigpio_command(pi, PI_CMD_READ, gpio, 0, 1);}
805 
806 int gpio_write(int pi, unsigned gpio, unsigned level)
807  {return pigpio_command(pi, PI_CMD_WRITE, gpio, level, 1);}
808 
809 int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle)
810  {return pigpio_command(pi, PI_CMD_PWM, user_gpio, dutycycle, 1);}
811 
812 int get_PWM_dutycycle(int pi, unsigned user_gpio)
813  {return pigpio_command(pi, PI_CMD_GDC, user_gpio, 0, 1);}
814 
815 int set_PWM_range(int pi, unsigned user_gpio, unsigned range)
816  {return pigpio_command(pi, PI_CMD_PRS, user_gpio, range, 1);}
817 
818 int get_PWM_range(int pi, unsigned user_gpio)
819  {return pigpio_command(pi, PI_CMD_PRG, user_gpio, 0, 1);}
820 
821 int get_PWM_real_range(int pi, unsigned user_gpio)
822  {return pigpio_command(pi, PI_CMD_PRRG, user_gpio, 0, 1);}
823 
824 int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency)
825  {return pigpio_command(pi, PI_CMD_PFS, user_gpio, frequency, 1);}
826 
827 int get_PWM_frequency(int pi, unsigned user_gpio)
828  {return pigpio_command(pi, PI_CMD_PFG, user_gpio, 0, 1);}
829 
830 int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth)
831  {return pigpio_command(pi, PI_CMD_SERVO, user_gpio, pulsewidth, 1);}
832 
833 int get_servo_pulsewidth(int pi, unsigned user_gpio)
834  {return pigpio_command(pi, PI_CMD_GPW, user_gpio, 0, 1);}
835 
836 int notify_open(int pi)
837  {return pigpio_command(pi, PI_CMD_NO, 0, 0, 1);}
838 
839 int notify_begin(int pi, unsigned handle, uint32_t bits)
840  {return pigpio_command(pi, PI_CMD_NB, handle, bits, 1);}
841 
842 int notify_pause(int pi, unsigned handle)
843  {return pigpio_command(pi, PI_CMD_NB, handle, 0, 1);}
844 
845 int notify_close(int pi, unsigned handle)
846  {return pigpio_command(pi, PI_CMD_NC, handle, 0, 1);}
847 
848 int set_watchdog(int pi, unsigned user_gpio, unsigned timeout)
849  {return pigpio_command(pi, PI_CMD_WDOG, user_gpio, timeout, 1);}
850 
851 uint32_t read_bank_1(int pi)
852  {return pigpio_command(pi, PI_CMD_BR1, 0, 0, 1);}
853 
854 uint32_t read_bank_2(int pi)
855  {return pigpio_command(pi, PI_CMD_BR2, 0, 0, 1);}
856 
857 int clear_bank_1(int pi, uint32_t levels)
858  {return pigpio_command(pi, PI_CMD_BC1, levels, 0, 1);}
859 
860 int clear_bank_2(int pi, uint32_t levels)
861  {return pigpio_command(pi, PI_CMD_BC2, levels, 0, 1);}
862 
863 int set_bank_1(int pi, uint32_t levels)
864  {return pigpio_command(pi, PI_CMD_BS1, levels, 0, 1);}
865 
866 int set_bank_2(int pi, uint32_t levels)
867  {return pigpio_command(pi, PI_CMD_BS2, levels, 0, 1);}
868 
869 int hardware_clock(int pi, unsigned gpio, unsigned frequency)
870  {return pigpio_command(pi, PI_CMD_HC, gpio, frequency, 1);}
871 
872 int hardware_PWM(int pi, unsigned gpio, unsigned frequency, uint32_t dutycycle)
873 {
874  gpioExtent_t ext[1];
875 
876  /*
877  p1=gpio
878  p2=frequency
879  p3=4
880  ## extension ##
881  uint32_t dutycycle
882  */
883 
884  ext[0].size = sizeof(dutycycle);
885  ext[0].ptr = &dutycycle;
886 
887  return pigpio_command_ext(
888  pi, PI_CMD_HP, gpio, frequency, sizeof(dutycycle), 1, ext, 1);
889 }
890 
891 uint32_t get_current_tick(int pi)
892  {return pigpio_command(pi, PI_CMD_TICK, 0, 0, 1);}
893 
894 uint32_t get_hardware_revision(int pi)
895  {return pigpio_command(pi, PI_CMD_HWVER, 0, 0, 1);}
896 
897 uint32_t get_pigpio_version(int pi)
898  {return pigpio_command(pi, PI_CMD_PIGPV, 0, 0, 1);}
899 
900 int wave_clear(int pi)
901  {return pigpio_command(pi, PI_CMD_WVCLR, 0, 0, 1);}
902 
903 int wave_add_new(int pi)
904  {return pigpio_command(pi, PI_CMD_WVNEW, 0, 0, 1);}
905 
906 int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses)
907 {
908  gpioExtent_t ext[1];
909 
910  /*
911  p1=0
912  p2=0
913  p3=pulses*sizeof(gpioPulse_t)
914  ## extension ##
915  gpioPulse_t[] pulses
916  */
917 
918  if (!numPulses) return 0;
919 
920  ext[0].size = numPulses * sizeof(gpioPulse_t);
921  ext[0].ptr = pulses;
922 
923  return pigpio_command_ext(
924  pi, PI_CMD_WVAG, 0, 0, ext[0].size, 1, ext, 1);
925 }
926 
928  int pi, unsigned user_gpio, unsigned baud, uint32_t databits,
929  uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str)
930 {
931  uint8_t buf[12];
932  gpioExtent_t ext[2];
933 
934  /*
935  p1=user_gpio
936  p2=baud
937  p3=len+12
938  ## extension ##
939  uint32_t databits
940  uint32_t stophalfbits
941  uint32_t offset
942  char[len] str
943  */
944 
945  if (!numChar) return 0;
946 
947  memcpy(buf, &databits, 4);
948  memcpy(buf+4, &stophalfbits, 4);
949  memcpy(buf+8, &offset, 4);
950 
951  ext[0].size = sizeof(buf);
952  ext[0].ptr = buf;
953 
954  ext[1].size = numChar;
955  ext[1].ptr = str;
956 
957  return pigpio_command_ext(pi, PI_CMD_WVAS,
958  user_gpio, baud, numChar+sizeof(buf), 2, ext, 1);
959 }
960 
961 int wave_create(int pi)
962  {return pigpio_command(pi, PI_CMD_WVCRE, 0, 0, 1);}
963 
964 int wave_delete(int pi, unsigned wave_id)
965  {return pigpio_command(pi, PI_CMD_WVDEL, wave_id, 0, 1);}
966 
967 int wave_tx_start(int pi) /* DEPRECATED */
968  {return pigpio_command(pi, PI_CMD_WVGO, 0, 0, 1);}
969 
970 int wave_tx_repeat(int pi) /* DEPRECATED */
971  {return pigpio_command(pi, PI_CMD_WVGOR, 0, 0, 1);}
972 
973 int wave_send_once(int pi, unsigned wave_id)
974  {return pigpio_command(pi, PI_CMD_WVTX, wave_id, 0, 1);}
975 
976 int wave_send_repeat(int pi, unsigned wave_id)
977  {return pigpio_command(pi, PI_CMD_WVTXR, wave_id, 0, 1);}
978 
979 int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode)
980  {return pigpio_command(pi, PI_CMD_WVTXM, wave_id, mode, 1);}
981 
982 int wave_chain(int pi, char *buf, unsigned bufSize)
983 {
984  gpioExtent_t ext[1];
985 
986  /*
987  p1=0
988  p2=0
989  p3=bufSize
990  ## extension ##
991  char buf[bufSize]
992  */
993 
994  ext[0].size = bufSize;
995  ext[0].ptr = buf;
996 
997  return pigpio_command_ext
998  (pi, PI_CMD_WVCHA, 0, 0, bufSize, 1, ext, 1);
999 }
1000 
1001 int wave_tx_at(int pi)
1002  {return pigpio_command(pi, PI_CMD_WVTAT, 0, 0, 1);}
1003 
1004 int wave_tx_busy(int pi)
1005  {return pigpio_command(pi, PI_CMD_WVBSY, 0, 0, 1);}
1006 
1007 int wave_tx_stop(int pi)
1008  {return pigpio_command(pi, PI_CMD_WVHLT, 0, 0, 1);}
1009 
1010 int wave_get_micros(int pi)
1011  {return pigpio_command(pi, PI_CMD_WVSM, 0, 0, 1);}
1012 
1014  {return pigpio_command(pi, PI_CMD_WVSM, 1, 0, 1);}
1015 
1017  {return pigpio_command(pi, PI_CMD_WVSM, 2, 0, 1);}
1018 
1019 int wave_get_pulses(int pi)
1020  {return pigpio_command(pi, PI_CMD_WVSP, 0, 0, 1);}
1021 
1023  {return pigpio_command(pi, PI_CMD_WVSP, 1, 0, 1);}
1024 
1026  {return pigpio_command(pi, PI_CMD_WVSP, 2, 0, 1);}
1027 
1028 int wave_get_cbs(int pi)
1029  {return pigpio_command(pi, PI_CMD_WVSC, 0, 0, 1);}
1030 
1032  {return pigpio_command(pi, PI_CMD_WVSC, 1, 0, 1);}
1033 
1034 int wave_get_max_cbs(int pi)
1035  {return pigpio_command(pi, PI_CMD_WVSC, 2, 0, 1);}
1036 
1037 int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, uint32_t level)
1038 {
1039  gpioExtent_t ext[1];
1040 
1041  /*
1042  p1=user_gpio
1043  p2=pulseLen
1044  p3=4
1045  ## extension ##
1046  unsigned level
1047  */
1048 
1049  ext[0].size = sizeof(uint32_t);
1050  ext[0].ptr = &level;
1051 
1052  return pigpio_command_ext(
1053  pi, PI_CMD_TRIG, user_gpio, pulseLen, 4, 1, ext, 1);
1054 }
1055 
1056 int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady)
1057  {return pigpio_command(pi, PI_CMD_FG, user_gpio, steady, 1);}
1058 
1059 int set_noise_filter(int pi, unsigned user_gpio, unsigned steady, unsigned active)
1060 {
1061  gpioExtent_t ext[1];
1062 
1063  /*
1064  p1=user_gpio
1065  p2=steady
1066  p3=4
1067  ## extension ##
1068  unsigned active
1069  */
1070 
1071  ext[0].size = sizeof(uint32_t);
1072  ext[0].ptr = &active;
1073 
1074  return pigpio_command_ext(
1075  pi, PI_CMD_FN, user_gpio, steady, 4, 1, ext, 1);
1076 }
1077 
1078 int store_script(int pi, char *script)
1079 {
1080  unsigned len;
1081  gpioExtent_t ext[1];
1082 
1083  /*
1084  p1=0
1085  p2=0
1086  p3=len
1087  ## extension ##
1088  char[len] script
1089  */
1090 
1091  len = strlen(script);
1092 
1093  if (!len) return 0;
1094 
1095  ext[0].size = len;
1096  ext[0].ptr = script;
1097 
1098  return pigpio_command_ext(pi, PI_CMD_PROC, 0, 0, len, 1, ext, 1);
1099 }
1100 
1101 int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
1102 {
1103  gpioExtent_t ext[1];
1104 
1105  /*
1106  p1=script id
1107  p2=0
1108  p3=numPar * 4
1109  ## extension ##
1110  uint32_t[numPar] pars
1111  */
1112 
1113  ext[0].size = 4 * numPar;
1114  ext[0].ptr = param;
1115 
1116  return pigpio_command_ext
1117  (pi, PI_CMD_PROCR, script_id, 0, numPar*4, 1, ext, 1);
1118 }
1119 
1120 int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
1121 {
1122  gpioExtent_t ext[1];
1123 
1124  /*
1125  p1=script id
1126  p2=0
1127  p3=numPar * 4
1128  ## extension ##
1129  uint32_t[numPar] pars
1130  */
1131 
1132  ext[0].size = 4 * numPar;
1133  ext[0].ptr = param;
1134 
1135  return pigpio_command_ext
1136  (pi, PI_CMD_PROCU, script_id, 0, numPar*4, 1, ext, 1);
1137 }
1138 
1139 int script_status(int pi, unsigned script_id, uint32_t *param)
1140 {
1141  int status;
1142  uint32_t p[PI_MAX_SCRIPT_PARAMS+1]; /* space for script status */
1143 
1144  status = pigpio_command(pi, PI_CMD_PROCP, script_id, 0, 0);
1145 
1146  if (status > 0)
1147  {
1148  recvMax(pi, p, sizeof(p), status);
1149  status = p[0];
1150  if (param) memcpy(param, p+1, sizeof(p)-4);
1151  }
1152 
1153  _pmu(pi);
1154 
1155  return status;
1156 }
1157 
1158 int stop_script(int pi, unsigned script_id)
1159  {return pigpio_command(pi, PI_CMD_PROCS, script_id, 0, 1);}
1160 
1161 int delete_script(int pi, unsigned script_id)
1162  {return pigpio_command(pi, PI_CMD_PROCD, script_id, 0, 1);}
1163 
1164 int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, uint32_t bbBits)
1165 {
1166  gpioExtent_t ext[1];
1167 
1168  /*
1169  p1=user_gpio
1170  p2=baud
1171  p3=4
1172  ## extension ##
1173  unsigned bbBits
1174  */
1175 
1176  ext[0].size = sizeof(uint32_t);
1177  ext[0].ptr = &bbBits;
1178 
1179  return pigpio_command_ext(
1180  pi, PI_CMD_SLRO, user_gpio, baud, 4, 1, ext, 1);
1181 }
1182 
1183 int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize)
1184 {
1185  int bytes;
1186 
1187  bytes = pigpio_command(pi, PI_CMD_SLR, user_gpio, bufSize, 0);
1188 
1189  if (bytes > 0)
1190  {
1191  bytes = recvMax(pi, buf, bufSize, bytes);
1192  }
1193 
1194  _pmu(pi);
1195 
1196  return bytes;
1197 }
1198 
1199 int bb_serial_read_close(int pi, unsigned user_gpio)
1200  {return pigpio_command(pi, PI_CMD_SLRC, user_gpio, 0, 1);}
1201 
1202 int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert)
1203  {return pigpio_command(pi, PI_CMD_SLRI, user_gpio, invert, 1);}
1204 
1205 int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags)
1206 {
1207  gpioExtent_t ext[1];
1208 
1209  /*
1210  p1=i2c_bus
1211  p2=i2c_addr
1212  p3=4
1213  ## extension ##
1214  uint32_t i2c_flags
1215  */
1216 
1217  ext[0].size = sizeof(uint32_t);
1218  ext[0].ptr = &i2c_flags;
1219 
1220  return pigpio_command_ext
1221  (pi, PI_CMD_I2CO, i2c_bus, i2c_addr, 4, 1, ext, 1);
1222 }
1223 
1224 int i2c_close(int pi, unsigned handle)
1225  {return pigpio_command(pi, PI_CMD_I2CC, handle, 0, 1);}
1226 
1227 int i2c_write_quick(int pi, unsigned handle, unsigned bit)
1228  {return pigpio_command(pi, PI_CMD_I2CWQ, handle, bit, 1);}
1229 
1230 int i2c_write_byte(int pi, unsigned handle, unsigned val)
1231  {return pigpio_command(pi, PI_CMD_I2CWS, handle, val, 1);}
1232 
1233 int i2c_read_byte(int pi, unsigned handle)
1234  {return pigpio_command(pi, PI_CMD_I2CRS, handle, 0, 1);}
1235 
1236 int i2c_write_byte_data(int pi, unsigned handle, unsigned reg, uint32_t val)
1237 {
1238  gpioExtent_t ext[1];
1239 
1240  /*
1241  p1=handle
1242  p2=reg
1243  p3=4
1244  ## extension ##
1245  uint32_t val
1246  */
1247 
1248  ext[0].size = sizeof(uint32_t);
1249  ext[0].ptr = &val;
1250 
1251  return pigpio_command_ext
1252  (pi, PI_CMD_I2CWB, handle, reg, 4, 1, ext, 1);
1253 }
1254 
1255 int i2c_write_word_data(int pi, unsigned handle, unsigned reg, uint32_t val)
1256 {
1257  gpioExtent_t ext[1];
1258 
1259  /*
1260  p1=handle
1261  p2=reg
1262  p3=4
1263  ## extension ##
1264  uint32_t val
1265  */
1266 
1267  ext[0].size = sizeof(uint32_t);
1268  ext[0].ptr = &val;
1269 
1270  return pigpio_command_ext
1271  (pi, PI_CMD_I2CWW, handle, reg, 4, 1, ext, 1);
1272 }
1273 
1274 int i2c_read_byte_data(int pi, unsigned handle, unsigned reg)
1275  {return pigpio_command(pi, PI_CMD_I2CRB, handle, reg, 1);}
1276 
1277 int i2c_read_word_data(int pi, unsigned handle, unsigned reg)
1278  {return pigpio_command(pi, PI_CMD_I2CRW, handle, reg, 1);}
1279 
1280 int i2c_process_call(int pi, unsigned handle, unsigned reg, uint32_t val)
1281 {
1282  gpioExtent_t ext[1];
1283 
1284  /*
1285  p1=handle
1286  p2=reg
1287  p3=4
1288  ## extension ##
1289  uint32_t val
1290  */
1291 
1292  ext[0].size = sizeof(uint32_t);
1293  ext[0].ptr = &val;
1294 
1295  return pigpio_command_ext
1296  (pi, PI_CMD_I2CPK, handle, reg, 4, 1, ext, 1);
1297 }
1298 
1300  int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
1301 {
1302  gpioExtent_t ext[1];
1303 
1304  /*
1305  p1=handle
1306  p2=reg
1307  p3=count
1308  ## extension ##
1309  char buf[count]
1310  */
1311 
1312  ext[0].size = count;
1313  ext[0].ptr = buf;
1314 
1315  return pigpio_command_ext
1316  (pi, PI_CMD_I2CWK, handle, reg, count, 1, ext, 1);
1317 }
1318 
1319 int i2c_read_block_data(int pi, unsigned handle, unsigned reg, char *buf)
1320 {
1321  int bytes;
1322 
1323  bytes = pigpio_command(pi, PI_CMD_I2CRK, handle, reg, 0);
1324 
1325  if (bytes > 0)
1326  {
1327  bytes = recvMax(pi, buf, 32, bytes);
1328  }
1329 
1330  _pmu(pi);
1331 
1332  return bytes;
1333 }
1334 
1336  int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
1337 {
1338  int bytes;
1339  gpioExtent_t ext[1];
1340 
1341  /*
1342  p1=handle
1343  p2=reg
1344  p3=count
1345  ## extension ##
1346  char buf[count]
1347  */
1348 
1349  ext[0].size = count;
1350  ext[0].ptr = buf;
1351 
1352  bytes = pigpio_command_ext
1353  (pi, PI_CMD_I2CPK, handle, reg, count, 1, ext, 0);
1354 
1355  if (bytes > 0)
1356  {
1357  bytes = recvMax(pi, buf, 32, bytes);
1358  }
1359 
1360  _pmu(pi);
1361 
1362  return bytes;
1363 }
1364 
1366  int pi, unsigned handle, unsigned reg, char *buf, uint32_t count)
1367 {
1368  int bytes;
1369  gpioExtent_t ext[1];
1370 
1371  /*
1372  p1=handle
1373  p2=reg
1374  p3=4
1375  ## extension ##
1376  uint32_t count
1377  */
1378 
1379  ext[0].size = sizeof(uint32_t);
1380  ext[0].ptr = &count;
1381 
1382  bytes = pigpio_command_ext
1383  (pi, PI_CMD_I2CRI, handle, reg, 4, 1, ext, 0);
1384 
1385  if (bytes > 0)
1386  {
1387  bytes = recvMax(pi, buf, count, bytes);
1388  }
1389 
1390  _pmu(pi);
1391 
1392  return bytes;
1393 }
1394 
1395 
1397  int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
1398 {
1399  gpioExtent_t ext[1];
1400 
1401  /*
1402  p1=handle
1403  p2=reg
1404  p3=count
1405  ## extension ##
1406  char buf[count]
1407  */
1408 
1409  ext[0].size = count;
1410  ext[0].ptr = buf;
1411 
1412  return pigpio_command_ext
1413  (pi, PI_CMD_I2CWI, handle, reg, count, 1, ext, 1);
1414 }
1415 
1416 int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count)
1417 {
1418  int bytes;
1419 
1420  bytes = pigpio_command(pi, PI_CMD_I2CRD, handle, count, 0);
1421 
1422  if (bytes > 0)
1423  {
1424  bytes = recvMax(pi, buf, count, bytes);
1425  }
1426 
1427  _pmu(pi);
1428 
1429  return bytes;
1430 }
1431 
1432 int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count)
1433 {
1434  gpioExtent_t ext[1];
1435 
1436  /*
1437  p1=handle
1438  p2=0
1439  p3=count
1440  ## extension ##
1441  char buf[count]
1442  */
1443 
1444  ext[0].size = count;
1445  ext[0].ptr = buf;
1446 
1447  return pigpio_command_ext
1448  (pi, PI_CMD_I2CWD, handle, 0, count, 1, ext, 1);
1449 }
1450 
1452  int pi,
1453  unsigned handle,
1454  char *inBuf,
1455  unsigned inLen,
1456  char *outBuf,
1457  unsigned outLen)
1458 {
1459  int bytes;
1460  gpioExtent_t ext[1];
1461 
1462  /*
1463  p1=handle
1464  p2=0
1465  p3=inLen
1466  ## extension ##
1467  char inBuf[inLen]
1468  */
1469 
1470  ext[0].size = inLen;
1471  ext[0].ptr = inBuf;
1472 
1473  bytes = pigpio_command_ext
1474  (pi, PI_CMD_I2CZ, handle, 0, inLen, 1, ext, 0);
1475 
1476  if (bytes > 0)
1477  {
1478  bytes = recvMax(pi, outBuf, outLen, bytes);
1479  }
1480 
1481  _pmu(pi);
1482 
1483  return bytes;
1484 }
1485 
1486 int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud)
1487 {
1488  gpioExtent_t ext[1];
1489 
1490  /*
1491  p1=SDA
1492  p2=SCL
1493  p3=4
1494  ## extension ##
1495  uint32_t baud
1496  */
1497 
1498  ext[0].size = sizeof(uint32_t);
1499  ext[0].ptr = &baud;
1500 
1501  return pigpio_command_ext
1502  (pi, PI_CMD_BI2CO, SDA, SCL, 4, 1, ext, 1);
1503 }
1504 
1505 int bb_i2c_close(int pi, unsigned SDA)
1506  {return pigpio_command(pi, PI_CMD_BI2CC, SDA, 0, 1);}
1507 
1509  int pi,
1510  unsigned SDA,
1511  char *inBuf,
1512  unsigned inLen,
1513  char *outBuf,
1514  unsigned outLen)
1515 {
1516  int bytes;
1517  gpioExtent_t ext[1];
1518 
1519  /*
1520  p1=SDA
1521  p2=0
1522  p3=inLen
1523  ## extension ##
1524  char inBuf[inLen]
1525  */
1526 
1527  ext[0].size = inLen;
1528  ext[0].ptr = inBuf;
1529 
1530  bytes = pigpio_command_ext
1531  (pi, PI_CMD_BI2CZ, SDA, 0, inLen, 1, ext, 0);
1532 
1533  if (bytes > 0)
1534  {
1535  bytes = recvMax(pi, outBuf, outLen, bytes);
1536  }
1537 
1538  _pmu(pi);
1539 
1540  return bytes;
1541 }
1542 
1544  int pi,
1545  unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK,
1546  unsigned baud, unsigned spiFlags)
1547 {
1548  uint8_t buf[20];
1549  gpioExtent_t ext[1];
1550 
1551  /*
1552  p1=CS
1553  p2=0
1554  p3=20
1555  ## extension ##
1556  uint32_t MISO
1557  uint32_t MOSI
1558  uint32_t SCLK
1559  uint32_t baud
1560  uint32_t spiFlags
1561  */
1562 
1563  ext[0].size = 20;
1564  ext[0].ptr = &buf;
1565 
1566  memcpy(buf + 0, &MISO, 4);
1567  memcpy(buf + 4, &MOSI, 4);
1568  memcpy(buf + 8, &SCLK, 4);
1569  memcpy(buf + 12, &baud, 4);
1570  memcpy(buf + 16, &spiFlags, 4);
1571 
1572  return pigpio_command_ext
1573  (pi, PI_CMD_BSPIO, CS, 0, 20, 1, ext, 1);
1574 }
1575 
1576 int bb_spi_close(int pi, unsigned CS)
1577  {return pigpio_command(pi, PI_CMD_BSPIC, CS, 0, 1);}
1578 
1580  int pi,
1581  unsigned CS,
1582  char *txBuf,
1583  char *rxBuf,
1584  unsigned count)
1585 {
1586  int bytes;
1587  gpioExtent_t ext[1];
1588 
1589  /*
1590  p1=CS
1591  p2=0
1592  p3=count
1593  ## extension ##
1594  char txBuf[count]
1595  */
1596 
1597  ext[0].size = count;
1598  ext[0].ptr = txBuf;
1599 
1600  bytes = pigpio_command_ext
1601  (pi, PI_CMD_BSPIX, CS, 0, count, 1, ext, 0);
1602 
1603  if (bytes > 0)
1604  {
1605  bytes = recvMax(pi, rxBuf, count, bytes);
1606  }
1607 
1608  _pmu(pi);
1609 
1610  return bytes;
1611 }
1612 
1613 int spi_open(int pi, unsigned channel, unsigned speed, uint32_t flags)
1614 {
1615  gpioExtent_t ext[1];
1616 
1617  /*
1618  p1=channel
1619  p2=speed
1620  p3=4
1621  ## extension ##
1622  uint32_t flags
1623  */
1624 
1625  ext[0].size = sizeof(uint32_t);
1626  ext[0].ptr = &flags;
1627 
1628  return pigpio_command_ext
1629  (pi, PI_CMD_SPIO, channel, speed, 4, 1, ext, 1);
1630 }
1631 
1632 int spi_close(int pi, unsigned handle)
1633  {return pigpio_command(pi, PI_CMD_SPIC, handle, 0, 1);}
1634 
1635 int spi_read(int pi, unsigned handle, char *buf, unsigned count)
1636 {
1637  int bytes;
1638 
1639  bytes = pigpio_command
1640  (pi, PI_CMD_SPIR, handle, count, 0);
1641 
1642  if (bytes > 0)
1643  {
1644  bytes = recvMax(pi, buf, count, bytes);
1645  }
1646 
1647  _pmu(pi);
1648 
1649  return bytes;
1650 }
1651 
1652 int spi_write(int pi, unsigned handle, char *buf, unsigned count)
1653 {
1654  gpioExtent_t ext[1];
1655 
1656  /*
1657  p1=handle
1658  p2=0
1659  p3=count
1660  ## extension ##
1661  char buf[count]
1662  */
1663 
1664  ext[0].size = count;
1665  ext[0].ptr = buf;
1666 
1667  return pigpio_command_ext
1668  (pi, PI_CMD_SPIW, handle, 0, count, 1, ext, 1);
1669 }
1670 
1671 int spi_xfer(int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count)
1672 {
1673  int bytes;
1674  gpioExtent_t ext[1];
1675 
1676  /*
1677  p1=handle
1678  p2=0
1679  p3=count
1680  ## extension ##
1681  char buf[count]
1682  */
1683 
1684  ext[0].size = count;
1685  ext[0].ptr = txBuf;
1686 
1687  bytes = pigpio_command_ext
1688  (pi, PI_CMD_SPIX, handle, 0, count, 1, ext, 0);
1689 
1690  if (bytes > 0)
1691  {
1692  bytes = recvMax(pi, rxBuf, count, bytes);
1693  }
1694 
1695  _pmu(pi);
1696 
1697  return bytes;
1698 }
1699 
1700 int serial_open(int pi, char *dev, unsigned baud, unsigned flags)
1701 {
1702  int len;
1703  gpioExtent_t ext[1];
1704 
1705  len = strlen(dev);
1706 
1707  /*
1708  p1=baud
1709  p2=flags
1710  p3=len
1711  ## extension ##
1712  char dev[len]
1713  */
1714 
1715  ext[0].size = len;
1716  ext[0].ptr = dev;
1717 
1718  return pigpio_command_ext
1719  (pi, PI_CMD_SERO, baud, flags, len, 1, ext, 1);
1720 }
1721 
1722 int serial_close(int pi, unsigned handle)
1723  {return pigpio_command(pi, PI_CMD_SERC, handle, 0, 1);}
1724 
1725 int serial_write_byte(int pi, unsigned handle, unsigned val)
1726  {return pigpio_command(pi, PI_CMD_SERWB, handle, val, 1);}
1727 
1728 int serial_read_byte(int pi, unsigned handle)
1729  {return pigpio_command(pi, PI_CMD_SERRB, handle, 0, 1);}
1730 
1731 int serial_write(int pi, unsigned handle, char *buf, unsigned count)
1732 {
1733  gpioExtent_t ext[1];
1734 
1735  /*
1736  p1=handle
1737  p2=0
1738  p3=count
1739  ## extension ##
1740  char buf[count]
1741  */
1742 
1743  ext[0].size = count;
1744  ext[0].ptr = buf;
1745 
1746  return pigpio_command_ext
1747  (pi, PI_CMD_SERW, handle, 0, count, 1, ext, 1);
1748 }
1749 
1750 int serial_read(int pi, unsigned handle, char *buf, unsigned count)
1751 {
1752  int bytes;
1753 
1754  bytes = pigpio_command
1755  (pi, PI_CMD_SERR, handle, count, 0);
1756 
1757  if (bytes > 0)
1758  {
1759  bytes = recvMax(pi, buf, count, bytes);
1760  }
1761 
1762  _pmu(pi);
1763 
1764  return bytes;
1765 }
1766 
1767 int serial_data_available(int pi, unsigned handle)
1768  {return pigpio_command(pi, PI_CMD_SERDA, handle, 0, 1);}
1769 
1770 int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned count)
1771 {
1772  gpioExtent_t ext[1];
1773 
1774  /*
1775  p1=arg1
1776  p2=arg2
1777  p3=count
1778  ## extension ##
1779  char argx[count]
1780  */
1781 
1782  ext[0].size = count;
1783  ext[0].ptr = argx;
1784 
1785  return pigpio_command_ext(
1786  pi, PI_CMD_CF1, arg1, arg2, count, 1, ext, 1);
1787 }
1788 
1789 
1790 int custom_2(int pi, unsigned arg1, char *argx, unsigned count,
1791  char *retBuf, uint32_t retMax)
1792 {
1793  int bytes;
1794  gpioExtent_t ext[1];
1795 
1796  /*
1797  p1=arg1
1798  p2=retMax
1799  p3=count
1800  ## extension ##
1801  char argx[count]
1802  */
1803 
1804  ext[0].size = count;
1805  ext[0].ptr = argx;
1806 
1807  bytes = pigpio_command_ext
1808  (pi, PI_CMD_CF2, arg1, retMax, count, 1, ext, 0);
1809 
1810  if (bytes > 0)
1811  {
1812  bytes = recvMax(pi, retBuf, retMax, bytes);
1813  }
1814 
1815  _pmu(pi);
1816 
1817  return bytes;
1818 }
1819 
1820 int get_pad_strength(int pi, unsigned pad)
1821  {return pigpio_command(pi, PI_CMD_PADG, pad, 0, 1);}
1822 
1823 int set_pad_strength(int pi, unsigned pad, unsigned padStrength)
1824  {return pigpio_command(pi, PI_CMD_PADS, pad, padStrength, 1);}
1825 
1826 int shell_(int pi, char *scriptName, char *scriptString)
1827 {
1828  int ln, ls;
1829  gpioExtent_t ext[2];
1830 
1831  ln = strlen(scriptName);
1832  ls = strlen(scriptString);
1833  /*
1834  p1=len(scriptName)
1835  p2=0
1836  p3=len(scriptName) + len(scriptString) + 1
1837  ## extension ##
1838  char[]
1839  */
1840 
1841  ext[0].size = ln + 1; /* include null byte */
1842  ext[0].ptr = scriptName;
1843 
1844  ext[1].size = ls;
1845  ext[1].ptr = scriptString;
1846 
1847  return pigpio_command_ext
1848  (pi, PI_CMD_SHELL, ln, 0, ln+ls+1, 2, ext, 1);
1849 }
1850 
1851 int file_open(int pi, char *file, unsigned mode)
1852 {
1853  int len;
1854  gpioExtent_t ext[1];
1855 
1856  len = strlen(file);
1857 
1858  /*
1859  p1=mode
1860  p2=0
1861  p3=len
1862  ## extension ##
1863  char file[len]
1864  */
1865 
1866  ext[0].size = len;
1867  ext[0].ptr = file;
1868 
1869  return pigpio_command_ext
1870  (pi, PI_CMD_FO, mode, 0, len, 1, ext, 1);
1871 }
1872 
1873 int file_close(int pi, unsigned handle)
1874  {return pigpio_command(pi, PI_CMD_FC, handle, 0, 1);}
1875 
1876 int file_write(int pi, unsigned handle, char *buf, unsigned count)
1877 {
1878  gpioExtent_t ext[1];
1879 
1880  /*
1881  p1=handle
1882  p2=0
1883  p3=count
1884  ## extension ##
1885  char buf[count]
1886  */
1887 
1888  ext[0].size = count;
1889  ext[0].ptr = buf;
1890 
1891  return pigpio_command_ext
1892  (pi, PI_CMD_FW, handle, 0, count, 1, ext, 1);
1893 }
1894 
1895 int file_read(int pi, unsigned handle, char *buf, unsigned count)
1896 {
1897  int bytes;
1898 
1899  bytes = pigpio_command
1900  (pi, PI_CMD_FR, handle, count, 0);
1901 
1902  if (bytes > 0)
1903  {
1904  bytes = recvMax(pi, buf, count, bytes);
1905  }
1906 
1907  _pmu(pi);
1908 
1909  return bytes;
1910 }
1911 
1912 int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom)
1913 {
1914  gpioExtent_t ext[1];
1915 
1916  /*
1917  p1=handle
1918  p2=seekOffset
1919  p3=4
1920  ## extension ##
1921  uint32_t seekFrom
1922  */
1923 
1924  ext[0].size = sizeof(uint32_t);
1925  ext[0].ptr = &seekFrom;
1926 
1927  return pigpio_command_ext
1928  (pi, PI_CMD_FS, handle, seekOffset, 4, 1, ext, 1);
1929 }
1930 
1931 int file_list(int pi, char *fpat, char *buf, unsigned count)
1932 {
1933  int len;
1934  int bytes;
1935  gpioExtent_t ext[1];
1936 
1937  len = strlen(fpat);
1938 
1939  /*
1940  p1=60000
1941  p2=0
1942  p3=len
1943  ## extension ##
1944  char fpat[len]
1945  */
1946 
1947  ext[0].size = len;
1948  ext[0].ptr = fpat;
1949 
1950  bytes = pigpio_command_ext(pi, PI_CMD_FL, 60000, 0, len, 1, ext, 0);
1951 
1952  if (bytes > 0)
1953  {
1954  bytes = recvMax(pi, buf, count, bytes);
1955  }
1956 
1957  _pmu(pi);
1958 
1959  return bytes;
1960 }
1961 
1962 int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f)
1963  {return intCallback(pi, user_gpio, edge, f, 0, 0);}
1964 
1966  int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user)
1967  {return intCallback(pi, user_gpio, edge, f, user, 1);}
1968 
1969 int callback_cancel(unsigned id)
1970 {
1971  callback_t *p;
1972  int pi;
1973 
1974  p = gCallBackFirst;
1975 
1976  while (p)
1977  {
1978  if (p->id == id)
1979  {
1980  pi = p->pi;
1981 
1982  if (p->prev) {p->prev->next = p->next;}
1983  else {gCallBackFirst = p->next;}
1984 
1985  if (p->next) {p->next->prev = p->prev;}
1986  else {gCallBackLast = p->prev;}
1987 
1988  free(p);
1989 
1990  findNotifyBits(pi);
1991 
1992  return 0;
1993  }
1994  p = p->next;
1995  }
1996  return pigif_callback_not_found;
1997 }
1998 
1999 int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout)
2000 {
2001  int triggered = 0;
2002  int id;
2003  double due;
2004 
2005  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi])
2006  return pigif_unconnected_pi;
2007 
2008  if (timeout <= 0.0) return 0;
2009 
2010  due = time_time() + timeout;
2011 
2012  id = callback_ex(pi, user_gpio, edge, _wfe, &triggered);
2013 
2014  while (!triggered && (time_time() < due)) time_sleep(0.05);
2015 
2016  callback_cancel(id);
2017 
2018  return triggered;
2019 }
2020 
2021 int bsc_xfer(int pi, bsc_xfer_t *bscxfer)
2022 {
2023  int bytes;
2024  int status;
2025  gpioExtent_t ext[1];
2026 
2027  /*
2028  p1=control
2029  p2=0
2030  p3=len
2031  ## extension ##
2032  char buf[len]
2033  */
2034 
2035  ext[0].size = bscxfer->txCnt;
2036  ext[0].ptr = bscxfer->txBuf;
2037 
2038  bytes = pigpio_command_ext
2039  (pi, PI_CMD_BSCX, bscxfer->control, 0, bscxfer->txCnt, 1, ext, 0);
2040 
2041  if (bytes > 0)
2042  {
2043  recvMax(pi, &status, 4, 4);
2044  status = ntohl(status);
2045  bytes -= 4;
2046  bytes = recvMax(pi, bscxfer->rxBuf, sizeof(bscxfer->rxBuf), bytes);
2047  bscxfer->rxCnt = bytes;
2048  }
2049  else
2050  {
2051  status = bytes;
2052  }
2053 
2054  _pmu(pi);
2055 
2056  return status;
2057 }
2058 
2059 
2060 int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer)
2061 {
2062  int control = 0;
2063 
2064  if (i2c_addr) control = (i2c_addr<<16) | 0x305;
2065  bscxfer->control = control;
2066  return bsc_xfer(pi, bscxfer);
2067 }
2068 
2069 
2070 int event_callback(int pi, unsigned event, evtCBFunc_t f)
2071  {return intEventCallback(pi, event, f, 0, 0);}
2072 
2074  int pi, unsigned event, evtCBFuncEx_t f, void *user)
2075  {return intEventCallback(pi, event, f, user, 1);}
2076 
2077 int event_callback_cancel(unsigned id)
2078 {
2079  evtCallback_t *ep;
2080  int pi;
2081 
2082  ep = geCallBackFirst;
2083 
2084  while (ep)
2085  {
2086  if (ep->id == id)
2087  {
2088  pi = ep->pi;
2089 
2090  if (ep->prev) {ep->prev->next = ep->next;}
2091  else {geCallBackFirst = ep->next;}
2092 
2093  if (ep->next) {ep->next->prev = ep->prev;}
2094  else {geCallBackLast = ep->prev;}
2095 
2096  free(ep);
2097 
2098  findEventBits(pi);
2099 
2100  return 0;
2101  }
2102  ep = ep->next;
2103  }
2104  return pigif_callback_not_found;
2105 }
2106 
2107 int wait_for_event(int pi, unsigned event, double timeout)
2108 {
2109  int triggered = 0;
2110  int id;
2111  double due;
2112 
2113  if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi])
2114  return pigif_unconnected_pi;
2115 
2116  if (timeout <= 0.0) return 0;
2117 
2118  due = time_time() + timeout;
2119 
2120  id = event_callback_ex(pi, event, _ewfe, &triggered);
2121 
2122  while (!triggered && (time_time() < due)) time_sleep(0.05);
2123 
2125 
2126  return triggered;
2127 }
2128 
2129 int event_trigger(int pi, unsigned event)
2130  {return pigpio_command(pi, PI_CMD_EVM, event, 0, 1);}
2131 
int notify_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:845
int wave_tx_start(int pi)
Definition: pigpiod_if2.c:967
uint32_t tick
Definition: pigpio.h:418
int bb_i2c_zip(int pi, unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if2.c:1508
#define PI_CMD_PRS
Definition: pigpio.h:6067
int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom)
Definition: pigpiod_if2.c:1912
static int gPiInUse[MAX_PI]
Definition: pigpiod_if2.c:92
#define PI_CMD_WVSC
Definition: pigpio.h:6097
#define PI_CMD_FL
Definition: pigpio.h:6186
char rxBuf[BSC_FIFO_SIZE]
Definition: pigpio.h:505
int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer)
Definition: pigpiod_if2.c:2060
int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, uint32_t bbBits)
Definition: pigpiod_if2.c:1164
#define PI_CMD_CF1
Definition: pigpio.h:6154
int spi_open(int pi, unsigned channel, unsigned speed, uint32_t flags)
Definition: pigpiod_if2.c:1613
#define PI_CMD_HWVER
Definition: pigpio.h:6078
int wave_send_repeat(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:976
#define PI_CMD_BR1
Definition: pigpio.h:6071
int wave_get_max_micros(int pi)
Definition: pigpiod_if2.c:1016
evtCallback_t * next
Definition: pigpiod_if2.c:87
#define PI_CMD_BR2
Definition: pigpio.h:6072
int wave_add_new(int pi)
Definition: pigpiod_if2.c:903
#define PI_CMD_NC
Definition: pigpio.h:6082
static int pigpio_command_ext(int pi, int command, int p1, int p2, int p3, int extents, gpioExtent_t *ext, int rl)
Definition: pigpiod_if2.c:196
void * user
Definition: pigpiod_if.c:68
int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady)
Definition: pigpiod_if2.c:1056
static uint32_t gEventBits[MAX_PI]
Definition: pigpiod_if2.c:98
int i2c_zip(int pi, unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if2.c:1451
#define PI_CMD_PROCR
Definition: pigpio.h:6101
int wave_tx_repeat(int pi)
Definition: pigpiod_if2.c:970
int set_watchdog(int pi, unsigned user_gpio, unsigned timeout)
Definition: pigpiod_if2.c:848
#define PI_CMD_WVTXR
Definition: pigpio.h:6113
#define PI_ENVADDR
Definition: pigpio.h:385
#define PI_CMD_I2CWS
Definition: pigpio.h:6122
int bsc_xfer(int pi, bsc_xfer_t *bscxfer)
Definition: pigpiod_if2.c:2021
#define PI_CMD_BC2
Definition: pigpio.h:6074
int gpio_read(int pi, unsigned gpio)
Definition: pigpiod_if2.c:803
uint16_t flags
Definition: pigpio.h:417
int txCnt
Definition: pigpio.h:506
int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned count)
Definition: pigpiod_if2.c:1770
int rxCnt
Definition: pigpio.h:504
static void _wfe(int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *user)
Definition: pigpiod_if2.c:427
#define PI_CMD_FO
Definition: pigpio.h:6181
#define PI_NTFY_FLAGS_EVENT
Definition: pigpio.h:624
#define PI_CMD_PFS
Definition: pigpio.h:6068
evtCallback_t * prev
Definition: pigpiod_if2.c:86
int i2c_write_byte_data(int pi, unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if2.c:1236
int get_PWM_dutycycle(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:812
uint32_t p3
Definition: command.h:61
uint32_t get_pigpio_version(int pi)
Definition: pigpiod_if2.c:897
unsigned pigpiod_if_version(void)
Definition: pigpiod_if2.c:663
static int pigpio_command(int pi, int command, int p1, int p2, int rl)
Definition: pigpiod_if2.c:133
int set_PWM_range(int pi, unsigned user_gpio, unsigned range)
Definition: pigpiod_if2.c:815
void(* CBFunc_t)(unsigned user_gpio, unsigned level, uint32_t tick)
Definition: pigpiod_if.h:288
#define PI_CMD_PFG
Definition: pigpio.h:6084
int event_callback(int pi, unsigned event, evtCBFunc_t f)
Definition: pigpiod_if2.c:2070
static int intCallback(int pi, unsigned user_gpio, unsigned edge, void *f, void *user, int ex)
Definition: pigpiod_if2.c:433
#define PI_CMD_FG
Definition: pigpio.h:6170
#define PI_CMD_GPW
Definition: pigpio.h:6149
#define PI_CMD_SPIR
Definition: pigpio.h:6136
#define PI_CMD_I2CWB
Definition: pigpio.h:6124
int file_write(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1876
#define PI_CMD_SPIX
Definition: pigpio.h:6138
int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses)
Definition: pigpiod_if2.c:906
uint32_t control
Definition: pigpio.h:503
#define PI_MAX_REPORTS_PER_READ
Definition: pigpiod_if2.c:55
int get_mode(int pi, unsigned gpio)
Definition: pigpiod_if2.c:797
#define PI_CMD_MODES
Definition: pigpio.h:6061
#define PI_CMD_BI2CC
Definition: pigpio.h:6157
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 wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout)
Definition: pigpiod_if2.c:1999
#define PI_CMD_SPIW
Definition: pigpio.h:6137
int custom_2(int pi, unsigned arg1, char *argx, unsigned count, char *retBuf, uint32_t retMax)
Definition: pigpiod_if2.c:1790
int get_PWM_range(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:818
int wave_get_high_pulses(int pi)
Definition: pigpiod_if2.c:1022
int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if2.c:1120
int notify_open(int pi)
Definition: pigpiod_if2.c:836
int i2c_read_block_data(int pi, unsigned handle, unsigned reg, char *buf)
Definition: pigpiod_if2.c:1319
#define PI_CMD_BC1
Definition: pigpio.h:6073
int wave_chain(int pi, char *buf, unsigned bufSize)
Definition: pigpiod_if2.c:982
#define PI_CMD_WVNEW
Definition: pigpio.h:6114
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
#define PI_CMD_PRG
Definition: pigpio.h:6083
#define PI_CMD_WVSP
Definition: pigpio.h:6096
#define PI_CMD_I2CRK
Definition: pigpio.h:6127
int wave_send_once(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:973
int i2c_read_word_data(int pi, unsigned handle, unsigned reg)
Definition: pigpiod_if2.c:1277
#define PI_CMD_SERDA
Definition: pigpio.h:6146
int wave_get_max_pulses(int pi)
Definition: pigpiod_if2.c:1025
int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1416
int bb_serial_read_close(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:1199
#define PI_CMD_READ
Definition: pigpio.h:6064
uint32_t p1
Definition: command.h:57
static int recvMax(int pi, void *buf, int bufsize, int sent)
Definition: pigpiod_if2.c:565
#define PI_CMD_WVCHA
Definition: pigpio.h:6163
#define PI_CMD_WVHLT
Definition: pigpio.h:6094
#define PI_CMD_SERO
Definition: pigpio.h:6140
#define PI_CMD_HP
Definition: pigpio.h:6152
#define PI_CMD_PUD
Definition: pigpio.h:6063
int wave_get_cbs(int pi)
Definition: pigpiod_if2.c:1028
handle
Definition: PCF8591.py:19
int wave_tx_at(int pi)
Definition: pigpiod_if2.c:1001
int get_pad_strength(int pi, unsigned pad)
Definition: pigpiod_if2.c:1820
void stop_thread(pthread_t *pth)
Definition: pigpiod_if2.c:701
static callback_t * gCallBackLast
Definition: pigpiod_if2.c:108
#define PI_CMD_FC
Definition: pigpio.h:6182
int hardware_PWM(int pi, unsigned gpio, unsigned frequency, uint32_t dutycycle)
Definition: pigpiod_if2.c:872
#define PI_CMD_SPIO
Definition: pigpio.h:6134
#define PI_CMD_PROC
Definition: pigpio.h:6099
static void dispatch_notification(int pi, gpioReport_t *r)
Definition: pigpiod_if2.c:295
#define PI_CMD_FR
Definition: pigpio.h:6183
static int gPigCommand[MAX_PI]
Definition: pigpiod_if2.c:94
#define PI_CMD_WVTXM
Definition: pigpio.h:6175
int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize)
Definition: pigpiod_if2.c:1183
#define PI_CMD_I2CC
Definition: pigpio.h:6117
#define PI_CMD_WVAG
Definition: pigpio.h:6089
int shell_(int pi, char *scriptName, char *scriptString)
Definition: pigpiod_if2.c:1826
#define PI_CMD_WVGOR
Definition: pigpio.h:6092
int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, uint32_t level)
Definition: pigpiod_if2.c:1037
int set_noise_filter(int pi, unsigned user_gpio, unsigned steady, unsigned active)
Definition: pigpiod_if2.c:1059
#define PI_CMD_EVM
Definition: pigpio.h:6196
int i2c_block_process_call(int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1335
int i2c_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1224
int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1432
void(* CBFuncEx_t)(unsigned user_gpio, unsigned level, uint32_t tick, void *user)
Definition: pigpiod_if.h:291
#define PI_CMD_WVTX
Definition: pigpio.h:6112
int get_PWM_frequency(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:827
int file_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1873
void(* evtCBFunc_t)(int pi, unsigned event, uint32_t tick)
Definition: pigpiod_if2.h:328
CBF_t f
Definition: pigpiod_if.c:67
#define PI_CMD_SLR
Definition: pigpio.h:6104
int set_bank_2(int pi, uint32_t levels)
Definition: pigpiod_if2.c:866
#define PI_CMD_TRIG
Definition: pigpio.h:6098
#define PI_CMD_WVTAT
Definition: pigpio.h:6176
void(* CBF_t)()
Definition: pigpiod_if2.c:61
uint32_t read_bank_2(int pi)
Definition: pigpiod_if2.c:854
#define PI_CMD_SPIC
Definition: pigpio.h:6135
#define PI_CMD_PIGPV
Definition: pigpio.h:6087
#define PI_CMD_NOIB
Definition: pigpio.h:6173
int set_bank_1(int pi, uint32_t levels)
Definition: pigpiod_if2.c:863
static pthread_mutex_t gCmdMutex[MAX_PI]
Definition: pigpiod_if2.c:104
#define PI_MAX_SCRIPT_PARAMS
Definition: pigpio.h:799
#define PI_CMD_BI2CZ
Definition: pigpio.h:6159
void * ptr
Definition: pigpio.h:404
double time_time(void)
Definition: pigpiod_if2.c:593
#define PI_CMD_WVSM
Definition: pigpio.h:6095
int i2c_read_byte_data(int pi, unsigned handle, unsigned reg)
Definition: pigpiod_if2.c:1274
int callback_cancel(unsigned id)
Definition: pigpiod_if2.c:1969
int spi_xfer(int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if2.c:1671
#define PI_CMD_I2CWD
Definition: pigpio.h:6119
int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud)
Definition: pigpiod_if2.c:1486
int set_pad_strength(int pi, unsigned pad, unsigned padStrength)
Definition: pigpiod_if2.c:1823
static evtCallback_t * geCallBackFirst
Definition: pigpiod_if2.c:110
void(* evtCBFuncEx_t)(int pi, unsigned event, uint32_t tick, void *userdata)
Definition: pigpiod_if2.h:331
uint32_t res
Definition: command.h:63
void pigpio_stop(int pi)
Definition: pigpiod_if2.c:763
#define PI_CMD_I2CRW
Definition: pigpio.h:6125
int file_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1895
#define PI_CMD_I2CWK
Definition: pigpio.h:6128
#define PI_CMD_BS1
Definition: pigpio.h:6075
#define PI_CMD_BSCX
Definition: pigpio.h:6194
static uint32_t gLastLevel[MAX_PI]
Definition: pigpiod_if2.c:100
int callback_ex(int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user)
Definition: pigpiod_if2.c:1965
#define PI_CMD_PRRG
Definition: pigpio.h:6085
int hardware_clock(int pi, unsigned gpio, unsigned frequency)
Definition: pigpiod_if2.c:869
int r
Definition: DHT22.py:259
int serial_data_available(int pi, unsigned handle)
Definition: pigpiod_if2.c:1767
#define PI_CMD_SERVO
Definition: pigpio.h:6069
#define PI_CMD_I2CWI
Definition: pigpio.h:6130
static int intEventCallback(int pi, unsigned event, void *f, void *user, int ex)
Definition: pigpiod_if2.c:513
#define PI_CMD_PWM
Definition: pigpio.h:6066
#define PI_CMD_SERC
Definition: pigpio.h:6141
#define PI_CMD_WRITE
Definition: pigpio.h:6065
int wave_tx_stop(int pi)
Definition: pigpiod_if2.c:1007
static void _pmu(int pi)
Definition: pigpiod_if2.c:124
static void * pthNotifyThread(void *x)
Definition: pigpiod_if2.c:366
pthread_t * start_thread(gpioThreadFunc_t thread_func, void *userdata)
Definition: pigpiod_if2.c:668
int wave_get_pulses(int pi)
Definition: pigpiod_if2.c:1019
static callback_t * gCallBackFirst
Definition: pigpiod_if2.c:107
int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert)
Definition: pigpiod_if2.c:1202
size_t size
Definition: pigpio.h:403
int event_trigger(int pi, unsigned event)
Definition: pigpiod_if2.c:2129
void *( gpioThreadFunc_t)(void *)
Definition: pigpio.h:552
#define PI_CMD_PROCU
Definition: pigpio.h:6199
#define PI_CMD_WDOG
Definition: pigpio.h:6070
char txBuf[BSC_FIFO_SIZE]
Definition: pigpio.h:507
int spi_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1632
int event_callback_cancel(unsigned id)
Definition: pigpiod_if2.c:2077
int i2c_write_byte(int pi, unsigned handle, unsigned val)
Definition: pigpiod_if2.c:1230
#define PI_CMD_FN
Definition: pigpio.h:6171
#define PI_CMD_BSPIC
Definition: pigpio.h:6190
#define PI_CMD_SERR
Definition: pigpio.h:6144
#define PI_NTFY_FLAGS_WDOG
Definition: pigpio.h:626
int status
Definition: pigs.c:57
int clear_bank_2(int pi, uint32_t levels)
Definition: pigpiod_if2.c:860
int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags)
Definition: pigpiod_if2.c:1205
#define PI_CMD_I2CRD
Definition: pigpio.h:6118
int i2c_write_i2c_block_data(int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1396
#define PI_CMD_I2CO
Definition: pigpio.h:6116
int clear_bank_1(int pi, uint32_t levels)
Definition: pigpiod_if2.c:857
#define PI_CMD_I2CRI
Definition: pigpio.h:6129
int spi_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1635
int wave_create(int pi)
Definition: pigpiod_if2.c:961
#define PI_CMD_TICK
Definition: pigpio.h:6077
#define PI_CMD_PROCD
Definition: pigpio.h:6100
#define MAX_PI
Definition: pigpiod_if2.c:59
static int gPigNotify[MAX_PI]
Definition: pigpiod_if2.c:96
static pthread_t * gPthNotify[MAX_PI]
Definition: pigpiod_if2.c:102
int wave_get_high_cbs(int pi)
Definition: pigpiod_if2.c:1031
#define PI_CMD_FS
Definition: pigpio.h:6185
#define PI_CMD_I2CRS
Definition: pigpio.h:6121
static int pigpio_notify(int pi)
Definition: pigpiod_if2.c:164
#define PI_CMD_SERRB
Definition: pigpio.h:6142
int i2c_write_quick(int pi, unsigned handle, unsigned bit)
Definition: pigpiod_if2.c:1227
char * pigpio_error(int errnum)
Definition: pigpiod_if2.c:623
int pigpio_start(char *addrStr, char *portStr)
Definition: pigpiod_if2.c:711
int serial_read(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1750
int wave_delete(int pi, unsigned wave_id)
Definition: pigpiod_if2.c:964
int wave_tx_busy(int pi)
Definition: pigpiod_if2.c:1004
static evtCallback_t * geCallBackLast
Definition: pigpiod_if2.c:111
static int gCancelState[MAX_PI]
Definition: pigpiod_if2.c:105
#define PI_CMD_I2CPK
Definition: pigpio.h:6132
int serial_read_byte(int pi, unsigned handle)
Definition: pigpiod_if2.c:1728
#define PI_CMD_SERW
Definition: pigpio.h:6145
int serial_close(int pi, unsigned handle)
Definition: pigpiod_if2.c:1722
int i2c_write_block_data(int pi, unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if2.c:1299
#define PIGPIOD_IF2_VERSION
Definition: pigpiod_if2.h:33
int stop_script(int pi, unsigned script_id)
Definition: pigpiod_if2.c:1158
#define PI_CMD_WVGO
Definition: pigpio.h:6091
#define PI_CMD_HC
Definition: pigpio.h:6151
#define PI_CMD_PADG
Definition: pigpio.h:6179
#define PI_CMD_SHELL
Definition: pigpio.h:6188
#define PI_CMD_I2CZ
Definition: pigpio.h:6161
int i2c_read_i2c_block_data(int pi, unsigned handle, unsigned reg, char *buf, uint32_t count)
Definition: pigpiod_if2.c:1365
int set_mode(int pi, unsigned gpio, unsigned mode)
Definition: pigpiod_if2.c:794
#define PI_CMD_WVDEL
Definition: pigpio.h:6111
callback_t * prev
Definition: pigpiod_if.c:70
#define PI_CMD_WVCLR
Definition: pigpio.h:6088
int bb_spi_open(int pi, unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spiFlags)
Definition: pigpiod_if2.c:1543
static void _pml(int pi)
Definition: pigpiod_if2.c:115
#define PI_CMD_SLRC
Definition: pigpio.h:6105
#define PI_CMD_FW
Definition: pigpio.h:6184
int wave_add_serial(int pi, unsigned user_gpio, unsigned baud, uint32_t databits, uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str)
Definition: pigpiod_if2.c:927
int bb_spi_close(int pi, unsigned CS)
Definition: pigpiod_if2.c:1576
#define PI_CMD_SERWB
Definition: pigpio.h:6143
int i2c_write_word_data(int pi, unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if2.c:1255
#define PI_CMD_BI2CO
Definition: pigpio.h:6158
#define PI_CMD_BSPIO
Definition: pigpio.h:6191
int store_script(int pi, char *script)
Definition: pigpiod_if2.c:1078
static int pigpioOpenSocket(char *addr, char *port)
Definition: pigpiod_if2.c:237
int set_pull_up_down(int pi, unsigned gpio, unsigned pud)
Definition: pigpiod_if2.c:800
int bb_i2c_close(int pi, unsigned SDA)
Definition: pigpiod_if2.c:1505
#define PI_DEFAULT_SOCKET_ADDR_STR
Definition: pigpio.h:6431
static void findEventBits(int pi)
Definition: pigpiod_if2.c:487
#define STACK_SIZE
Definition: pigpiod_if2.c:57
#define PI_CMD_PADS
Definition: pigpio.h:6178
void time_sleep(double seconds)
Definition: pigpiod_if2.c:605
#define PI_DEFAULT_SOCKET_PORT_STR
Definition: pigpio.h:6430
int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode)
Definition: pigpiod_if2.c:979
int get_PWM_real_range(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:821
static uint32_t gNotifyBits[MAX_PI]
Definition: pigpiod_if2.c:99
int notify_pause(int pi, unsigned handle)
Definition: pigpiod_if2.c:842
int wave_clear(int pi)
Definition: pigpiod_if2.c:900
#define PI_CMD_MODEG
Definition: pigpio.h:6062
int file_list(int pi, char *fpat, char *buf, unsigned count)
Definition: pigpiod_if2.c:1931
int serial_write_byte(int pi, unsigned handle, unsigned val)
Definition: pigpiod_if2.c:1725
#define PI_CMD_WVAS
Definition: pigpio.h:6090
callback_t * next
Definition: pigpiod_if.c:71
#define PI_CMD_I2CWW
Definition: pigpio.h:6126
#define PI_CMD_CF2
Definition: pigpio.h:6155
#define PI_CMD_I2CRB
Definition: pigpio.h:6123
int delete_script(int pi, unsigned script_id)
Definition: pigpiod_if2.c:1161
int event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *user)
Definition: pigpiod_if2.c:2073
int notify_begin(int pi, unsigned handle, uint32_t bits)
Definition: pigpiod_if2.c:839
static void _ewfe(int pi, unsigned event, uint32_t tick, void *user)
Definition: pigpiod_if2.c:507
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
#define PI_CMD_PROCP
Definition: pigpio.h:6106
int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if2.c:1101
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 serial_open(int pi, char *dev, unsigned baud, unsigned flags)
Definition: pigpiod_if2.c:1700
int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth)
Definition: pigpiod_if2.c:830
#define PI_CMD_WVCRE
Definition: pigpio.h:6110
#define PI_CMD_NO
Definition: pigpio.h:6079
#define PI_ENVPORT
Definition: pigpio.h:384
#define PI_CMD_BS2
Definition: pigpio.h:6076
int wave_get_max_cbs(int pi)
Definition: pigpiod_if2.c:1034
#define PI_TIMEOUT
Definition: pigpio.h:577
int wait_for_event(int pi, unsigned event, double timeout)
Definition: pigpiod_if2.c:2107
int bb_spi_xfer(int pi, unsigned CS, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if2.c:1579
char * cmdErrStr(int error)
Definition: command.c:1248
int get_servo_pulsewidth(int pi, unsigned user_gpio)
Definition: pigpiod_if2.c:833
#define PI_CMD_PROCS
Definition: pigpio.h:6102
#define PI_CMD_BSPIX
Definition: pigpio.h:6192
uint32_t level
Definition: pigpio.h:419
int wave_get_micros(int pi)
Definition: pigpiod_if2.c:1010
int i2c_read_byte(int pi, unsigned handle)
Definition: pigpiod_if2.c:1233
static int gPigHandle[MAX_PI]
Definition: pigpiod_if2.c:95
int script_status(int pi, unsigned script_id, uint32_t *param)
Definition: pigpiod_if2.c:1139
#define PI_CMD_I2CWQ
Definition: pigpio.h:6120
void report(int err, char *fmt,...)
Definition: pigs.c:64
#define PI_CMD_WVBSY
Definition: pigpio.h:6093
uint32_t p2
Definition: command.h:58
static void findNotifyBits(int pi)
Definition: pigpiod_if2.c:407
int wave_get_high_micros(int pi)
Definition: pigpiod_if2.c:1013
#define PI_CMD_GDC
Definition: pigpio.h:6148
int serial_write(int pi, unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if2.c:1731
#define PI_CMD_SLRO
Definition: pigpio.h:6103
int i2c_process_call(int pi, unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if2.c:1280
#define PI_CMD_SLRI
Definition: pigpio.h:6165
#define PI_CMD_NB
Definition: pigpio.h:6080
int file_open(int pi, char *file, unsigned mode)
Definition: pigpiod_if2.c:1851
uint32_t cmd
Definition: command.h:56


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