pigpiod_if.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_IF_VERSION 27 */
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_if.h"
54 
55 #define PISCOPE_MAX_REPORTS_PER_READ 4096
56 
57 #define STACK_SIZE (256*1024)
58 
59 typedef void (*CBF_t) ();
60 
61 struct callback_s
62 {
63 
64  int id;
65  int gpio;
66  int edge;
68  void * user;
69  int ex;
72 };
73 
74 /* GLOBALS ---------------------------------------------------------------- */
75 
77 
78 static int gPigCommand = -1;
79 static int gPigHandle = -1;
80 static int gPigNotify = -1;
81 
82 static uint32_t gNotifyBits;
83 static uint32_t gLastLevel;
84 
87 
88 static int gPigStarted = 0;
89 
90 static pthread_t *pthNotify;
91 
92 static pthread_mutex_t command_mutex = PTHREAD_MUTEX_INITIALIZER;
93 
94 /* PRIVATE ---------------------------------------------------------------- */
95 
96 static int pigpio_command(int fd, int command, int p1, int p2, int rl)
97 {
98  cmdCmd_t cmd;
99 
100  cmd.cmd = command;
101  cmd.p1 = p1;
102  cmd.p2 = p2;
103  cmd.res = 0;
104 
105  pthread_mutex_lock(&command_mutex);
106 
107  if (send(fd, &cmd, sizeof(cmd), 0) != sizeof(cmd))
108  {
109  pthread_mutex_unlock(&command_mutex);
110  return pigif_bad_send;
111  }
112 
113  if (recv(fd, &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd))
114  {
115  pthread_mutex_unlock(&command_mutex);
116  return pigif_bad_recv;
117  }
118 
119  if (rl) pthread_mutex_unlock(&command_mutex);
120 
121  return cmd.res;
122 }
123 
124 static int pigpio_command_ext
125  (int fd, int command, int p1, int p2, int p3,
126  int extents, gpioExtent_t *ext, int rl)
127 {
128  int i;
129  cmdCmd_t cmd;
130 
131  cmd.cmd = command;
132  cmd.p1 = p1;
133  cmd.p2 = p2;
134  cmd.p3 = p3;
135 
136  pthread_mutex_lock(&command_mutex);
137 
138  if (send(fd, &cmd, sizeof(cmd), 0) != sizeof(cmd))
139  {
140  pthread_mutex_unlock(&command_mutex);
141  return pigif_bad_send;
142  }
143 
144  for (i=0; i<extents; i++)
145  {
146  if (send(fd, ext[i].ptr, ext[i].size, 0) != ext[i].size)
147  {
148  pthread_mutex_unlock(&command_mutex);
149  return pigif_bad_send;
150  }
151  }
152 
153  if (recv(fd, &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd))
154  {
155  pthread_mutex_unlock(&command_mutex);
156  return pigif_bad_recv;
157  }
158 
159  if (rl) pthread_mutex_unlock(&command_mutex);
160 
161  return cmd.res;
162 }
163 
164 static int pigpioOpenSocket(char *addr, char *port)
165 {
166  int sock, err, opt;
167  struct addrinfo hints, *res, *rp;
168  const char *addrStr, *portStr;
169 
170  if (!addr)
171  {
172  addrStr = getenv(PI_ENVADDR);
173 
174  if ((!addrStr) || (!strlen(addrStr)))
175  {
176  addrStr = PI_DEFAULT_SOCKET_ADDR_STR;
177  }
178  }
179  else addrStr = addr;
180 
181  if (!port)
182  {
183  portStr = getenv(PI_ENVPORT);
184 
185  if ((!portStr) || (!strlen(portStr)))
186  {
187  portStr = PI_DEFAULT_SOCKET_PORT_STR;
188  }
189  }
190  else portStr = port;
191 
192  memset (&hints, 0, sizeof (hints));
193 
194  hints.ai_family = PF_UNSPEC;
195  hints.ai_socktype = SOCK_STREAM;
196  hints.ai_flags |= AI_CANONNAME;
197 
198  err = getaddrinfo (addrStr, portStr, &hints, &res);
199 
200  if (err) return pigif_bad_getaddrinfo;
201 
202  for (rp=res; rp!=NULL; rp=rp->ai_next)
203  {
204  sock = socket(rp->ai_family, rp->ai_socktype, rp->ai_protocol);
205 
206  if (sock == -1) continue;
207 
208  /* Disable the Nagle algorithm. */
209  opt = 1;
210  setsockopt(sock, IPPROTO_TCP, TCP_NODELAY, (char*)&opt, sizeof(int));
211 
212  if (connect(sock, rp->ai_addr, rp->ai_addrlen) != -1) break;
213  }
214 
215  freeaddrinfo(res);
216 
217  if (rp == NULL) return pigif_bad_connect;
218 
219  return sock;
220 }
221 
223 {
224  callback_t *p;
225  uint32_t changed;
226  int l, g;
227 
228  /*
229  printf("s=%d f=%d l=%8X, t=%10u\n",
230  r->seqno, r->flags, r->level, r->tick);
231  */
232 
233  if (r->flags == 0)
234  {
235  changed = (r->level ^ gLastLevel) & gNotifyBits;
236 
237  gLastLevel = r->level;
238 
239  p = gCallBackFirst;
240 
241  while (p)
242  {
243  if (changed & (1<<(p->gpio)))
244  {
245  if ((r->level) & (1<<(p->gpio))) l = 1; else l = 0;
246  if ((p->edge) ^ l)
247  {
248  if (p->ex) (p->f)(p->gpio, l, r->tick, p->user);
249  else (p->f)(p->gpio, l, r->tick);
250  }
251  }
252  p = p->next;
253  }
254  }
255  else
256  {
257  g = (r->flags) & 31;
258 
259  p = gCallBackFirst;
260 
261  while (p)
262  {
263  if ((p->gpio) == g)
264  {
265  if (p->ex) (p->f)(g, PI_TIMEOUT, r->tick, p->user);
266  else (p->f)(g, PI_TIMEOUT, r->tick);
267  }
268  p = p->next;
269  }
270  }
271 }
272 
273 static void *pthNotifyThread(void *x)
274 {
275  static int got = 0;
276 
277  int bytes, r;
278 
279  while (1)
280  {
281  bytes = read(gPigNotify, (char*)&gReport+got, sizeof(gReport)-got);
282 
283  if (bytes > 0) got += bytes;
284  else break;
285 
286  r = 0;
287 
288  while (got >= sizeof(gpioReport_t))
289  {
290  dispatch_notification(&gReport[r]);
291 
292  r++;
293 
294  got -= sizeof(gpioReport_t);
295  }
296 
297  /* copy any partial report to start of array */
298 
299  if (got && r) gReport[0] = gReport[r];
300  }
301  return 0;
302 }
303 
304 static void findNotifyBits(void)
305 {
306  callback_t *p;
307  uint32_t bits = 0;
308 
309  p = gCallBackFirst;
310 
311  while (p)
312  {
313  bits |= (1<<(p->gpio));
314  p = p->next;
315  }
316 
317  if (bits != gNotifyBits)
318  {
319  gNotifyBits = bits;
321  }
322 }
323 
324 static void _wfe(unsigned user_gpio, unsigned level, uint32_t tick, void *user)
325 {
326  *(int *)user = 1;
327 }
328 
329 static int intCallback(unsigned user_gpio, unsigned edge, void *f, void *user, int ex)
330 {
331  static int id = 0;
332  callback_t *p;
333 
334  if ((user_gpio >=0) && (user_gpio < 32) && (edge >=0) && (edge <= 2) && f)
335  {
336  /* prevent duplicates */
337 
338  p = gCallBackFirst;
339 
340  while (p)
341  {
342  if ((p->gpio == user_gpio) && (p->edge == edge) && (p->f == f))
343  {
345  }
346  p = p->next;
347  }
348 
349  p = malloc(sizeof(callback_t));
350 
351  if (p)
352  {
353  if (!gCallBackFirst) gCallBackFirst = p;
354 
355  p->id = id++;
356  p->gpio = user_gpio;
357  p->edge = edge;
358  p->f = f;
359  p->user = user;
360  p->ex = ex;
361  p->next = 0;
362  p->prev = gCallBackLast;
363 
364  if (p->prev) (p->prev)->next = p;
365  gCallBackLast = p;
366 
367  findNotifyBits();
368 
369  return p->id;
370  }
371 
372  return pigif_bad_malloc;
373  }
374 
375  return pigif_bad_callback;
376 }
377 
378 /* PUBLIC ----------------------------------------------------------------- */
379 
380 double time_time(void)
381 {
382  struct timeval tv;
383  double t;
384 
385  gettimeofday(&tv, 0);
386 
387  t = (double)tv.tv_sec + ((double)tv.tv_usec / 1E6);
388 
389  return t;
390 }
391 
392 void time_sleep(double seconds)
393 {
394  struct timespec ts, rem;
395 
396  if (seconds > 0.0)
397  {
398  ts.tv_sec = seconds;
399  ts.tv_nsec = (seconds-(double)ts.tv_sec) * 1E9;
400 
401  while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem))
402  {
403  /* copy remaining time to ts */
404  ts.tv_sec = rem.tv_sec;
405  ts.tv_nsec = rem.tv_nsec;
406  }
407  }
408 }
409 
410 char *pigpio_error(int errnum)
411 {
412  if (errnum > -1000) return cmdErrStr(errnum);
413  else
414  {
415  switch(errnum)
416  {
417  case pigif_bad_send:
418  return "failed to send to pigpiod";
419  case pigif_bad_recv:
420  return "failed to receive from pigpiod";
422  return "failed to find address of pigpiod";
423  case pigif_bad_connect:
424  return "failed to connect to pigpiod";
425  case pigif_bad_socket:
426  return "failed to create socket";
427  case pigif_bad_noib:
428  return "failed to open noib";
430  return "identical callback exists";
431  case pigif_bad_malloc:
432  return "failed to malloc";
433  case pigif_bad_callback:
434  return "bad callback parameter";
435  case pigif_notify_failed:
436  return "failed to create notification thread";
438  return "callback not found";
439  default:
440  return "unknown error";
441  }
442  }
443 }
444 
445 unsigned pigpiod_if_version(void)
446 {
447  return PIGPIOD_IF_VERSION;
448 }
449 
450 pthread_t *start_thread(gpioThreadFunc_t thread_func, void *arg)
451 {
452  pthread_t *pth;
453  pthread_attr_t pthAttr;
454 
455  pth = malloc(sizeof(pthread_t));
456 
457  if (pth)
458  {
459  if (pthread_attr_init(&pthAttr))
460  {
461  perror("pthread_attr_init failed");
462  free(pth);
463  return NULL;
464  }
465 
466  if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE))
467  {
468  perror("pthread_attr_setstacksize failed");
469  free(pth);
470  return NULL;
471  }
472 
473  if (pthread_create(pth, &pthAttr, thread_func, arg))
474  {
475  perror("pthread_create socket failed");
476  free(pth);
477  return NULL;
478  }
479  }
480  return pth;
481 }
482 
483 void stop_thread(pthread_t *pth)
484 {
485  if (pth)
486  {
487  pthread_cancel(*pth);
488  pthread_join(*pth, NULL);
489  free(pth);
490  }
491 }
492 
493 int pigpio_start(char *addrStr, char *portStr)
494 {
495  if ((!addrStr) || (strlen(addrStr) == 0))
496  {
497  addrStr = "localhost";
498  }
499 
500  if (!gPigStarted)
501  {
502  gPigCommand = pigpioOpenSocket(addrStr, portStr);
503 
504  if (gPigCommand >= 0)
505  {
506  gPigNotify = pigpioOpenSocket(addrStr, portStr);
507 
508  if (gPigNotify >= 0)
509  {
511 
512  if (gPigHandle < 0) return pigif_bad_noib;
513  else
514  {
516 
518  if (pthNotify)
519  {
520  gPigStarted = 1;
521  return 0;
522  }
523  else return pigif_notify_failed;
524  }
525  }
526  else return gPigNotify;
527  }
528  else return gPigCommand;
529  }
530  return 0;
531 }
532 
533 void pigpio_stop(void)
534 {
535  gPigStarted = 0;
536 
537  if (pthNotify)
538  {
540  pthNotify = 0;
541  }
542 
543  if (gPigNotify >= 0)
544  {
545  if (gPigHandle >= 0)
546  {
548  gPigHandle = -1;
549  }
550 
551  close(gPigNotify);
552  gPigNotify = -1;
553  }
554 
555  if (gPigCommand >= 0)
556  {
557  if (gPigHandle >= 0)
558  {
560  gPigHandle = -1;
561  }
562 
563  close(gPigCommand);
564  gPigCommand = -1;
565  }
566 }
567 
568 int set_mode(unsigned gpio, unsigned mode)
569  {return pigpio_command(gPigCommand, PI_CMD_MODES, gpio, mode, 1);}
570 
571 int get_mode(unsigned gpio)
572  {return pigpio_command(gPigCommand, PI_CMD_MODEG, gpio, 0, 1);}
573 
574 int set_pull_up_down(unsigned gpio, unsigned pud)
575  {return pigpio_command(gPigCommand, PI_CMD_PUD, gpio, pud, 1);}
576 
577 int gpio_read(unsigned gpio)
578  {return pigpio_command(gPigCommand, PI_CMD_READ, gpio, 0, 1);}
579 
580 int gpio_write(unsigned gpio, unsigned level)
581  {return pigpio_command(gPigCommand, PI_CMD_WRITE, gpio, level, 1);}
582 
583 int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle)
584  {return pigpio_command(gPigCommand, PI_CMD_PWM, user_gpio, dutycycle, 1);}
585 
586 int get_PWM_dutycycle(unsigned user_gpio)
587  {return pigpio_command(gPigCommand, PI_CMD_GDC, user_gpio, 0, 1);}
588 
589 int set_PWM_range(unsigned user_gpio, unsigned range)
590  {return pigpio_command(gPigCommand, PI_CMD_PRS, user_gpio, range, 1);}
591 
592 int get_PWM_range(unsigned user_gpio)
593  {return pigpio_command(gPigCommand, PI_CMD_PRG, user_gpio, 0, 1);}
594 
595 int get_PWM_real_range(unsigned user_gpio)
596  {return pigpio_command(gPigCommand, PI_CMD_PRRG, user_gpio, 0, 1);}
597 
598 int set_PWM_frequency(unsigned user_gpio, unsigned frequency)
599  {return pigpio_command(gPigCommand, PI_CMD_PFS, user_gpio, frequency, 1);}
600 
601 int get_PWM_frequency(unsigned user_gpio)
602  {return pigpio_command(gPigCommand, PI_CMD_PFG, user_gpio, 0, 1);}
603 
604 int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth)
605  {return pigpio_command(gPigCommand, PI_CMD_SERVO, user_gpio, pulsewidth, 1);}
606 
607 int get_servo_pulsewidth(unsigned user_gpio)
608  {return pigpio_command(gPigCommand, PI_CMD_GPW, user_gpio, 0, 1);}
609 
610 int notify_open(void)
611  {return pigpio_command(gPigCommand, PI_CMD_NO, 0, 0, 1);}
612 
613 int notify_begin(unsigned handle, uint32_t bits)
614  {return pigpio_command(gPigCommand, PI_CMD_NB, handle, bits, 1);}
615 
616 int notify_pause(unsigned handle)
617  {return pigpio_command(gPigCommand, PI_CMD_NB, handle, 0, 1);}
618 
619 int notify_close(unsigned handle)
620  {return pigpio_command(gPigCommand, PI_CMD_NC, handle, 0, 1);}
621 
622 int set_watchdog(unsigned user_gpio, unsigned timeout)
623  {return pigpio_command(gPigCommand, PI_CMD_WDOG, user_gpio, timeout, 1);}
624 
625 uint32_t read_bank_1(void)
626  {return pigpio_command(gPigCommand, PI_CMD_BR1, 0, 0, 1);}
627 
628 uint32_t read_bank_2(void)
629  {return pigpio_command(gPigCommand, PI_CMD_BR2, 0, 0, 1);}
630 
631 int clear_bank_1(uint32_t levels)
632  {return pigpio_command(gPigCommand, PI_CMD_BC1, levels, 0, 1);}
633 
634 int clear_bank_2(uint32_t levels)
635  {return pigpio_command(gPigCommand, PI_CMD_BC2, levels, 0, 1);}
636 
637 int set_bank_1(uint32_t levels)
638  {return pigpio_command(gPigCommand, PI_CMD_BS1, levels, 0, 1);}
639 
640 int set_bank_2(uint32_t levels)
641  {return pigpio_command(gPigCommand, PI_CMD_BS2, levels, 0, 1);}
642 
643 int hardware_clock(unsigned gpio, unsigned frequency)
644  {return pigpio_command(gPigCommand, PI_CMD_HC, gpio, frequency, 1);}
645 
646 int hardware_PWM(unsigned gpio, unsigned frequency, uint32_t dutycycle)
647 {
648  gpioExtent_t ext[1];
649 
650  /*
651  p1=gpio
652  p2=frequency
653  p3=4
654  ## extension ##
655  uint32_t dutycycle
656  */
657 
658  ext[0].size = sizeof(dutycycle);
659  ext[0].ptr = &dutycycle;
660 
661  return pigpio_command_ext(
662  gPigCommand, PI_CMD_HP, gpio, frequency, sizeof(dutycycle), 1, ext, 1);
663 }
664 
665 uint32_t get_current_tick(void)
666  {return pigpio_command(gPigCommand, PI_CMD_TICK, 0, 0, 1);}
667 
668 uint32_t get_hardware_revision(void)
669  {return pigpio_command(gPigCommand, PI_CMD_HWVER, 0, 0, 1);}
670 
671 uint32_t get_pigpio_version(void)
672  {return pigpio_command(gPigCommand, PI_CMD_PIGPV, 0, 0, 1);}
673 
674 int wave_clear(void)
675  {return pigpio_command(gPigCommand, PI_CMD_WVCLR, 0, 0, 1);}
676 
677 int wave_add_new(void)
678  {return pigpio_command(gPigCommand, PI_CMD_WVNEW, 0, 0, 1);}
679 
680 int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses)
681 {
682  gpioExtent_t ext[1];
683 
684  /*
685  p1=0
686  p2=0
687  p3=pulses*sizeof(gpioPulse_t)
688  ## extension ##
689  gpioPulse_t[] pulses
690  */
691 
692  if (!numPulses) return 0;
693 
694  ext[0].size = numPulses * sizeof(gpioPulse_t);
695  ext[0].ptr = pulses;
696 
697  return pigpio_command_ext(
698  gPigCommand, PI_CMD_WVAG, 0, 0, ext[0].size, 1, ext, 1);
699 }
700 
702  unsigned user_gpio, unsigned baud, uint32_t databits,
703  uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str)
704 {
705  uint8_t buf[12];
706  gpioExtent_t ext[2];
707 
708  /*
709  p1=user_gpio
710  p2=baud
711  p3=len+12
712  ## extension ##
713  uint32_t databits
714  uint32_t stophalfbits
715  uint32_t offset
716  char[len] str
717  */
718 
719  if (!numChar) return 0;
720 
721  memcpy(buf, &databits, 4);
722  memcpy(buf+4, &stophalfbits, 4);
723  memcpy(buf+8, &offset, 4);
724 
725  ext[0].size = sizeof(buf);
726  ext[0].ptr = buf;
727 
728  ext[1].size = numChar;
729  ext[1].ptr = str;
730 
732  user_gpio, baud, numChar+sizeof(buf), 2, ext, 1);
733 }
734 
735 int wave_create(void)
736  {return pigpio_command(gPigCommand, PI_CMD_WVCRE, 0, 0, 1);}
737 
738 int wave_delete(unsigned wave_id)
739  {return pigpio_command(gPigCommand, PI_CMD_WVDEL, wave_id, 0, 1);}
740 
741 int wave_tx_start(void) /* DEPRECATED */
742  {return pigpio_command(gPigCommand, PI_CMD_WVGO, 0, 0, 1);}
743 
744 int wave_tx_repeat(void) /* DEPRECATED */
745  {return pigpio_command(gPigCommand, PI_CMD_WVGOR, 0, 0, 1);}
746 
747 int wave_send_once(unsigned wave_id)
748  {return pigpio_command(gPigCommand, PI_CMD_WVTX, wave_id, 0, 1);}
749 
750 int wave_send_repeat(unsigned wave_id)
751  {return pigpio_command(gPigCommand, PI_CMD_WVTXR, wave_id, 0, 1);}
752 
753 int wave_chain(char *buf, unsigned bufSize)
754 {
755  gpioExtent_t ext[1];
756 
757  /*
758  p1=0
759  p2=0
760  p3=bufSize
761  ## extension ##
762  char buf[bufSize]
763  */
764 
765  ext[0].size = bufSize;
766  ext[0].ptr = buf;
767 
768  return pigpio_command_ext
769  (gPigCommand, PI_CMD_WVCHA, 0, 0, bufSize, 1, ext, 1);
770 }
771 
772 int wave_tx_busy(void)
773  {return pigpio_command(gPigCommand, PI_CMD_WVBSY, 0, 0, 1);}
774 
775 int wave_tx_stop(void)
776  {return pigpio_command(gPigCommand, PI_CMD_WVHLT, 0, 0, 1);}
777 
779  {return pigpio_command(gPigCommand, PI_CMD_WVSM, 0, 0, 1);}
780 
782  {return pigpio_command(gPigCommand, PI_CMD_WVSM, 1, 0, 1);}
783 
785  {return pigpio_command(gPigCommand, PI_CMD_WVSM, 2, 0, 1);}
786 
788  {return pigpio_command(gPigCommand, PI_CMD_WVSP, 0, 0, 1);}
789 
791  {return pigpio_command(gPigCommand, PI_CMD_WVSP, 1, 0, 1);}
792 
794  {return pigpio_command(gPigCommand, PI_CMD_WVSP, 2, 0, 1);}
795 
796 int wave_get_cbs(void)
797  {return pigpio_command(gPigCommand, PI_CMD_WVSC, 0, 0, 1);}
798 
800  {return pigpio_command(gPigCommand, PI_CMD_WVSC, 1, 0, 1);}
801 
803  {return pigpio_command(gPigCommand, PI_CMD_WVSC, 2, 0, 1);}
804 
805 int gpio_trigger(unsigned user_gpio, unsigned pulseLen, uint32_t level)
806 {
807  gpioExtent_t ext[1];
808 
809  /*
810  p1=user_gpio
811  p2=pulseLen
812  p3=4
813  ## extension ##
814  unsigned level
815  */
816 
817  ext[0].size = sizeof(uint32_t);
818  ext[0].ptr = &level;
819 
820  return pigpio_command_ext(
821  gPigCommand, PI_CMD_TRIG, user_gpio, pulseLen, 4, 1, ext, 1);
822 }
823 
824 int set_glitch_filter(unsigned user_gpio, unsigned steady)
825  {return pigpio_command(gPigCommand, PI_CMD_FG, user_gpio, steady, 1);}
826 
827 int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active)
828 {
829  gpioExtent_t ext[1];
830 
831  /*
832  p1=user_gpio
833  p2=steady
834  p3=4
835  ## extension ##
836  unsigned active
837  */
838 
839  ext[0].size = sizeof(uint32_t);
840  ext[0].ptr = &active;
841 
842  return pigpio_command_ext(
843  gPigCommand, PI_CMD_FN, user_gpio, steady, 4, 1, ext, 1);
844 }
845 
846 int store_script(char *script)
847 {
848  unsigned len;
849  gpioExtent_t ext[1];
850 
851  /*
852  p1=0
853  p2=0
854  p3=len
855  ## extension ##
856  char[len] script
857  */
858 
859  len = strlen(script);
860 
861  if (!len) return 0;
862 
863  ext[0].size = len;
864  ext[0].ptr = script;
865 
866  return pigpio_command_ext(gPigCommand, PI_CMD_PROC, 0, 0, len, 1, ext, 1);
867 }
868 
869 int run_script(unsigned script_id, unsigned numPar, uint32_t *param)
870 {
871  gpioExtent_t ext[1];
872 
873  /*
874  p1=script id
875  p2=0
876  p3=numPar * 4
877  ## extension ##
878  uint32_t[numPar] pars
879  */
880 
881  ext[0].size = 4 * numPar;
882  ext[0].ptr = param;
883 
884  return pigpio_command_ext
885  (gPigCommand, PI_CMD_PROCR, script_id, 0, numPar*4, 1, ext, 1);
886 }
887 
888 int recvMax(void *buf, int bufsize, int sent)
889 {
890  uint8_t scratch[4096];
891  int remaining, fetch, count;
892 
893  if (sent < bufsize) count = sent; else count = bufsize;
894 
895  if (count) recv(gPigCommand, buf, count, MSG_WAITALL);
896 
897  remaining = sent - count;
898 
899  while (remaining)
900  {
901  fetch = remaining;
902  if (fetch > sizeof(scratch)) fetch = sizeof(scratch);
903  recv(gPigCommand, scratch, fetch, MSG_WAITALL);
904  remaining -= fetch;
905  }
906 
907  return count;
908 }
909 
910 int script_status(unsigned script_id, uint32_t *param)
911 {
912  int status;
913  uint32_t p[PI_MAX_SCRIPT_PARAMS+1]; /* space for script status */
914 
915  status = pigpio_command(gPigCommand, PI_CMD_PROCP, script_id, 0, 0);
916 
917  if (status > 0)
918  {
919  recvMax(p, sizeof(p), status);
920  status = p[0];
921  if (param) memcpy(param, p+1, sizeof(p)-4);
922  }
923 
924  pthread_mutex_unlock(&command_mutex);
925 
926  return status;
927 }
928 
929 int stop_script(unsigned script_id)
930  {return pigpio_command(gPigCommand, PI_CMD_PROCS, script_id, 0, 1);}
931 
932 int delete_script(unsigned script_id)
933  {return pigpio_command(gPigCommand, PI_CMD_PROCD, script_id, 0, 1);}
934 
935 int bb_serial_read_open(unsigned user_gpio, unsigned baud, uint32_t bbBits)
936 {
937  gpioExtent_t ext[1];
938 
939  /*
940  p1=user_gpio
941  p2=baud
942  p3=4
943  ## extension ##
944  unsigned bbBits
945  */
946 
947  ext[0].size = sizeof(uint32_t);
948  ext[0].ptr = &bbBits;
949 
950  return pigpio_command_ext(
951  gPigCommand, PI_CMD_SLRO, user_gpio, baud, 4, 1, ext, 1);
952 }
953 
954 int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize)
955 {
956  int bytes;
957 
958  bytes = pigpio_command(gPigCommand, PI_CMD_SLR, user_gpio, bufSize, 0);
959 
960  if (bytes > 0)
961  {
962  bytes = recvMax(buf, bufSize, bytes);
963  }
964 
965  pthread_mutex_unlock(&command_mutex);
966 
967  return bytes;
968 }
969 
970 int bb_serial_read_close(unsigned user_gpio)
971  {return pigpio_command(gPigCommand, PI_CMD_SLRC, user_gpio, 0, 1);}
972 
973 int bb_serial_invert(unsigned user_gpio, unsigned invert)
974  {return pigpio_command(gPigCommand, PI_CMD_SLRI, user_gpio, invert, 1);}
975 
976 int i2c_open(unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags)
977 {
978  gpioExtent_t ext[1];
979 
980  /*
981  p1=i2c_bus
982  p2=i2c_addr
983  p3=4
984  ## extension ##
985  uint32_t i2c_flags
986  */
987 
988  ext[0].size = sizeof(uint32_t);
989  ext[0].ptr = &i2c_flags;
990 
991  return pigpio_command_ext
992  (gPigCommand, PI_CMD_I2CO, i2c_bus, i2c_addr, 4, 1, ext, 1);
993 }
994 
995 int i2c_close(unsigned handle)
996  {return pigpio_command(gPigCommand, PI_CMD_I2CC, handle, 0, 1);}
997 
998 int i2c_write_quick(unsigned handle, unsigned bit)
999  {return pigpio_command(gPigCommand, PI_CMD_I2CWQ, handle, bit, 1);}
1000 
1001 int i2c_write_byte(unsigned handle, unsigned val)
1002  {return pigpio_command(gPigCommand, PI_CMD_I2CWS, handle, val, 1);}
1003 
1004 int i2c_read_byte(unsigned handle)
1005  {return pigpio_command(gPigCommand, PI_CMD_I2CRS, handle, 0, 1);}
1006 
1007 int i2c_write_byte_data(unsigned handle, unsigned reg, uint32_t val)
1008 {
1009  gpioExtent_t ext[1];
1010 
1011  /*
1012  p1=handle
1013  p2=reg
1014  p3=4
1015  ## extension ##
1016  uint32_t val
1017  */
1018 
1019  ext[0].size = sizeof(uint32_t);
1020  ext[0].ptr = &val;
1021 
1022  return pigpio_command_ext
1023  (gPigCommand, PI_CMD_I2CWB, handle, reg, 4, 1, ext, 1);
1024 }
1025 
1026 int i2c_write_word_data(unsigned handle, unsigned reg, uint32_t val)
1027 {
1028  gpioExtent_t ext[1];
1029 
1030  /*
1031  p1=handle
1032  p2=reg
1033  p3=4
1034  ## extension ##
1035  uint32_t val
1036  */
1037 
1038  ext[0].size = sizeof(uint32_t);
1039  ext[0].ptr = &val;
1040 
1041  return pigpio_command_ext
1042  (gPigCommand, PI_CMD_I2CWW, handle, reg, 4, 1, ext, 1);
1043 }
1044 
1045 int i2c_read_byte_data(unsigned handle, unsigned reg)
1046  {return pigpio_command(gPigCommand, PI_CMD_I2CRB, handle, reg, 1);}
1047 
1048 int i2c_read_word_data(unsigned handle, unsigned reg)
1049  {return pigpio_command(gPigCommand, PI_CMD_I2CRW, handle, reg, 1);}
1050 
1051 int i2c_process_call(unsigned handle, unsigned reg, uint32_t val)
1052 {
1053  gpioExtent_t ext[1];
1054 
1055  /*
1056  p1=handle
1057  p2=reg
1058  p3=4
1059  ## extension ##
1060  uint32_t val
1061  */
1062 
1063  ext[0].size = sizeof(uint32_t);
1064  ext[0].ptr = &val;
1065 
1066  return pigpio_command_ext
1067  (gPigCommand, PI_CMD_I2CPK, handle, reg, 4, 1, ext, 1);
1068 }
1069 
1071  unsigned handle, unsigned reg, char *buf, unsigned count)
1072 {
1073  gpioExtent_t ext[1];
1074 
1075  /*
1076  p1=handle
1077  p2=reg
1078  p3=count
1079  ## extension ##
1080  char buf[count]
1081  */
1082 
1083  ext[0].size = count;
1084  ext[0].ptr = buf;
1085 
1086  return pigpio_command_ext
1087  (gPigCommand, PI_CMD_I2CWK, handle, reg, count, 1, ext, 1);
1088 }
1089 
1090 int i2c_read_block_data(unsigned handle, unsigned reg, char *buf)
1091 {
1092  int bytes;
1093 
1094  bytes = pigpio_command(gPigCommand, PI_CMD_I2CRK, handle, reg, 0);
1095 
1096  if (bytes > 0)
1097  {
1098  bytes = recvMax(buf, 32, bytes);
1099  }
1100 
1101  pthread_mutex_unlock(&command_mutex);
1102 
1103  return bytes;
1104 }
1105 
1107  unsigned handle, unsigned reg, char *buf, unsigned count)
1108 {
1109  int bytes;
1110  gpioExtent_t ext[1];
1111 
1112  /*
1113  p1=handle
1114  p2=reg
1115  p3=count
1116  ## extension ##
1117  char buf[count]
1118  */
1119 
1120  ext[0].size = count;
1121  ext[0].ptr = buf;
1122 
1123  bytes = pigpio_command_ext
1124  (gPigCommand, PI_CMD_I2CPK, handle, reg, count, 1, ext, 0);
1125 
1126  if (bytes > 0)
1127  {
1128  bytes = recvMax(buf, 32, bytes);
1129  }
1130 
1131  pthread_mutex_unlock(&command_mutex);
1132 
1133  return bytes;
1134 }
1135 
1137  unsigned handle, unsigned reg, char *buf, uint32_t count)
1138 {
1139  int bytes;
1140  gpioExtent_t ext[1];
1141 
1142  /*
1143  p1=handle
1144  p2=reg
1145  p3=4
1146  ## extension ##
1147  uint32_t count
1148  */
1149 
1150  ext[0].size = sizeof(uint32_t);
1151  ext[0].ptr = &count;
1152 
1153  bytes = pigpio_command_ext
1154  (gPigCommand, PI_CMD_I2CRI, handle, reg, 4, 1, ext, 0);
1155 
1156  if (bytes > 0)
1157  {
1158  bytes = recvMax(buf, count, bytes);
1159  }
1160 
1161  pthread_mutex_unlock(&command_mutex);
1162 
1163  return bytes;
1164 }
1165 
1166 
1168  unsigned handle, unsigned reg, char *buf, unsigned count)
1169 {
1170  gpioExtent_t ext[1];
1171 
1172  /*
1173  p1=handle
1174  p2=reg
1175  p3=count
1176  ## extension ##
1177  char buf[count]
1178  */
1179 
1180  ext[0].size = count;
1181  ext[0].ptr = buf;
1182 
1183  return pigpio_command_ext
1184  (gPigCommand, PI_CMD_I2CWI, handle, reg, count, 1, ext, 1);
1185 }
1186 
1187 int i2c_read_device(unsigned handle, char *buf, unsigned count)
1188 {
1189  int bytes;
1190 
1191  bytes = pigpio_command(gPigCommand, PI_CMD_I2CRD, handle, count, 0);
1192 
1193  if (bytes > 0)
1194  {
1195  bytes = recvMax(buf, count, bytes);
1196  }
1197 
1198  pthread_mutex_unlock(&command_mutex);
1199 
1200  return bytes;
1201 }
1202 
1203 int i2c_write_device(unsigned handle, char *buf, unsigned count)
1204 {
1205  gpioExtent_t ext[1];
1206 
1207  /*
1208  p1=handle
1209  p2=0
1210  p3=count
1211  ## extension ##
1212  char buf[count]
1213  */
1214 
1215  ext[0].size = count;
1216  ext[0].ptr = buf;
1217 
1218  return pigpio_command_ext
1219  (gPigCommand, PI_CMD_I2CWD, handle, 0, count, 1, ext, 1);
1220 }
1221 
1223  unsigned handle,
1224  char *inBuf,
1225  unsigned inLen,
1226  char *outBuf,
1227  unsigned outLen)
1228 {
1229  int bytes;
1230  gpioExtent_t ext[1];
1231 
1232  /*
1233  p1=handle
1234  p2=0
1235  p3=inLen
1236  ## extension ##
1237  char inBuf[inLen]
1238  */
1239 
1240  ext[0].size = inLen;
1241  ext[0].ptr = inBuf;
1242 
1243  bytes = pigpio_command_ext
1244  (gPigCommand, PI_CMD_I2CZ, handle, 0, inLen, 1, ext, 0);
1245 
1246  if (bytes > 0)
1247  {
1248  bytes = recvMax(outBuf, outLen, bytes);
1249  }
1250 
1251  pthread_mutex_unlock(&command_mutex);
1252 
1253  return bytes;
1254 }
1255 
1256 int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud)
1257 {
1258  gpioExtent_t ext[1];
1259 
1260  /*
1261  p1=SDA
1262  p2=SCL
1263  p3=4
1264  ## extension ##
1265  uint32_t baud
1266  */
1267 
1268  ext[0].size = sizeof(uint32_t);
1269  ext[0].ptr = &baud;
1270 
1271  return pigpio_command_ext
1272  (gPigCommand, PI_CMD_BI2CO, SDA, SCL, 4, 1, ext, 1);
1273 }
1274 
1275 int bb_i2c_close(unsigned SDA)
1276  {return pigpio_command(gPigCommand, PI_CMD_BI2CC, SDA, 0, 1);}
1277 
1279  unsigned SDA,
1280  char *inBuf,
1281  unsigned inLen,
1282  char *outBuf,
1283  unsigned outLen)
1284 {
1285  int bytes;
1286  gpioExtent_t ext[1];
1287 
1288  /*
1289  p1=SDA
1290  p2=0
1291  p3=inLen
1292  ## extension ##
1293  char inBuf[inLen]
1294  */
1295 
1296  ext[0].size = inLen;
1297  ext[0].ptr = inBuf;
1298 
1299  bytes = pigpio_command_ext
1300  (gPigCommand, PI_CMD_BI2CZ, SDA, 0, inLen, 1, ext, 0);
1301 
1302  if (bytes > 0)
1303  {
1304  bytes = recvMax(outBuf, outLen, bytes);
1305  }
1306 
1307  pthread_mutex_unlock(&command_mutex);
1308 
1309  return bytes;
1310 }
1311 
1312 int spi_open(unsigned channel, unsigned speed, uint32_t flags)
1313 {
1314  gpioExtent_t ext[1];
1315 
1316  /*
1317  p1=channel
1318  p2=speed
1319  p3=4
1320  ## extension ##
1321  uint32_t flags
1322  */
1323 
1324  ext[0].size = sizeof(uint32_t);
1325  ext[0].ptr = &flags;
1326 
1327  return pigpio_command_ext
1328  (gPigCommand, PI_CMD_SPIO, channel, speed, 4, 1, ext, 1);
1329 }
1330 
1331 int spi_close(unsigned handle)
1332  {return pigpio_command(gPigCommand, PI_CMD_SPIC, handle, 0, 1);}
1333 
1334 int spi_read(unsigned handle, char *buf, unsigned count)
1335 {
1336  int bytes;
1337 
1338  bytes = pigpio_command
1339  (gPigCommand, PI_CMD_SPIR, handle, count, 0);
1340 
1341  if (bytes > 0)
1342  {
1343  bytes = recvMax(buf, count, bytes);
1344  }
1345 
1346  pthread_mutex_unlock(&command_mutex);
1347 
1348  return bytes;
1349 }
1350 
1351 int spi_write(unsigned handle, char *buf, unsigned count)
1352 {
1353  gpioExtent_t ext[1];
1354 
1355  /*
1356  p1=handle
1357  p2=0
1358  p3=count
1359  ## extension ##
1360  char buf[count]
1361  */
1362 
1363  ext[0].size = count;
1364  ext[0].ptr = buf;
1365 
1366  return pigpio_command_ext
1367  (gPigCommand, PI_CMD_SPIW, handle, 0, count, 1, ext, 1);
1368 }
1369 
1370 int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)
1371 {
1372  int bytes;
1373  gpioExtent_t ext[1];
1374 
1375  /*
1376  p1=handle
1377  p2=0
1378  p3=count
1379  ## extension ##
1380  char buf[count]
1381  */
1382 
1383  ext[0].size = count;
1384  ext[0].ptr = txBuf;
1385 
1386  bytes = pigpio_command_ext
1387  (gPigCommand, PI_CMD_SPIX, handle, 0, count, 1, ext, 0);
1388 
1389  if (bytes > 0)
1390  {
1391  bytes = recvMax(rxBuf, count, bytes);
1392  }
1393 
1394  pthread_mutex_unlock(&command_mutex);
1395 
1396  return bytes;
1397 }
1398 
1399 int serial_open(char *dev, unsigned baud, unsigned flags)
1400 {
1401  int len;
1402  gpioExtent_t ext[1];
1403 
1404  len = strlen(dev);
1405 
1406  /*
1407  p1=baud
1408  p2=flags
1409  p3=len
1410  ## extension ##
1411  char dev[len]
1412  */
1413 
1414  ext[0].size = len;
1415  ext[0].ptr = dev;
1416 
1417  return pigpio_command_ext
1418  (gPigCommand, PI_CMD_SERO, baud, flags, len, 1, ext, 1);
1419 }
1420 
1421 int serial_close(unsigned handle)
1422  {return pigpio_command(gPigCommand, PI_CMD_SERC, handle, 0, 1);}
1423 
1424 int serial_write_byte(unsigned handle, unsigned val)
1425  {return pigpio_command(gPigCommand, PI_CMD_SERWB, handle, val, 1);}
1426 
1428  {return pigpio_command(gPigCommand, PI_CMD_SERRB, handle, 0, 1);}
1429 
1430 int serial_write(unsigned handle, char *buf, unsigned count)
1431 {
1432  gpioExtent_t ext[1];
1433 
1434  /*
1435  p1=handle
1436  p2=0
1437  p3=count
1438  ## extension ##
1439  char buf[count]
1440  */
1441 
1442  ext[0].size = count;
1443  ext[0].ptr = buf;
1444 
1445  return pigpio_command_ext
1446  (gPigCommand, PI_CMD_SERW, handle, 0, count, 1, ext, 1);
1447 }
1448 
1449 int serial_read(unsigned handle, char *buf, unsigned count)
1450 {
1451  int bytes;
1452 
1453  bytes = pigpio_command
1454  (gPigCommand, PI_CMD_SERR, handle, count, 0);
1455 
1456  if (bytes > 0)
1457  {
1458  bytes = recvMax(buf, count, bytes);
1459  }
1460 
1461  pthread_mutex_unlock(&command_mutex);
1462 
1463  return bytes;
1464 }
1465 
1467  {return pigpio_command(gPigCommand, PI_CMD_SERDA, handle, 0, 1);}
1468 
1469 int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned count)
1470 {
1471  gpioExtent_t ext[1];
1472 
1473  /*
1474  p1=arg1
1475  p2=arg2
1476  p3=count
1477  ## extension ##
1478  char argx[count]
1479  */
1480 
1481  ext[0].size = count;
1482  ext[0].ptr = argx;
1483 
1484  return pigpio_command_ext(
1485  gPigCommand, PI_CMD_CF1, arg1, arg2, count, 1, ext, 1);
1486 }
1487 
1488 
1489 int custom_2(unsigned arg1, char *argx, unsigned count,
1490  char *retBuf, uint32_t retMax)
1491 {
1492  int bytes;
1493  gpioExtent_t ext[1];
1494 
1495  /*
1496  p1=arg1
1497  p2=retMax
1498  p3=count
1499  ## extension ##
1500  char argx[count]
1501  */
1502 
1503  ext[0].size = count;
1504  ext[0].ptr = argx;
1505 
1506  bytes = pigpio_command_ext
1507  (gPigCommand, PI_CMD_CF2, arg1, retMax, count, 1, ext, 0);
1508 
1509  if (bytes > 0)
1510  {
1511  bytes = recvMax(retBuf, retMax, bytes);
1512  }
1513 
1514  pthread_mutex_unlock(&command_mutex);
1515 
1516  return bytes;
1517 }
1518 
1519 
1520 int callback(unsigned user_gpio, unsigned edge, CBFunc_t f)
1521  {return intCallback(user_gpio, edge, f, 0, 0);}
1522 
1523 int callback_ex(unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user)
1524  {return intCallback(user_gpio, edge, f, user, 1);}
1525 
1526 int callback_cancel(unsigned id)
1527 {
1528  callback_t *p;
1529 
1530  p = gCallBackFirst;
1531 
1532  while (p)
1533  {
1534  if (p->id == id)
1535  {
1536  if (p->prev) p->prev->next = p->next;
1537  else gCallBackFirst = p->next;
1538 
1539  if (p->next) p->next->prev = p->prev;
1540  else gCallBackLast = p->prev;
1541 
1542  free(p);
1543 
1544  findNotifyBits();
1545 
1546  return 0;
1547  }
1548  p = p->next;
1549  }
1550  return pigif_callback_not_found;
1551 }
1552 
1553 int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout)
1554 {
1555  int triggered = 0;
1556  int id;
1557  double due;
1558 
1559  if (timeout <= 0.0) return 0;
1560 
1561  due = time_time() + timeout;
1562 
1563  id = callback_ex(user_gpio, edge, _wfe, &triggered);
1564 
1565  while (!triggered && (time_time() < due)) time_sleep(0.1);
1566 
1567  callback_cancel(id);
1568 
1569  return triggered;
1570 }
1571 
1572 
uint32_t tick
Definition: pigpio.h:418
#define PI_CMD_PRS
Definition: pigpio.h:6067
int wave_tx_busy(void)
Definition: pigpiod_if.c:772
void(* CBF_t)()
Definition: pigpiod_if.c:59
#define PI_CMD_WVSC
Definition: pigpio.h:6097
#define PI_CMD_CF1
Definition: pigpio.h:6154
int callback_ex(unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user)
Definition: pigpiod_if.c:1523
#define PI_CMD_HWVER
Definition: pigpio.h:6078
#define PI_CMD_BR1
Definition: pigpio.h:6071
#define PI_CMD_BR2
Definition: pigpio.h:6072
#define PIGPIOD_IF_VERSION
Definition: pigpiod_if.h:33
int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active)
Definition: pigpiod_if.c:827
int i2c_write_byte_data(unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if.c:1007
#define PI_CMD_NC
Definition: pigpio.h:6082
void * user
Definition: pigpiod_if.c:68
#define PI_CMD_PROCR
Definition: pigpio.h:6101
#define PI_CMD_WVTXR
Definition: pigpio.h:6113
int serial_write(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1430
#define PI_ENVADDR
Definition: pigpio.h:385
#define PI_CMD_I2CWS
Definition: pigpio.h:6122
#define PI_CMD_BC2
Definition: pigpio.h:6074
int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize)
Definition: pigpiod_if.c:954
uint16_t flags
Definition: pigpio.h:417
int set_bank_1(uint32_t levels)
Definition: pigpiod_if.c:637
int wave_add_new(void)
Definition: pigpiod_if.c:677
int bb_i2c_close(unsigned SDA)
Definition: pigpiod_if.c:1275
int gpio_read(unsigned gpio)
Definition: pigpiod_if.c:577
static uint32_t gNotifyBits
Definition: pigpiod_if.c:82
int i2c_read_i2c_block_data(unsigned handle, unsigned reg, char *buf, uint32_t count)
Definition: pigpiod_if.c:1136
#define PI_CMD_PFS
Definition: pigpio.h:6068
int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)
Definition: pigpiod_if.c:1370
static int gPigCommand
Definition: pigpiod_if.c:78
int set_bank_2(uint32_t levels)
Definition: pigpiod_if.c:640
uint32_t p3
Definition: command.h:61
static pthread_mutex_t command_mutex
Definition: pigpiod_if.c:92
int i2c_write_device(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1203
int i2c_read_byte_data(unsigned handle, unsigned reg)
Definition: pigpiod_if.c:1045
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 bb_serial_read_open(unsigned user_gpio, unsigned baud, uint32_t bbBits)
Definition: pigpiod_if.c:935
int i2c_zip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if.c:1222
int wave_tx_start(void)
Definition: pigpiod_if.c:741
int wave_get_pulses(void)
Definition: pigpiod_if.c:787
#define PI_CMD_FG
Definition: pigpio.h:6170
#define PI_CMD_GPW
Definition: pigpio.h:6149
int wave_tx_repeat(void)
Definition: pigpiod_if.c:744
#define PI_CMD_SPIR
Definition: pigpio.h:6136
int wave_send_repeat(unsigned wave_id)
Definition: pigpiod_if.c:750
static int gPigStarted
Definition: pigpiod_if.c:88
#define PI_CMD_I2CWB
Definition: pigpio.h:6124
#define PI_CMD_SPIX
Definition: pigpio.h:6138
#define PI_CMD_MODES
Definition: pigpio.h:6061
#define PI_CMD_BI2CC
Definition: pigpio.h:6157
int wave_add_serial(unsigned user_gpio, unsigned baud, uint32_t databits, uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str)
Definition: pigpiod_if.c:701
#define PI_CMD_SPIW
Definition: pigpio.h:6137
static gpioReport_t gReport[PISCOPE_MAX_REPORTS_PER_READ]
Definition: pigpiod_if.c:76
int script_status(unsigned script_id, uint32_t *param)
Definition: pigpiod_if.c:910
static int gPigNotify
Definition: pigpiod_if.c:80
#define PI_CMD_BC1
Definition: pigpio.h:6073
#define PI_CMD_WVNEW
Definition: pigpio.h:6114
int wave_create(void)
Definition: pigpiod_if.c:735
#define PI_CMD_PRG
Definition: pigpio.h:6083
static void dispatch_notification(gpioReport_t *r)
Definition: pigpiod_if.c:222
#define PI_CMD_WVSP
Definition: pigpio.h:6096
#define PI_CMD_I2CRK
Definition: pigpio.h:6127
int bb_i2c_zip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
Definition: pigpiod_if.c:1278
#define PI_CMD_SERDA
Definition: pigpio.h:6146
static uint32_t gLastLevel
Definition: pigpiod_if.c:83
#define PI_CMD_READ
Definition: pigpio.h:6064
uint32_t p1
Definition: command.h:57
int i2c_open(unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags)
Definition: pigpiod_if.c:976
#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 bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud)
Definition: pigpiod_if.c:1256
uint32_t read_bank_2(void)
Definition: pigpiod_if.c:628
int store_script(char *script)
Definition: pigpiod_if.c:846
handle
Definition: PCF8591.py:19
int spi_open(unsigned channel, unsigned speed, uint32_t flags)
Definition: pigpiod_if.c:1312
int serial_data_available(unsigned handle)
Definition: pigpiod_if.c:1466
uint32_t get_current_tick(void)
Definition: pigpiod_if.c:665
int set_PWM_frequency(unsigned user_gpio, unsigned frequency)
Definition: pigpiod_if.c:598
static int gPigHandle
Definition: pigpiod_if.c:79
#define PI_CMD_SPIO
Definition: pigpio.h:6134
int recvMax(void *buf, int bufsize, int sent)
Definition: pigpiod_if.c:888
void pigpio_stop(void)
Definition: pigpiod_if.c:533
#define PI_CMD_PROC
Definition: pigpio.h:6099
static int pigpio_command(int fd, int command, int p1, int p2, int rl)
Definition: pigpiod_if.c:96
int i2c_close(unsigned handle)
Definition: pigpiod_if.c:995
#define PI_CMD_I2CC
Definition: pigpio.h:6117
#define PI_CMD_WVAG
Definition: pigpio.h:6089
#define PI_CMD_WVGOR
Definition: pigpio.h:6092
int wave_get_max_cbs(void)
Definition: pigpiod_if.c:802
int bb_serial_invert(unsigned user_gpio, unsigned invert)
Definition: pigpiod_if.c:973
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 i2c_read_device(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1187
int i2c_write_quick(unsigned handle, unsigned bit)
Definition: pigpiod_if.c:998
CBF_t f
Definition: pigpiod_if.c:67
int spi_read(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1334
#define PI_CMD_SLR
Definition: pigpio.h:6104
#define PI_CMD_TRIG
Definition: pigpio.h:6098
int serial_open(char *dev, unsigned baud, unsigned flags)
Definition: pigpiod_if.c:1399
#define PI_CMD_SPIC
Definition: pigpio.h:6135
int get_servo_pulsewidth(unsigned user_gpio)
Definition: pigpiod_if.c:607
#define PI_CMD_PIGPV
Definition: pigpio.h:6087
#define PI_CMD_NOIB
Definition: pigpio.h:6173
static void * pthNotifyThread(void *x)
Definition: pigpiod_if.c:273
int wave_get_max_pulses(void)
Definition: pigpiod_if.c:793
#define PI_MAX_SCRIPT_PARAMS
Definition: pigpio.h:799
#define PI_CMD_BI2CZ
Definition: pigpio.h:6159
void * ptr
Definition: pigpio.h:404
int get_PWM_range(unsigned user_gpio)
Definition: pigpiod_if.c:592
#define PI_CMD_WVSM
Definition: pigpio.h:6095
#define PI_CMD_I2CWD
Definition: pigpio.h:6119
int i2c_write_word_data(unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if.c:1026
uint32_t res
Definition: command.h:63
#define PI_CMD_I2CRW
Definition: pigpio.h:6125
int serial_read_byte(unsigned handle)
Definition: pigpiod_if.c:1427
int wave_get_high_cbs(void)
Definition: pigpiod_if.c:799
#define PI_CMD_I2CWK
Definition: pigpio.h:6128
int spi_write(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1351
#define PI_CMD_BS1
Definition: pigpio.h:6075
int get_PWM_real_range(unsigned user_gpio)
Definition: pigpiod_if.c:595
int set_mode(unsigned gpio, unsigned mode)
Definition: pigpiod_if.c:568
int i2c_write_byte(unsigned handle, unsigned val)
Definition: pigpiod_if.c:1001
int delete_script(unsigned script_id)
Definition: pigpiod_if.c:932
#define PI_CMD_PRRG
Definition: pigpio.h:6085
int r
Definition: DHT22.py:259
char * pigpio_error(int errnum)
Definition: pigpiod_if.c:410
void time_sleep(double seconds)
Definition: pigpiod_if.c:392
#define PI_CMD_SERVO
Definition: pigpio.h:6069
int run_script(unsigned script_id, unsigned numPar, uint32_t *param)
Definition: pigpiod_if.c:869
#define PI_CMD_I2CWI
Definition: pigpio.h:6130
int pigpio_start(char *addrStr, char *portStr)
Definition: pigpiod_if.c:493
callback_t * gCallBackLast
Definition: pigpiod_if.c:86
int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle)
Definition: pigpiod_if.c:583
#define PI_CMD_PWM
Definition: pigpio.h:6066
#define PI_CMD_SERC
Definition: pigpio.h:6141
int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses)
Definition: pigpiod_if.c:680
int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth)
Definition: pigpiod_if.c:604
#define PI_CMD_WRITE
Definition: pigpio.h:6065
uint32_t read_bank_1(void)
Definition: pigpiod_if.c:625
int wave_tx_stop(void)
Definition: pigpiod_if.c:775
int gpio_write(unsigned gpio, unsigned level)
Definition: pigpiod_if.c:580
int gpio_trigger(unsigned user_gpio, unsigned pulseLen, uint32_t level)
Definition: pigpiod_if.c:805
static void findNotifyBits(void)
Definition: pigpiod_if.c:304
uint32_t get_hardware_revision(void)
Definition: pigpiod_if.c:668
size_t size
Definition: pigpio.h:403
void *( gpioThreadFunc_t)(void *)
Definition: pigpio.h:552
#define PI_CMD_WDOG
Definition: pigpio.h:6070
#define PI_CMD_FN
Definition: pigpio.h:6171
#define PI_CMD_SERR
Definition: pigpio.h:6144
static void _wfe(unsigned user_gpio, unsigned level, uint32_t tick, void *user)
Definition: pigpiod_if.c:324
int status
Definition: pigs.c:57
int wave_get_max_micros(void)
Definition: pigpiod_if.c:784
#define PI_CMD_I2CRD
Definition: pigpio.h:6118
#define PI_CMD_I2CO
Definition: pigpio.h:6116
#define PI_CMD_I2CRI
Definition: pigpio.h:6129
int i2c_process_call(unsigned handle, unsigned reg, uint32_t val)
Definition: pigpiod_if.c:1051
#define PI_CMD_TICK
Definition: pigpio.h:6077
#define PI_CMD_PROCD
Definition: pigpio.h:6100
int hardware_PWM(unsigned gpio, unsigned frequency, uint32_t dutycycle)
Definition: pigpiod_if.c:646
int wave_get_high_pulses(void)
Definition: pigpiod_if.c:790
int get_mode(unsigned gpio)
Definition: pigpiod_if.c:571
int wave_chain(char *buf, unsigned bufSize)
Definition: pigpiod_if.c:753
uint32_t get_pigpio_version(void)
Definition: pigpiod_if.c:671
int serial_close(unsigned handle)
Definition: pigpiod_if.c:1421
int i2c_write_i2c_block_data(unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1167
int wave_get_cbs(void)
Definition: pigpiod_if.c:796
#define PI_CMD_I2CRS
Definition: pigpio.h:6121
static int intCallback(unsigned user_gpio, unsigned edge, void *f, void *user, int ex)
Definition: pigpiod_if.c:329
#define PI_CMD_SERRB
Definition: pigpio.h:6142
static pthread_t * pthNotify
Definition: pigpiod_if.c:90
int i2c_read_block_data(unsigned handle, unsigned reg, char *buf)
Definition: pigpiod_if.c:1090
int serial_read(unsigned handle, char *buf, unsigned count)
Definition: pigpiod_if.c:1449
int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned count)
Definition: pigpiod_if.c:1469
int i2c_write_block_data(unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1070
int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout)
Definition: pigpiod_if.c:1553
int clear_bank_1(uint32_t levels)
Definition: pigpiod_if.c:631
#define PI_CMD_I2CPK
Definition: pigpio.h:6132
#define PI_CMD_SERW
Definition: pigpio.h:6145
int set_glitch_filter(unsigned user_gpio, unsigned steady)
Definition: pigpiod_if.c:824
int callback(unsigned user_gpio, unsigned edge, CBFunc_t f)
Definition: pigpiod_if.c:1520
unsigned pigpiod_if_version(void)
Definition: pigpiod_if.c:445
#define PI_CMD_WVGO
Definition: pigpio.h:6091
#define PI_CMD_HC
Definition: pigpio.h:6151
void stop_thread(pthread_t *pth)
Definition: pigpiod_if.c:483
#define STACK_SIZE
Definition: pigpiod_if.c:57
int i2c_block_process_call(unsigned handle, unsigned reg, char *buf, unsigned count)
Definition: pigpiod_if.c:1106
int get_PWM_frequency(unsigned user_gpio)
Definition: pigpiod_if.c:601
#define PI_CMD_I2CZ
Definition: pigpio.h:6161
int notify_open(void)
Definition: pigpiod_if.c:610
#define PI_CMD_WVDEL
Definition: pigpio.h:6111
callback_t * prev
Definition: pigpiod_if.c:70
#define PI_CMD_WVCLR
Definition: pigpio.h:6088
#define PI_CMD_SLRC
Definition: pigpio.h:6105
int bb_serial_read_close(unsigned user_gpio)
Definition: pigpiod_if.c:970
int wave_send_once(unsigned wave_id)
Definition: pigpiod_if.c:747
#define PI_CMD_SERWB
Definition: pigpio.h:6143
double time_time(void)
Definition: pigpiod_if.c:380
pthread_t * start_thread(gpioThreadFunc_t thread_func, void *arg)
Definition: pigpiod_if.c:450
#define PI_CMD_BI2CO
Definition: pigpio.h:6158
int i2c_read_byte(unsigned handle)
Definition: pigpiod_if.c:1004
int set_PWM_range(unsigned user_gpio, unsigned range)
Definition: pigpiod_if.c:589
int spi_close(unsigned handle)
Definition: pigpiod_if.c:1331
int wave_get_micros(void)
Definition: pigpiod_if.c:778
int serial_write_byte(unsigned handle, unsigned val)
Definition: pigpiod_if.c:1424
#define PI_DEFAULT_SOCKET_ADDR_STR
Definition: pigpio.h:6431
#define PI_DEFAULT_SOCKET_PORT_STR
Definition: pigpio.h:6430
callback_t * gCallBackFirst
Definition: pigpiod_if.c:85
int set_pull_up_down(unsigned gpio, unsigned pud)
Definition: pigpiod_if.c:574
#define PI_CMD_MODEG
Definition: pigpio.h:6062
#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 clear_bank_2(uint32_t levels)
Definition: pigpiod_if.c:634
int wave_get_high_micros(void)
Definition: pigpiod_if.c:781
int custom_2(unsigned arg1, char *argx, unsigned count, char *retBuf, uint32_t retMax)
Definition: pigpiod_if.c:1489
#define PI_CMD_PROCP
Definition: pigpio.h:6106
int hardware_clock(unsigned gpio, unsigned frequency)
Definition: pigpiod_if.c:643
static int pigpioOpenSocket(char *addr, char *port)
Definition: pigpiod_if.c:164
#define PI_CMD_WVCRE
Definition: pigpio.h:6110
#define PI_CMD_NO
Definition: pigpio.h:6079
int notify_begin(unsigned handle, uint32_t bits)
Definition: pigpiod_if.c:613
#define PI_ENVPORT
Definition: pigpio.h:384
#define PI_CMD_BS2
Definition: pigpio.h:6076
#define PI_TIMEOUT
Definition: pigpio.h:577
int wave_clear(void)
Definition: pigpiod_if.c:674
static int pigpio_command_ext(int fd, int command, int p1, int p2, int p3, int extents, gpioExtent_t *ext, int rl)
Definition: pigpiod_if.c:125
int wave_delete(unsigned wave_id)
Definition: pigpiod_if.c:738
char * cmdErrStr(int error)
Definition: command.c:1248
int callback_cancel(unsigned id)
Definition: pigpiod_if.c:1526
#define PI_CMD_PROCS
Definition: pigpio.h:6102
int notify_close(unsigned handle)
Definition: pigpiod_if.c:619
int get_PWM_dutycycle(unsigned user_gpio)
Definition: pigpiod_if.c:586
uint32_t level
Definition: pigpio.h:419
#define PI_CMD_I2CWQ
Definition: pigpio.h:6120
#define PI_CMD_WVBSY
Definition: pigpio.h:6093
int set_watchdog(unsigned user_gpio, unsigned timeout)
Definition: pigpiod_if.c:622
uint32_t p2
Definition: command.h:58
int notify_pause(unsigned handle)
Definition: pigpiod_if.c:616
int i2c_read_word_data(unsigned handle, unsigned reg)
Definition: pigpiod_if.c:1048
int stop_script(unsigned script_id)
Definition: pigpiod_if.c:929
#define PI_CMD_GDC
Definition: pigpio.h:6148
#define PI_CMD_SLRO
Definition: pigpio.h:6103
#define PI_CMD_SLRI
Definition: pigpio.h:6165
#define PI_CMD_NB
Definition: pigpio.h:6080
#define PISCOPE_MAX_REPORTS_PER_READ
Definition: pigpiod_if.c:55
uint32_t cmd
Definition: command.h:56


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