Classes | Defines | Typedefs | Functions | Variables
pigpiod_if.c File Reference
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <string.h>
#include <fcntl.h>
#include <unistd.h>
#include <errno.h>
#include <time.h>
#include <netdb.h>
#include <pthread.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/time.h>
#include <sys/socket.h>
#include <netinet/tcp.h>
#include <sys/select.h>
#include <arpa/inet.h>
#include "pigpio.h"
#include "command.h"
#include "pigpiod_if.h"
Include dependency graph for pigpiod_if.c:

Go to the source code of this file.

Classes

struct  callback_s

Defines

#define PISCOPE_MAX_REPORTS_PER_READ   4096
#define STACK_SIZE   (256*1024)

Typedefs

typedef void(* CBF_t )()

Functions

static void _wfe (unsigned user_gpio, unsigned level, uint32_t tick, void *user)
int bb_i2c_close (unsigned SDA)
int bb_i2c_open (unsigned SDA, unsigned SCL, unsigned baud)
int bb_i2c_zip (unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
int bb_serial_invert (unsigned user_gpio, unsigned invert)
int bb_serial_read (unsigned user_gpio, void *buf, size_t bufSize)
int bb_serial_read_close (unsigned user_gpio)
int bb_serial_read_open (unsigned user_gpio, unsigned baud, uint32_t bbBits)
int callback (unsigned user_gpio, unsigned edge, CBFunc_t f)
int callback_cancel (unsigned id)
int callback_ex (unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user)
int clear_bank_1 (uint32_t levels)
int clear_bank_2 (uint32_t levels)
int custom_1 (unsigned arg1, unsigned arg2, char *argx, unsigned count)
int custom_2 (unsigned arg1, char *argx, unsigned count, char *retBuf, uint32_t retMax)
int delete_script (unsigned script_id)
static void dispatch_notification (gpioReport_t *r)
static void findNotifyBits (void)
uint32_t get_current_tick (void)
uint32_t get_hardware_revision (void)
int get_mode (unsigned gpio)
uint32_t get_pigpio_version (void)
int get_PWM_dutycycle (unsigned user_gpio)
int get_PWM_frequency (unsigned user_gpio)
int get_PWM_range (unsigned user_gpio)
int get_PWM_real_range (unsigned user_gpio)
int get_servo_pulsewidth (unsigned user_gpio)
int gpio_read (unsigned gpio)
int gpio_trigger (unsigned user_gpio, unsigned pulseLen, uint32_t level)
int gpio_write (unsigned gpio, unsigned level)
int hardware_clock (unsigned gpio, unsigned frequency)
int hardware_PWM (unsigned gpio, unsigned frequency, uint32_t dutycycle)
int i2c_block_process_call (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2c_close (unsigned handle)
int i2c_open (unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags)
int i2c_process_call (unsigned handle, unsigned reg, uint32_t val)
int i2c_read_block_data (unsigned handle, unsigned reg, char *buf)
int i2c_read_byte (unsigned handle)
int i2c_read_byte_data (unsigned handle, unsigned reg)
int i2c_read_device (unsigned handle, char *buf, unsigned count)
int i2c_read_i2c_block_data (unsigned handle, unsigned reg, char *buf, uint32_t count)
int i2c_read_word_data (unsigned handle, unsigned reg)
int i2c_write_block_data (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2c_write_byte (unsigned handle, unsigned val)
int i2c_write_byte_data (unsigned handle, unsigned reg, uint32_t val)
int i2c_write_device (unsigned handle, char *buf, unsigned count)
int i2c_write_i2c_block_data (unsigned handle, unsigned reg, char *buf, unsigned count)
int i2c_write_quick (unsigned handle, unsigned bit)
int i2c_write_word_data (unsigned handle, unsigned reg, uint32_t val)
int i2c_zip (unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)
static int intCallback (unsigned user_gpio, unsigned edge, void *f, void *user, int ex)
int notify_begin (unsigned handle, uint32_t bits)
int notify_close (unsigned handle)
int notify_open (void)
int notify_pause (unsigned handle)
static int pigpio_command (int fd, int command, int p1, int p2, int rl)
static int pigpio_command_ext (int fd, int command, int p1, int p2, int p3, int extents, gpioExtent_t *ext, int rl)
char * pigpio_error (int errnum)
int pigpio_start (char *addrStr, char *portStr)
void pigpio_stop (void)
unsigned pigpiod_if_version (void)
static int pigpioOpenSocket (char *addr, char *port)
static void * pthNotifyThread (void *x)
uint32_t read_bank_1 (void)
uint32_t read_bank_2 (void)
int recvMax (void *buf, int bufsize, int sent)
int run_script (unsigned script_id, unsigned numPar, uint32_t *param)
int script_status (unsigned script_id, uint32_t *param)
int serial_close (unsigned handle)
int serial_data_available (unsigned handle)
int serial_open (char *dev, unsigned baud, unsigned flags)
int serial_read (unsigned handle, char *buf, unsigned count)
int serial_read_byte (unsigned handle)
int serial_write (unsigned handle, char *buf, unsigned count)
int serial_write_byte (unsigned handle, unsigned val)
int set_bank_1 (uint32_t levels)
int set_bank_2 (uint32_t levels)
int set_glitch_filter (unsigned user_gpio, unsigned steady)
int set_mode (unsigned gpio, unsigned mode)
int set_noise_filter (unsigned user_gpio, unsigned steady, unsigned active)
int set_pull_up_down (unsigned gpio, unsigned pud)
int set_PWM_dutycycle (unsigned user_gpio, unsigned dutycycle)
int set_PWM_frequency (unsigned user_gpio, unsigned frequency)
int set_PWM_range (unsigned user_gpio, unsigned range)
int set_servo_pulsewidth (unsigned user_gpio, unsigned pulsewidth)
int set_watchdog (unsigned user_gpio, unsigned timeout)
int spi_close (unsigned handle)
int spi_open (unsigned channel, unsigned speed, uint32_t flags)
int spi_read (unsigned handle, char *buf, unsigned count)
int spi_write (unsigned handle, char *buf, unsigned count)
int spi_xfer (unsigned handle, char *txBuf, char *rxBuf, unsigned count)
pthread_t * start_thread (gpioThreadFunc_t thread_func, void *arg)
int stop_script (unsigned script_id)
void stop_thread (pthread_t *pth)
int store_script (char *script)
void time_sleep (double seconds)
double time_time (void)
int wait_for_edge (unsigned user_gpio, unsigned edge, double timeout)
int wave_add_generic (unsigned numPulses, gpioPulse_t *pulses)
int wave_add_new (void)
int wave_add_serial (unsigned user_gpio, unsigned baud, uint32_t databits, uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str)
int wave_chain (char *buf, unsigned bufSize)
int wave_clear (void)
int wave_create (void)
int wave_delete (unsigned wave_id)
int wave_get_cbs (void)
int wave_get_high_cbs (void)
int wave_get_high_micros (void)
int wave_get_high_pulses (void)
int wave_get_max_cbs (void)
int wave_get_max_micros (void)
int wave_get_max_pulses (void)
int wave_get_micros (void)
int wave_get_pulses (void)
int wave_send_once (unsigned wave_id)
int wave_send_repeat (unsigned wave_id)
int wave_tx_busy (void)
int wave_tx_repeat (void)
int wave_tx_start (void)
int wave_tx_stop (void)

Variables

static pthread_mutex_t command_mutex = PTHREAD_MUTEX_INITIALIZER
callback_tgCallBackFirst = 0
callback_tgCallBackLast = 0
static uint32_t gLastLevel
static uint32_t gNotifyBits
static int gPigCommand = -1
static int gPigHandle = -1
static int gPigNotify = -1
static int gPigStarted = 0
static gpioReport_t gReport [PISCOPE_MAX_REPORTS_PER_READ]
static pthread_t * pthNotify

Define Documentation

#define PISCOPE_MAX_REPORTS_PER_READ   4096

Definition at line 55 of file pigpiod_if.c.

#define STACK_SIZE   (256*1024)

Definition at line 57 of file pigpiod_if.c.


Typedef Documentation

typedef void(* CBF_t)()

Definition at line 59 of file pigpiod_if.c.


Function Documentation

static void _wfe ( unsigned  user_gpio,
unsigned  level,
uint32_t  tick,
void *  user 
) [static]

Definition at line 324 of file pigpiod_if.c.

int bb_i2c_close ( unsigned  SDA)

Definition at line 1275 of file pigpiod_if.c.

int bb_i2c_open ( unsigned  SDA,
unsigned  SCL,
unsigned  baud 
)

Definition at line 1256 of file pigpiod_if.c.

int bb_i2c_zip ( unsigned  SDA,
char *  inBuf,
unsigned  inLen,
char *  outBuf,
unsigned  outLen 
)

Definition at line 1278 of file pigpiod_if.c.

int bb_serial_invert ( unsigned  user_gpio,
unsigned  invert 
)

Definition at line 973 of file pigpiod_if.c.

int bb_serial_read ( unsigned  user_gpio,
void *  buf,
size_t  bufSize 
)

Definition at line 954 of file pigpiod_if.c.

int bb_serial_read_close ( unsigned  user_gpio)

Definition at line 970 of file pigpiod_if.c.

int bb_serial_read_open ( unsigned  user_gpio,
unsigned  baud,
uint32_t  bbBits 
)

Definition at line 935 of file pigpiod_if.c.

int callback ( unsigned  user_gpio,
unsigned  edge,
CBFunc_t  f 
)

Definition at line 1520 of file pigpiod_if.c.

int callback_cancel ( unsigned  id)

Definition at line 1526 of file pigpiod_if.c.

int callback_ex ( unsigned  user_gpio,
unsigned  edge,
CBFuncEx_t  f,
void *  user 
)

Definition at line 1523 of file pigpiod_if.c.

int clear_bank_1 ( uint32_t  levels)

Definition at line 631 of file pigpiod_if.c.

int clear_bank_2 ( uint32_t  levels)

Definition at line 634 of file pigpiod_if.c.

int custom_1 ( unsigned  arg1,
unsigned  arg2,
char *  argx,
unsigned  count 
)

Definition at line 1469 of file pigpiod_if.c.

int custom_2 ( unsigned  arg1,
char *  argx,
unsigned  count,
char *  retBuf,
uint32_t  retMax 
)

Definition at line 1489 of file pigpiod_if.c.

int delete_script ( unsigned  script_id)

Definition at line 932 of file pigpiod_if.c.

static void dispatch_notification ( gpioReport_t r) [static]

Definition at line 222 of file pigpiod_if.c.

static void findNotifyBits ( void  ) [static]

Definition at line 304 of file pigpiod_if.c.

uint32_t get_current_tick ( void  )

Definition at line 665 of file pigpiod_if.c.

uint32_t get_hardware_revision ( void  )

Definition at line 668 of file pigpiod_if.c.

int get_mode ( unsigned  gpio)

Definition at line 571 of file pigpiod_if.c.

uint32_t get_pigpio_version ( void  )

Definition at line 671 of file pigpiod_if.c.

int get_PWM_dutycycle ( unsigned  user_gpio)

Definition at line 586 of file pigpiod_if.c.

int get_PWM_frequency ( unsigned  user_gpio)

Definition at line 601 of file pigpiod_if.c.

int get_PWM_range ( unsigned  user_gpio)

Definition at line 592 of file pigpiod_if.c.

int get_PWM_real_range ( unsigned  user_gpio)

Definition at line 595 of file pigpiod_if.c.

int get_servo_pulsewidth ( unsigned  user_gpio)

Definition at line 607 of file pigpiod_if.c.

int gpio_read ( unsigned  gpio)

Definition at line 577 of file pigpiod_if.c.

int gpio_trigger ( unsigned  user_gpio,
unsigned  pulseLen,
uint32_t  level 
)

Definition at line 805 of file pigpiod_if.c.

int gpio_write ( unsigned  gpio,
unsigned  level 
)

Definition at line 580 of file pigpiod_if.c.

int hardware_clock ( unsigned  gpio,
unsigned  frequency 
)

Definition at line 643 of file pigpiod_if.c.

int hardware_PWM ( unsigned  gpio,
unsigned  frequency,
uint32_t  dutycycle 
)

Definition at line 646 of file pigpiod_if.c.

int i2c_block_process_call ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 1106 of file pigpiod_if.c.

int i2c_close ( unsigned  handle)

Definition at line 995 of file pigpiod_if.c.

int i2c_open ( unsigned  i2c_bus,
unsigned  i2c_addr,
uint32_t  i2c_flags 
)

Definition at line 976 of file pigpiod_if.c.

int i2c_process_call ( unsigned  handle,
unsigned  reg,
uint32_t  val 
)

Definition at line 1051 of file pigpiod_if.c.

int i2c_read_block_data ( unsigned  handle,
unsigned  reg,
char *  buf 
)

Definition at line 1090 of file pigpiod_if.c.

int i2c_read_byte ( unsigned  handle)

Definition at line 1004 of file pigpiod_if.c.

int i2c_read_byte_data ( unsigned  handle,
unsigned  reg 
)

Definition at line 1045 of file pigpiod_if.c.

int i2c_read_device ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1187 of file pigpiod_if.c.

int i2c_read_i2c_block_data ( unsigned  handle,
unsigned  reg,
char *  buf,
uint32_t  count 
)

Definition at line 1136 of file pigpiod_if.c.

int i2c_read_word_data ( unsigned  handle,
unsigned  reg 
)

Definition at line 1048 of file pigpiod_if.c.

int i2c_write_block_data ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 1070 of file pigpiod_if.c.

int i2c_write_byte ( unsigned  handle,
unsigned  val 
)

Definition at line 1001 of file pigpiod_if.c.

int i2c_write_byte_data ( unsigned  handle,
unsigned  reg,
uint32_t  val 
)

Definition at line 1007 of file pigpiod_if.c.

int i2c_write_device ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1203 of file pigpiod_if.c.

int i2c_write_i2c_block_data ( unsigned  handle,
unsigned  reg,
char *  buf,
unsigned  count 
)

Definition at line 1167 of file pigpiod_if.c.

int i2c_write_quick ( unsigned  handle,
unsigned  bit 
)

Definition at line 998 of file pigpiod_if.c.

int i2c_write_word_data ( unsigned  handle,
unsigned  reg,
uint32_t  val 
)

Definition at line 1026 of file pigpiod_if.c.

int i2c_zip ( unsigned  handle,
char *  inBuf,
unsigned  inLen,
char *  outBuf,
unsigned  outLen 
)

Definition at line 1222 of file pigpiod_if.c.

static int intCallback ( unsigned  user_gpio,
unsigned  edge,
void *  f,
void *  user,
int  ex 
) [static]

Definition at line 329 of file pigpiod_if.c.

int notify_begin ( unsigned  handle,
uint32_t  bits 
)

Definition at line 613 of file pigpiod_if.c.

int notify_close ( unsigned  handle)

Definition at line 619 of file pigpiod_if.c.

int notify_open ( void  )

Definition at line 610 of file pigpiod_if.c.

int notify_pause ( unsigned  handle)

Definition at line 616 of file pigpiod_if.c.

static int pigpio_command ( int  fd,
int  command,
int  p1,
int  p2,
int  rl 
) [static]

Definition at line 96 of file pigpiod_if.c.

static int pigpio_command_ext ( int  fd,
int  command,
int  p1,
int  p2,
int  p3,
int  extents,
gpioExtent_t ext,
int  rl 
) [static]

Definition at line 125 of file pigpiod_if.c.

char* pigpio_error ( int  errnum)

Definition at line 410 of file pigpiod_if.c.

int pigpio_start ( char *  addrStr,
char *  portStr 
)

Definition at line 493 of file pigpiod_if.c.

void pigpio_stop ( void  )

Definition at line 533 of file pigpiod_if.c.

unsigned pigpiod_if_version ( void  )

Definition at line 445 of file pigpiod_if.c.

static int pigpioOpenSocket ( char *  addr,
char *  port 
) [static]

Definition at line 164 of file pigpiod_if.c.

static void* pthNotifyThread ( void *  x) [static]

Definition at line 273 of file pigpiod_if.c.

uint32_t read_bank_1 ( void  )

Definition at line 625 of file pigpiod_if.c.

uint32_t read_bank_2 ( void  )

Definition at line 628 of file pigpiod_if.c.

int recvMax ( void *  buf,
int  bufsize,
int  sent 
)

Definition at line 888 of file pigpiod_if.c.

int run_script ( unsigned  script_id,
unsigned  numPar,
uint32_t *  param 
)

Definition at line 869 of file pigpiod_if.c.

int script_status ( unsigned  script_id,
uint32_t *  param 
)

Definition at line 910 of file pigpiod_if.c.

int serial_close ( unsigned  handle)

Definition at line 1421 of file pigpiod_if.c.

int serial_data_available ( unsigned  handle)

Definition at line 1466 of file pigpiod_if.c.

int serial_open ( char *  dev,
unsigned  baud,
unsigned  flags 
)

Definition at line 1399 of file pigpiod_if.c.

int serial_read ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1449 of file pigpiod_if.c.

int serial_read_byte ( unsigned  handle)

Definition at line 1427 of file pigpiod_if.c.

int serial_write ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1430 of file pigpiod_if.c.

int serial_write_byte ( unsigned  handle,
unsigned  val 
)

Definition at line 1424 of file pigpiod_if.c.

int set_bank_1 ( uint32_t  levels)

Definition at line 637 of file pigpiod_if.c.

int set_bank_2 ( uint32_t  levels)

Definition at line 640 of file pigpiod_if.c.

int set_glitch_filter ( unsigned  user_gpio,
unsigned  steady 
)

Definition at line 824 of file pigpiod_if.c.

int set_mode ( unsigned  gpio,
unsigned  mode 
)

Definition at line 568 of file pigpiod_if.c.

int set_noise_filter ( unsigned  user_gpio,
unsigned  steady,
unsigned  active 
)

Definition at line 827 of file pigpiod_if.c.

int set_pull_up_down ( unsigned  gpio,
unsigned  pud 
)

Definition at line 574 of file pigpiod_if.c.

int set_PWM_dutycycle ( unsigned  user_gpio,
unsigned  dutycycle 
)

Definition at line 583 of file pigpiod_if.c.

int set_PWM_frequency ( unsigned  user_gpio,
unsigned  frequency 
)

Definition at line 598 of file pigpiod_if.c.

int set_PWM_range ( unsigned  user_gpio,
unsigned  range 
)

Definition at line 589 of file pigpiod_if.c.

int set_servo_pulsewidth ( unsigned  user_gpio,
unsigned  pulsewidth 
)

Definition at line 604 of file pigpiod_if.c.

int set_watchdog ( unsigned  user_gpio,
unsigned  timeout 
)

Definition at line 622 of file pigpiod_if.c.

int spi_close ( unsigned  handle)

Definition at line 1331 of file pigpiod_if.c.

int spi_open ( unsigned  channel,
unsigned  speed,
uint32_t  flags 
)

Definition at line 1312 of file pigpiod_if.c.

int spi_read ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1334 of file pigpiod_if.c.

int spi_write ( unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1351 of file pigpiod_if.c.

int spi_xfer ( unsigned  handle,
char *  txBuf,
char *  rxBuf,
unsigned  count 
)

Definition at line 1370 of file pigpiod_if.c.

pthread_t* start_thread ( gpioThreadFunc_t  thread_func,
void *  arg 
)

Definition at line 450 of file pigpiod_if.c.

int stop_script ( unsigned  script_id)

Definition at line 929 of file pigpiod_if.c.

void stop_thread ( pthread_t *  pth)

Definition at line 483 of file pigpiod_if.c.

int store_script ( char *  script)

Definition at line 846 of file pigpiod_if.c.

void time_sleep ( double  seconds)

Definition at line 392 of file pigpiod_if.c.

double time_time ( void  )

Definition at line 380 of file pigpiod_if.c.

int wait_for_edge ( unsigned  user_gpio,
unsigned  edge,
double  timeout 
)

Definition at line 1553 of file pigpiod_if.c.

int wave_add_generic ( unsigned  numPulses,
gpioPulse_t pulses 
)

Definition at line 680 of file pigpiod_if.c.

int wave_add_new ( void  )

Definition at line 677 of file pigpiod_if.c.

int wave_add_serial ( unsigned  user_gpio,
unsigned  baud,
uint32_t  databits,
uint32_t  stophalfbits,
uint32_t  offset,
unsigned  numChar,
char *  str 
)

Definition at line 701 of file pigpiod_if.c.

int wave_chain ( char *  buf,
unsigned  bufSize 
)

Definition at line 753 of file pigpiod_if.c.

int wave_clear ( void  )

Definition at line 674 of file pigpiod_if.c.

int wave_create ( void  )

Definition at line 735 of file pigpiod_if.c.

int wave_delete ( unsigned  wave_id)

Definition at line 738 of file pigpiod_if.c.

int wave_get_cbs ( void  )

Definition at line 796 of file pigpiod_if.c.

int wave_get_high_cbs ( void  )

Definition at line 799 of file pigpiod_if.c.

int wave_get_high_micros ( void  )

Definition at line 781 of file pigpiod_if.c.

int wave_get_high_pulses ( void  )

Definition at line 790 of file pigpiod_if.c.

int wave_get_max_cbs ( void  )

Definition at line 802 of file pigpiod_if.c.

int wave_get_max_micros ( void  )

Definition at line 784 of file pigpiod_if.c.

int wave_get_max_pulses ( void  )

Definition at line 793 of file pigpiod_if.c.

int wave_get_micros ( void  )

Definition at line 778 of file pigpiod_if.c.

int wave_get_pulses ( void  )

Definition at line 787 of file pigpiod_if.c.

int wave_send_once ( unsigned  wave_id)

Definition at line 747 of file pigpiod_if.c.

int wave_send_repeat ( unsigned  wave_id)

Definition at line 750 of file pigpiod_if.c.

int wave_tx_busy ( void  )

Definition at line 772 of file pigpiod_if.c.

int wave_tx_repeat ( void  )

Definition at line 744 of file pigpiod_if.c.

int wave_tx_start ( void  )

Definition at line 741 of file pigpiod_if.c.

int wave_tx_stop ( void  )

Definition at line 775 of file pigpiod_if.c.


Variable Documentation

pthread_mutex_t command_mutex = PTHREAD_MUTEX_INITIALIZER [static]

Definition at line 92 of file pigpiod_if.c.

Definition at line 85 of file pigpiod_if.c.

Definition at line 86 of file pigpiod_if.c.

uint32_t gLastLevel [static]

Definition at line 83 of file pigpiod_if.c.

uint32_t gNotifyBits [static]

Definition at line 82 of file pigpiod_if.c.

int gPigCommand = -1 [static]

Definition at line 78 of file pigpiod_if.c.

int gPigHandle = -1 [static]

Definition at line 79 of file pigpiod_if.c.

int gPigNotify = -1 [static]

Definition at line 80 of file pigpiod_if.c.

int gPigStarted = 0 [static]

Definition at line 88 of file pigpiod_if.c.

Definition at line 76 of file pigpiod_if.c.

pthread_t* pthNotify [static]

Definition at line 90 of file pigpiod_if.c.



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