Classes | Macros | Typedefs | Functions | Variables
pigpiod_if2.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_if2.h"
Include dependency graph for pigpiod_if2.c:

Go to the source code of this file.

Classes

struct  callback_s
 
struct  evtCallback_s
 

Macros

#define MAX_PI   32
 
#define PI_MAX_REPORTS_PER_READ   4096
 
#define STACK_SIZE   (256*1024)
 

Typedefs

typedef void(* CBF_t) ()
 

Functions

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

Variables

static callback_tgCallBackFirst = 0
 
static callback_tgCallBackLast = 0
 
static int gCancelState [MAX_PI]
 
static pthread_mutex_t gCmdMutex [MAX_PI]
 
static evtCallback_tgeCallBackFirst = 0
 
static evtCallback_tgeCallBackLast = 0
 
static uint32_t gEventBits [MAX_PI]
 
static uint32_t gLastLevel [MAX_PI]
 
static uint32_t gNotifyBits [MAX_PI]
 
static int gPigCommand [MAX_PI]
 
static int gPigHandle [MAX_PI]
 
static int gPigNotify [MAX_PI]
 
static int gPiInUse [MAX_PI]
 
static pthread_t * gPthNotify [MAX_PI]
 

Macro Definition Documentation

#define MAX_PI   32

Definition at line 59 of file pigpiod_if2.c.

#define PI_MAX_REPORTS_PER_READ   4096

Definition at line 55 of file pigpiod_if2.c.

#define STACK_SIZE   (256*1024)

Definition at line 57 of file pigpiod_if2.c.

Typedef Documentation

typedef void(* CBF_t) ()

Definition at line 61 of file pigpiod_if2.c.

Function Documentation

static void _ewfe ( int  pi,
unsigned  event,
uint32_t  tick,
void *  user 
)
static

Definition at line 507 of file pigpiod_if2.c.

static void _pml ( int  pi)
static

Definition at line 115 of file pigpiod_if2.c.

static void _pmu ( int  pi)
static

Definition at line 124 of file pigpiod_if2.c.

static void _wfe ( int  pi,
unsigned  user_gpio,
unsigned  level,
uint32_t  tick,
void *  user 
)
static

Definition at line 427 of file pigpiod_if2.c.

int bb_i2c_close ( int  pi,
unsigned  SDA 
)

Definition at line 1505 of file pigpiod_if2.c.

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

Definition at line 1486 of file pigpiod_if2.c.

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

Definition at line 1508 of file pigpiod_if2.c.

int bb_serial_invert ( int  pi,
unsigned  user_gpio,
unsigned  invert 
)

Definition at line 1202 of file pigpiod_if2.c.

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

Definition at line 1183 of file pigpiod_if2.c.

int bb_serial_read_close ( int  pi,
unsigned  user_gpio 
)

Definition at line 1199 of file pigpiod_if2.c.

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

Definition at line 1164 of file pigpiod_if2.c.

int bb_spi_close ( int  pi,
unsigned  CS 
)

Definition at line 1576 of file pigpiod_if2.c.

int bb_spi_open ( int  pi,
unsigned  CS,
unsigned  MISO,
unsigned  MOSI,
unsigned  SCLK,
unsigned  baud,
unsigned  spiFlags 
)

Definition at line 1543 of file pigpiod_if2.c.

int bb_spi_xfer ( int  pi,
unsigned  CS,
char *  txBuf,
char *  rxBuf,
unsigned  count 
)

Definition at line 1579 of file pigpiod_if2.c.

int bsc_i2c ( int  pi,
int  i2c_addr,
bsc_xfer_t bscxfer 
)

Definition at line 2060 of file pigpiod_if2.c.

int bsc_xfer ( int  pi,
bsc_xfer_t bscxfer 
)

Definition at line 2021 of file pigpiod_if2.c.

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

Definition at line 1962 of file pigpiod_if2.c.

int callback_cancel ( unsigned  id)

Definition at line 1969 of file pigpiod_if2.c.

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

Definition at line 1965 of file pigpiod_if2.c.

int clear_bank_1 ( int  pi,
uint32_t  levels 
)

Definition at line 857 of file pigpiod_if2.c.

int clear_bank_2 ( int  pi,
uint32_t  levels 
)

Definition at line 860 of file pigpiod_if2.c.

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

Definition at line 1770 of file pigpiod_if2.c.

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

Definition at line 1790 of file pigpiod_if2.c.

int delete_script ( int  pi,
unsigned  script_id 
)

Definition at line 1161 of file pigpiod_if2.c.

static void dispatch_notification ( int  pi,
gpioReport_t r 
)
static

Definition at line 295 of file pigpiod_if2.c.

int event_callback ( int  pi,
unsigned  event,
evtCBFunc_t  f 
)

Definition at line 2070 of file pigpiod_if2.c.

int event_callback_cancel ( unsigned  id)

Definition at line 2077 of file pigpiod_if2.c.

int event_callback_ex ( int  pi,
unsigned  event,
evtCBFuncEx_t  f,
void *  user 
)

Definition at line 2073 of file pigpiod_if2.c.

int event_trigger ( int  pi,
unsigned  event 
)

Definition at line 2129 of file pigpiod_if2.c.

int file_close ( int  pi,
unsigned  handle 
)

Definition at line 1873 of file pigpiod_if2.c.

int file_list ( int  pi,
char *  fpat,
char *  buf,
unsigned  count 
)

Definition at line 1931 of file pigpiod_if2.c.

int file_open ( int  pi,
char *  file,
unsigned  mode 
)

Definition at line 1851 of file pigpiod_if2.c.

int file_read ( int  pi,
unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1895 of file pigpiod_if2.c.

int file_seek ( int  pi,
unsigned  handle,
int32_t  seekOffset,
int  seekFrom 
)

Definition at line 1912 of file pigpiod_if2.c.

int file_write ( int  pi,
unsigned  handle,
char *  buf,
unsigned  count 
)

Definition at line 1876 of file pigpiod_if2.c.

static void findEventBits ( int  pi)
static

Definition at line 487 of file pigpiod_if2.c.

static void findNotifyBits ( int  pi)
static

Definition at line 407 of file pigpiod_if2.c.

uint32_t get_current_tick ( int  pi)

Definition at line 891 of file pigpiod_if2.c.

uint32_t get_hardware_revision ( int  pi)

Definition at line 894 of file pigpiod_if2.c.

int get_mode ( int  pi,
unsigned  gpio 
)

Definition at line 797 of file pigpiod_if2.c.

int get_pad_strength ( int  pi,
unsigned  pad 
)

Definition at line 1820 of file pigpiod_if2.c.

uint32_t get_pigpio_version ( int  pi)

Definition at line 897 of file pigpiod_if2.c.

int get_PWM_dutycycle ( int  pi,
unsigned  user_gpio 
)

Definition at line 812 of file pigpiod_if2.c.

int get_PWM_frequency ( int  pi,
unsigned  user_gpio 
)

Definition at line 827 of file pigpiod_if2.c.

int get_PWM_range ( int  pi,
unsigned  user_gpio 
)

Definition at line 818 of file pigpiod_if2.c.

int get_PWM_real_range ( int  pi,
unsigned  user_gpio 
)

Definition at line 821 of file pigpiod_if2.c.

int get_servo_pulsewidth ( int  pi,
unsigned  user_gpio 
)

Definition at line 833 of file pigpiod_if2.c.

int gpio_read ( int  pi,
unsigned  gpio 
)

Definition at line 803 of file pigpiod_if2.c.

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

Definition at line 1037 of file pigpiod_if2.c.

int gpio_write ( int  pi,
unsigned  gpio,
unsigned  level 
)

Definition at line 806 of file pigpiod_if2.c.

int hardware_clock ( int  pi,
unsigned  gpio,
unsigned  frequency 
)

Definition at line 869 of file pigpiod_if2.c.

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

Definition at line 872 of file pigpiod_if2.c.

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

Definition at line 1335 of file pigpiod_if2.c.

int i2c_close ( int  pi,
unsigned  handle 
)

Definition at line 1224 of file pigpiod_if2.c.

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

Definition at line 1205 of file pigpiod_if2.c.

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

Definition at line 1280 of file pigpiod_if2.c.

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

Definition at line 1319 of file pigpiod_if2.c.

int i2c_read_byte ( int  pi,
unsigned  handle 
)

Definition at line 1233 of file pigpiod_if2.c.

int i2c_read_byte_data ( int  pi,
unsigned  handle,
unsigned  reg 
)

Definition at line 1274 of file pigpiod_if2.c.

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

Definition at line 1416 of file pigpiod_if2.c.

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

Definition at line 1365 of file pigpiod_if2.c.

int i2c_read_word_data ( int  pi,
unsigned  handle,
unsigned  reg 
)

Definition at line 1277 of file pigpiod_if2.c.

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

Definition at line 1299 of file pigpiod_if2.c.

int i2c_write_byte ( int  pi,
unsigned  handle,
unsigned  val 
)

Definition at line 1230 of file pigpiod_if2.c.

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

Definition at line 1236 of file pigpiod_if2.c.

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

Definition at line 1432 of file pigpiod_if2.c.

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

Definition at line 1396 of file pigpiod_if2.c.

int i2c_write_quick ( int  pi,
unsigned  handle,
unsigned  bit 
)

Definition at line 1227 of file pigpiod_if2.c.

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

Definition at line 1255 of file pigpiod_if2.c.

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

Definition at line 1451 of file pigpiod_if2.c.

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

Definition at line 433 of file pigpiod_if2.c.

static int intEventCallback ( int  pi,
unsigned  event,
void *  f,
void *  user,
int  ex 
)
static

Definition at line 513 of file pigpiod_if2.c.

int notify_begin ( int  pi,
unsigned  handle,
uint32_t  bits 
)

Definition at line 839 of file pigpiod_if2.c.

int notify_close ( int  pi,
unsigned  handle 
)

Definition at line 845 of file pigpiod_if2.c.

int notify_open ( int  pi)

Definition at line 836 of file pigpiod_if2.c.

int notify_pause ( int  pi,
unsigned  handle 
)

Definition at line 842 of file pigpiod_if2.c.

static int pigpio_command ( int  pi,
int  command,
int  p1,
int  p2,
int  rl 
)
static

Definition at line 133 of file pigpiod_if2.c.

static int pigpio_command_ext ( int  pi,
int  command,
int  p1,
int  p2,
int  p3,
int  extents,
gpioExtent_t ext,
int  rl 
)
static

Definition at line 196 of file pigpiod_if2.c.

char* pigpio_error ( int  errnum)

Definition at line 623 of file pigpiod_if2.c.

static int pigpio_notify ( int  pi)
static

Definition at line 164 of file pigpiod_if2.c.

int pigpio_start ( char *  addrStr,
char *  portStr 
)

Definition at line 711 of file pigpiod_if2.c.

void pigpio_stop ( int  pi)

Definition at line 763 of file pigpiod_if2.c.

unsigned pigpiod_if_version ( void  )

Definition at line 663 of file pigpiod_if2.c.

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

Definition at line 237 of file pigpiod_if2.c.

static void* pthNotifyThread ( void *  x)
static

Definition at line 366 of file pigpiod_if2.c.

uint32_t read_bank_1 ( int  pi)

Definition at line 851 of file pigpiod_if2.c.

uint32_t read_bank_2 ( int  pi)

Definition at line 854 of file pigpiod_if2.c.

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

Definition at line 565 of file pigpiod_if2.c.

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

Definition at line 1101 of file pigpiod_if2.c.

int script_status ( int  pi,
unsigned  script_id,
uint32_t *  param 
)

Definition at line 1139 of file pigpiod_if2.c.

int serial_close ( int  pi,
unsigned  handle 
)

Definition at line 1722 of file pigpiod_if2.c.

int serial_data_available ( int  pi,
unsigned  handle 
)

Definition at line 1767 of file pigpiod_if2.c.

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

Definition at line 1700 of file pigpiod_if2.c.

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

Definition at line 1750 of file pigpiod_if2.c.

int serial_read_byte ( int  pi,
unsigned  handle 
)

Definition at line 1728 of file pigpiod_if2.c.

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

Definition at line 1731 of file pigpiod_if2.c.

int serial_write_byte ( int  pi,
unsigned  handle,
unsigned  val 
)

Definition at line 1725 of file pigpiod_if2.c.

int set_bank_1 ( int  pi,
uint32_t  levels 
)

Definition at line 863 of file pigpiod_if2.c.

int set_bank_2 ( int  pi,
uint32_t  levels 
)

Definition at line 866 of file pigpiod_if2.c.

int set_glitch_filter ( int  pi,
unsigned  user_gpio,
unsigned  steady 
)

Definition at line 1056 of file pigpiod_if2.c.

int set_mode ( int  pi,
unsigned  gpio,
unsigned  mode 
)

Definition at line 794 of file pigpiod_if2.c.

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

Definition at line 1059 of file pigpiod_if2.c.

int set_pad_strength ( int  pi,
unsigned  pad,
unsigned  padStrength 
)

Definition at line 1823 of file pigpiod_if2.c.

int set_pull_up_down ( int  pi,
unsigned  gpio,
unsigned  pud 
)

Definition at line 800 of file pigpiod_if2.c.

int set_PWM_dutycycle ( int  pi,
unsigned  user_gpio,
unsigned  dutycycle 
)

Definition at line 809 of file pigpiod_if2.c.

int set_PWM_frequency ( int  pi,
unsigned  user_gpio,
unsigned  frequency 
)

Definition at line 824 of file pigpiod_if2.c.

int set_PWM_range ( int  pi,
unsigned  user_gpio,
unsigned  range 
)

Definition at line 815 of file pigpiod_if2.c.

int set_servo_pulsewidth ( int  pi,
unsigned  user_gpio,
unsigned  pulsewidth 
)

Definition at line 830 of file pigpiod_if2.c.

int set_watchdog ( int  pi,
unsigned  user_gpio,
unsigned  timeout 
)

Definition at line 848 of file pigpiod_if2.c.

int shell_ ( int  pi,
char *  scriptName,
char *  scriptString 
)

Definition at line 1826 of file pigpiod_if2.c.

int spi_close ( int  pi,
unsigned  handle 
)

Definition at line 1632 of file pigpiod_if2.c.

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

Definition at line 1613 of file pigpiod_if2.c.

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

Definition at line 1635 of file pigpiod_if2.c.

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

Definition at line 1652 of file pigpiod_if2.c.

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

Definition at line 1671 of file pigpiod_if2.c.

pthread_t* start_thread ( gpioThreadFunc_t  thread_func,
void *  userdata 
)

Definition at line 668 of file pigpiod_if2.c.

int stop_script ( int  pi,
unsigned  script_id 
)

Definition at line 1158 of file pigpiod_if2.c.

void stop_thread ( pthread_t *  pth)

Definition at line 701 of file pigpiod_if2.c.

int store_script ( int  pi,
char *  script 
)

Definition at line 1078 of file pigpiod_if2.c.

void time_sleep ( double  seconds)

Definition at line 605 of file pigpiod_if2.c.

double time_time ( void  )

Definition at line 593 of file pigpiod_if2.c.

int update_script ( int  pi,
unsigned  script_id,
unsigned  numPar,
uint32_t *  param 
)

Definition at line 1120 of file pigpiod_if2.c.

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

Definition at line 1999 of file pigpiod_if2.c.

int wait_for_event ( int  pi,
unsigned  event,
double  timeout 
)

Definition at line 2107 of file pigpiod_if2.c.

int wave_add_generic ( int  pi,
unsigned  numPulses,
gpioPulse_t pulses 
)

Definition at line 906 of file pigpiod_if2.c.

int wave_add_new ( int  pi)

Definition at line 903 of file pigpiod_if2.c.

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 at line 927 of file pigpiod_if2.c.

int wave_chain ( int  pi,
char *  buf,
unsigned  bufSize 
)

Definition at line 982 of file pigpiod_if2.c.

int wave_clear ( int  pi)

Definition at line 900 of file pigpiod_if2.c.

int wave_create ( int  pi)

Definition at line 961 of file pigpiod_if2.c.

int wave_delete ( int  pi,
unsigned  wave_id 
)

Definition at line 964 of file pigpiod_if2.c.

int wave_get_cbs ( int  pi)

Definition at line 1028 of file pigpiod_if2.c.

int wave_get_high_cbs ( int  pi)

Definition at line 1031 of file pigpiod_if2.c.

int wave_get_high_micros ( int  pi)

Definition at line 1013 of file pigpiod_if2.c.

int wave_get_high_pulses ( int  pi)

Definition at line 1022 of file pigpiod_if2.c.

int wave_get_max_cbs ( int  pi)

Definition at line 1034 of file pigpiod_if2.c.

int wave_get_max_micros ( int  pi)

Definition at line 1016 of file pigpiod_if2.c.

int wave_get_max_pulses ( int  pi)

Definition at line 1025 of file pigpiod_if2.c.

int wave_get_micros ( int  pi)

Definition at line 1010 of file pigpiod_if2.c.

int wave_get_pulses ( int  pi)

Definition at line 1019 of file pigpiod_if2.c.

int wave_send_once ( int  pi,
unsigned  wave_id 
)

Definition at line 973 of file pigpiod_if2.c.

int wave_send_repeat ( int  pi,
unsigned  wave_id 
)

Definition at line 976 of file pigpiod_if2.c.

int wave_send_using_mode ( int  pi,
unsigned  wave_id,
unsigned  mode 
)

Definition at line 979 of file pigpiod_if2.c.

int wave_tx_at ( int  pi)

Definition at line 1001 of file pigpiod_if2.c.

int wave_tx_busy ( int  pi)

Definition at line 1004 of file pigpiod_if2.c.

int wave_tx_repeat ( int  pi)

Definition at line 970 of file pigpiod_if2.c.

int wave_tx_start ( int  pi)

Definition at line 967 of file pigpiod_if2.c.

int wave_tx_stop ( int  pi)

Definition at line 1007 of file pigpiod_if2.c.

Variable Documentation

callback_t* gCallBackFirst = 0
static

Definition at line 107 of file pigpiod_if2.c.

callback_t* gCallBackLast = 0
static

Definition at line 108 of file pigpiod_if2.c.

int gCancelState[MAX_PI]
static

Definition at line 105 of file pigpiod_if2.c.

pthread_mutex_t gCmdMutex[MAX_PI]
static

Definition at line 104 of file pigpiod_if2.c.

evtCallback_t* geCallBackFirst = 0
static

Definition at line 110 of file pigpiod_if2.c.

evtCallback_t* geCallBackLast = 0
static

Definition at line 111 of file pigpiod_if2.c.

uint32_t gEventBits[MAX_PI]
static

Definition at line 98 of file pigpiod_if2.c.

uint32_t gLastLevel[MAX_PI]
static

Definition at line 100 of file pigpiod_if2.c.

uint32_t gNotifyBits[MAX_PI]
static

Definition at line 99 of file pigpiod_if2.c.

int gPigCommand[MAX_PI]
static

Definition at line 94 of file pigpiod_if2.c.

int gPigHandle[MAX_PI]
static

Definition at line 95 of file pigpiod_if2.c.

int gPigNotify[MAX_PI]
static

Definition at line 96 of file pigpiod_if2.c.

int gPiInUse[MAX_PI]
static

Definition at line 92 of file pigpiod_if2.c.

pthread_t* gPthNotify[MAX_PI]
static

Definition at line 102 of file pigpiod_if2.c.



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