#include <stdio.h>
#include <string.h>
#include <math.h>
#include <errno.h>
#include <stdlib.h>
#include <stdarg.h>
#include "../libusb/libusb-win32-src/src/usb.h"
#include "libsub.h"
#include <stddef.h>
Go to the source code of this file.
Classes | |
struct | sub_dev_cache_entry |
struct | sub_pack |
Defines | |
#define | __VER__ 18 |
#define | BUF_2_INT(I, BUF) I=(BUF[3]<<24)+(BUF[2]<<16)+(BUF[1]<<8)+BUF[0] |
#define | CTRL_REQ_RCPT_DEVICE 0 |
#define | CTRL_REQ_RCPT_ENDPOINT 2 |
#define | CTRL_REQ_RCPT_INTERFACE 1 |
#define | CTRL_REQ_RCPT_OTHER 3 |
#define | CTRL_REQ_TRANSFER_DIR_IN (1<<7) |
#define | CTRL_REQ_TRANSFER_DIR_OUT 0 |
#define | CTRL_REQ_TYPE_CLASS (1<<5) |
#define | CTRL_REQ_TYPE_STANDARD (0<<5) |
#define | CTRL_REQ_TYPE_VENDOR (2<<5) |
#define | DEF_SUB_ERROR(NAME, VAL, DESCR) DESCR, |
#define | INT_2_BUF(I, BUF) BUF[0]=((char)I);BUF[1]=(char)((I)>>8);BUF[2]=(char)((I)>>16);BUF[3]=(char)((I)>>24) |
#define | INT_2_LE16(I, LE16) |
#define | SUB_F_CPU 16000000 |
#define | SUB_FEATURE_SPI_SZ 0x00 |
#define | SUB_FIFO_IN_EP 0x84 |
#define | SUB_FIFO_OUT_EP 0x03 |
#define | SUB_IN_EP 0x82 |
#define | SUB_OUT_EP 0x01 |
#define | SUB_PID 0xFFC3 |
#define | SUB_VID 0x04D8 |
Functions | |
void | hexdump_buf (int level, char *buf, int sz) |
static void | ma_copy (uint8_t *ma_buf, sub_int32_t ma, int ma_sz) |
int | sub_adc_config (sub_handle hndl, int flags) |
int | sub_adc_read (sub_handle hndl, int *data, int *mux, int reads) |
int | sub_adc_single (sub_handle hndl, int *data, int mux) |
int | sub_bb_i2c_config (sub_handle hndl, int mode, int stretch_ms) |
int | sub_bb_i2c_read (sub_handle hndl, int channel, int sa, sub_int32_t ma, int ma_sz, char *buf, int sz) |
int | sub_bb_i2c_scan (sub_handle hndl, int channel, int *slave_cnt, char *slave_buf) |
int | sub_bb_i2c_write (sub_handle hndl, int channel, int sa, sub_int32_t ma, int ma_sz, char *buf, int sz) |
int | sub_close (sub_handle hndl) |
int | sub_control_request (sub_handle hndl, int type, int request, int value, int index, char *buf, int sz, int timeout) |
static int | sub_dev_cache_get_feature (sub_handle hndl, int feature, void *val) |
static int | sub_dev_cache_lookup (sub_handle hndl) |
int | sub_fifo_config (sub_handle hndl, int config) |
int | sub_fifo_read (sub_handle hndl, char *buf, int sz, int to_ms) |
int | sub_fifo_write (sub_handle hndl, char *buf, int sz, int to_ms) |
sub_device | sub_find_devices (sub_device first) |
int | sub_fpwm_config (sub_handle hndl, double freq_hz, int flags) |
int | sub_fpwm_set (sub_handle hndl, int pwm_n, double duty) |
struct sub_cfg_vpd * | sub_get_cfg_vpd (sub_handle hndl) |
int | sub_get_errno (void) |
int | sub_get_i2c_status (void) |
int | sub_get_mode (sub_handle hndl, int *mode) |
int | sub_get_product_id (sub_handle hndl, char *buf, int sz) |
int | sub_get_serial_number (sub_handle hndl, char *buf, int sz) |
struct sub_version * | sub_get_version (sub_handle hndl) |
int | sub_gpio_config (sub_handle hndl, sub_int32_t set, sub_int32_t *get, sub_int32_t mask) |
int | sub_gpio_read (sub_handle hndl, sub_int32_t *get) |
int | sub_gpio_write (sub_handle hndl, sub_int32_t set, sub_int32_t *get, sub_int32_t mask) |
int | sub_gpiob_config (sub_handle hndl, sub_int32_t set, sub_int32_t *get, sub_int32_t mask) |
int | sub_gpiob_read (sub_handle hndl, sub_int32_t *get) |
int | sub_gpiob_write (sub_handle hndl, sub_int32_t set, sub_int32_t *get, sub_int32_t mask) |
int | sub_i2c_config (sub_handle hndl, int sa, int flags) |
int | sub_i2c_freq (sub_handle hndl, sub_int32_t *freq) |
int | sub_i2c_read (sub_handle hndl, int sa, sub_int32_t ma, int ma_sz, char *buf, int sz) |
int | sub_i2c_scan (sub_handle hndl, int *slave_cnt, char *slave_buf) |
int | sub_i2c_start (sub_handle hndl) |
int | sub_i2c_stop (sub_handle hndl) |
int | sub_i2c_write (sub_handle hndl, int sa, sub_int32_t ma, int ma_sz, char *buf, int sz) |
int | sub_ir_config (sub_handle hndl, int carrier, int duty, int mode,...) |
int | sub_ir_tx (sub_handle hndl, int sz, char *buf) |
int | sub_lcd_write (sub_handle hndl, char *str) |
int | sub_mdio22 (sub_handle hndl, int op, int phyad, int regad, int data, int *content) |
int | sub_mdio45 (sub_handle hndl, int op, int prtad, int devad, int data, int *content) |
int | sub_mdio_xfer (sub_handle hndl, int count, union sub_mdio_frame *mdios) |
int | sub_mdio_xfer_ex (sub_handle hndl, int channel, int count, union sub_mdio_frame *mdios) |
sub_handle | sub_open (sub_device dev) |
int | sub_pwm_config (sub_handle hndl, int res_us, int limit) |
int | sub_pwm_set (sub_handle hndl, int pwm_n, int duty) |
int | sub_rs_get_config (sub_handle hndl, int *config, sub_int32_t *baud) |
int | sub_rs_set_config (sub_handle hndl, int config, sub_int32_t baud) |
int | sub_rs_timing (sub_handle hndl, int flags, int tx_space_us, int rx_msg_us, int rx_byte_us) |
int | sub_rs_xfer (sub_handle hndl, char *tx_buf, int tx_sz, char *rx_buf, int rx_sz) |
int | sub_sdio_transfer (sub_handle hndl, char *out_buf, char *in_buf, int out_sz, int in_sz, int ss_config) |
int | sub_spi_config (sub_handle hndl, int cfg_set, int *cfg_get) |
int | sub_spi_transfer (sub_handle hndl, char *out_buf, char *in_buf, int sz, int ss_config) |
char * | sub_strerror (int errnum) |
void | sub_trace (int level, char *format,...) |
int | sub_transaction (sub_handle hndl, sub_pack *outpk, sub_pack *inpk, int timeout) |
int | usb_transaction (sub_handle hndl, char *out_buf, int out_sz, char *in_buf, int in_sz, int timeout) |
Variables | |
int | sub_debug_level |
sub_dev_cache_entry | sub_dev_cache [255] |
char * | sub_errlist [] |
int | sub_errno |
int | sub_i2c_status |
#define __VER__ 18 |
Definition at line 89 of file lib/libsub.c.
#define BUF_2_INT | ( | I, | |||
BUF | ) | I=(BUF[3]<<24)+(BUF[2]<<16)+(BUF[1]<<8)+BUF[0] |
Definition at line 163 of file lib/libsub.c.
#define CTRL_REQ_RCPT_DEVICE 0 |
Definition at line 155 of file lib/libsub.c.
#define CTRL_REQ_RCPT_ENDPOINT 2 |
Definition at line 157 of file lib/libsub.c.
#define CTRL_REQ_RCPT_INTERFACE 1 |
Definition at line 156 of file lib/libsub.c.
#define CTRL_REQ_RCPT_OTHER 3 |
Definition at line 158 of file lib/libsub.c.
#define CTRL_REQ_TRANSFER_DIR_IN (1<<7) |
Definition at line 148 of file lib/libsub.c.
#define CTRL_REQ_TRANSFER_DIR_OUT 0 |
Definition at line 149 of file lib/libsub.c.
#define CTRL_REQ_TYPE_CLASS (1<<5) |
Definition at line 152 of file lib/libsub.c.
#define CTRL_REQ_TYPE_STANDARD (0<<5) |
Definition at line 151 of file lib/libsub.c.
#define CTRL_REQ_TYPE_VENDOR (2<<5) |
Definition at line 153 of file lib/libsub.c.
#define DEF_SUB_ERROR | ( | NAME, | |||
VAL, | |||||
DESCR | ) | DESCR, |
Definition at line 2167 of file lib/libsub.c.
#define INT_2_BUF | ( | I, | |||
BUF | ) | BUF[0]=((char)I);BUF[1]=(char)((I)>>8);BUF[2]=(char)((I)>>16);BUF[3]=(char)((I)>>24) |
Definition at line 164 of file lib/libsub.c.
#define INT_2_LE16 | ( | I, | |||
LE16 | ) |
do { \ ((char*)&LE16)[0]=(I); \ ((char*)&LE16)[1]=(I)>>8; \ } while(0)
Definition at line 165 of file lib/libsub.c.
#define SUB_F_CPU 16000000 |
Definition at line 99 of file lib/libsub.c.
#define SUB_FEATURE_SPI_SZ 0x00 |
Definition at line 80 of file lib/libsub.c.
#define SUB_FIFO_IN_EP 0x84 |
Definition at line 97 of file lib/libsub.c.
#define SUB_FIFO_OUT_EP 0x03 |
Definition at line 96 of file lib/libsub.c.
#define SUB_IN_EP 0x82 |
Definition at line 95 of file lib/libsub.c.
#define SUB_OUT_EP 0x01 |
Definition at line 94 of file lib/libsub.c.
#define SUB_PID 0xFFC3 |
Definition at line 92 of file lib/libsub.c.
#define SUB_VID 0x04D8 |
Definition at line 91 of file lib/libsub.c.
void hexdump_buf | ( | int | level, | |
char * | buf, | |||
int | sz | |||
) |
Definition at line 2252 of file lib/libsub.c.
static void ma_copy | ( | uint8_t * | ma_buf, | |
sub_int32_t | ma, | |||
int | ma_sz | |||
) | [static] |
Definition at line 748 of file lib/libsub.c.
int sub_adc_config | ( | sub_handle | hndl, | |
int | flags | |||
) |
Definition at line 1442 of file lib/libsub.c.
int sub_adc_read | ( | sub_handle | hndl, | |
int * | data, | |||
int * | mux, | |||
int | reads | |||
) |
Definition at line 1461 of file lib/libsub.c.
int sub_adc_single | ( | sub_handle | hndl, | |
int * | data, | |||
int | mux | |||
) |
Definition at line 1457 of file lib/libsub.c.
int sub_bb_i2c_config | ( | sub_handle | hndl, | |
int | mode, | |||
int | stretch_ms | |||
) |
Definition at line 1624 of file lib/libsub.c.
int sub_bb_i2c_read | ( | sub_handle | hndl, | |
int | channel, | |||
int | sa, | |||
sub_int32_t | ma, | |||
int | ma_sz, | |||
char * | buf, | |||
int | sz | |||
) |
Definition at line 1664 of file lib/libsub.c.
int sub_bb_i2c_scan | ( | sub_handle | hndl, | |
int | channel, | |||
int * | slave_cnt, | |||
char * | slave_buf | |||
) |
Definition at line 1642 of file lib/libsub.c.
int sub_bb_i2c_write | ( | sub_handle | hndl, | |
int | channel, | |||
int | sa, | |||
sub_int32_t | ma, | |||
int | ma_sz, | |||
char * | buf, | |||
int | sz | |||
) |
Definition at line 1710 of file lib/libsub.c.
int sub_close | ( | sub_handle | hndl | ) |
Definition at line 485 of file lib/libsub.c.
int sub_control_request | ( | sub_handle | hndl, | |
int | type, | |||
int | request, | |||
int | value, | |||
int | index, | |||
char * | buf, | |||
int | sz, | |||
int | timeout | |||
) |
Definition at line 2189 of file lib/libsub.c.
static int sub_dev_cache_get_feature | ( | sub_handle | hndl, | |
int | feature, | |||
void * | val | |||
) | [static] |
Definition at line 191 of file lib/libsub.c.
static int sub_dev_cache_lookup | ( | sub_handle | hndl | ) | [static] |
Definition at line 180 of file lib/libsub.c.
int sub_fifo_config | ( | sub_handle | hndl, | |
int | config | |||
) |
Definition at line 1936 of file lib/libsub.c.
int sub_fifo_read | ( | sub_handle | hndl, | |
char * | buf, | |||
int | sz, | |||
int | to_ms | |||
) |
Definition at line 1869 of file lib/libsub.c.
int sub_fifo_write | ( | sub_handle | hndl, | |
char * | buf, | |||
int | sz, | |||
int | to_ms | |||
) |
Definition at line 1836 of file lib/libsub.c.
sub_device sub_find_devices | ( | sub_device | first | ) |
Definition at line 238 of file lib/libsub.c.
int sub_fpwm_config | ( | sub_handle | hndl, | |
double | freq_hz, | |||
int | flags | |||
) |
Definition at line 1259 of file lib/libsub.c.
int sub_fpwm_set | ( | sub_handle | hndl, | |
int | pwm_n, | |||
double | duty | |||
) |
Definition at line 1319 of file lib/libsub.c.
struct sub_cfg_vpd* sub_get_cfg_vpd | ( | sub_handle | hndl | ) | [read] |
Definition at line 582 of file lib/libsub.c.
int sub_get_errno | ( | void | ) |
Definition at line 2378 of file lib/libsub.c.
int sub_get_i2c_status | ( | void | ) |
Definition at line 2383 of file lib/libsub.c.
int sub_get_mode | ( | sub_handle | hndl, | |
int * | mode | |||
) |
Definition at line 505 of file lib/libsub.c.
int sub_get_product_id | ( | sub_handle | hndl, | |
char * | buf, | |||
int | sz | |||
) |
Definition at line 2218 of file lib/libsub.c.
int sub_get_serial_number | ( | sub_handle | hndl, | |
char * | buf, | |||
int | sz | |||
) |
Definition at line 2206 of file lib/libsub.c.
struct sub_version* sub_get_version | ( | sub_handle | hndl | ) | [read] |
Definition at line 530 of file lib/libsub.c.
int sub_gpio_config | ( | sub_handle | hndl, | |
sub_int32_t | set, | |||
sub_int32_t * | get, | |||
sub_int32_t | mask | |||
) |
Definition at line 1151 of file lib/libsub.c.
int sub_gpio_read | ( | sub_handle | hndl, | |
sub_int32_t * | get | |||
) |
Definition at line 1168 of file lib/libsub.c.
int sub_gpio_write | ( | sub_handle | hndl, | |
sub_int32_t | set, | |||
sub_int32_t * | get, | |||
sub_int32_t | mask | |||
) |
Definition at line 1183 of file lib/libsub.c.
int sub_gpiob_config | ( | sub_handle | hndl, | |
sub_int32_t | set, | |||
sub_int32_t * | get, | |||
sub_int32_t | mask | |||
) |
Definition at line 1205 of file lib/libsub.c.
int sub_gpiob_read | ( | sub_handle | hndl, | |
sub_int32_t * | get | |||
) |
Definition at line 1222 of file lib/libsub.c.
int sub_gpiob_write | ( | sub_handle | hndl, | |
sub_int32_t | set, | |||
sub_int32_t * | get, | |||
sub_int32_t | mask | |||
) |
Definition at line 1237 of file lib/libsub.c.
int sub_i2c_config | ( | sub_handle | hndl, | |
int | sa, | |||
int | flags | |||
) |
Definition at line 672 of file lib/libsub.c.
int sub_i2c_freq | ( | sub_handle | hndl, | |
sub_int32_t * | freq | |||
) |
Definition at line 617 of file lib/libsub.c.
int sub_i2c_read | ( | sub_handle | hndl, | |
int | sa, | |||
sub_int32_t | ma, | |||
int | ma_sz, | |||
char * | buf, | |||
int | sz | |||
) |
Definition at line 759 of file lib/libsub.c.
int sub_i2c_scan | ( | sub_handle | hndl, | |
int * | slave_cnt, | |||
char * | slave_buf | |||
) |
Definition at line 727 of file lib/libsub.c.
int sub_i2c_start | ( | sub_handle | hndl | ) |
Definition at line 687 of file lib/libsub.c.
int sub_i2c_stop | ( | sub_handle | hndl | ) |
Definition at line 708 of file lib/libsub.c.
int sub_i2c_write | ( | sub_handle | hndl, | |
int | sa, | |||
sub_int32_t | ma, | |||
int | ma_sz, | |||
char * | buf, | |||
int | sz | |||
) |
Definition at line 827 of file lib/libsub.c.
int sub_ir_config | ( | sub_handle | hndl, | |
int | carrier, | |||
int | duty, | |||
int | mode, | |||
... | ||||
) |
Definition at line 1751 of file lib/libsub.c.
int sub_ir_tx | ( | sub_handle | hndl, | |
int | sz, | |||
char * | buf | |||
) |
Definition at line 1804 of file lib/libsub.c.
int sub_lcd_write | ( | sub_handle | hndl, | |
char * | str | |||
) |
Definition at line 1498 of file lib/libsub.c.
int sub_mdio22 | ( | sub_handle | hndl, | |
int | op, | |||
int | phyad, | |||
int | regad, | |||
int | data, | |||
int * | content | |||
) |
Definition at line 1041 of file lib/libsub.c.
int sub_mdio45 | ( | sub_handle | hndl, | |
int | op, | |||
int | prtad, | |||
int | devad, | |||
int | data, | |||
int * | content | |||
) |
Definition at line 1057 of file lib/libsub.c.
int sub_mdio_xfer | ( | sub_handle | hndl, | |
int | count, | |||
union sub_mdio_frame * | mdios | |||
) |
Definition at line 1096 of file lib/libsub.c.
int sub_mdio_xfer_ex | ( | sub_handle | hndl, | |
int | channel, | |||
int | count, | |||
union sub_mdio_frame * | mdios | |||
) |
Definition at line 1073 of file lib/libsub.c.
sub_handle sub_open | ( | sub_device | dev | ) |
Definition at line 363 of file lib/libsub.c.
int sub_pwm_config | ( | sub_handle | hndl, | |
int | res_us, | |||
int | limit | |||
) |
Definition at line 1349 of file lib/libsub.c.
int sub_pwm_set | ( | sub_handle | hndl, | |
int | pwm_n, | |||
int | duty | |||
) |
Definition at line 1410 of file lib/libsub.c.
int sub_rs_get_config | ( | sub_handle | hndl, | |
int * | config, | |||
sub_int32_t * | baud | |||
) |
Definition at line 1550 of file lib/libsub.c.
int sub_rs_set_config | ( | sub_handle | hndl, | |
int | config, | |||
sub_int32_t | baud | |||
) |
Definition at line 1524 of file lib/libsub.c.
int sub_rs_timing | ( | sub_handle | hndl, | |
int | flags, | |||
int | tx_space_us, | |||
int | rx_msg_us, | |||
int | rx_byte_us | |||
) |
Definition at line 1573 of file lib/libsub.c.
int sub_rs_xfer | ( | sub_handle | hndl, | |
char * | tx_buf, | |||
int | tx_sz, | |||
char * | rx_buf, | |||
int | rx_sz | |||
) |
Definition at line 1597 of file lib/libsub.c.
int sub_sdio_transfer | ( | sub_handle | hndl, | |
char * | out_buf, | |||
char * | in_buf, | |||
int | out_sz, | |||
int | in_sz, | |||
int | ss_config | |||
) |
Definition at line 1009 of file lib/libsub.c.
int sub_spi_config | ( | sub_handle | hndl, | |
int | cfg_set, | |||
int * | cfg_get | |||
) |
Definition at line 891 of file lib/libsub.c.
int sub_spi_transfer | ( | sub_handle | hndl, | |
char * | out_buf, | |||
char * | in_buf, | |||
int | sz, | |||
int | ss_config | |||
) |
Definition at line 915 of file lib/libsub.c.
char* sub_strerror | ( | int | errnum | ) |
Definition at line 2173 of file lib/libsub.c.
void sub_trace | ( | int | level, | |
char * | format, | |||
... | ||||
) |
Definition at line 2230 of file lib/libsub.c.
int sub_transaction | ( | sub_handle | hndl, | |
sub_pack * | outpk, | |||
sub_pack * | inpk, | |||
int | timeout | |||
) |
Definition at line 1967 of file lib/libsub.c.
int usb_transaction | ( | sub_handle | hndl, | |
char * | out_buf, | |||
int | out_sz, | |||
char * | in_buf, | |||
int | in_sz, | |||
int | timeout | |||
) |
Definition at line 2022 of file lib/libsub.c.
int sub_debug_level |
Definition at line 108 of file lib/libsub.c.
Definition at line 120 of file lib/libsub.c.
char* sub_errlist[] |
{ SUB_ERRORS }
Definition at line 2168 of file lib/libsub.c.
int sub_errno |
Definition at line 111 of file lib/libsub.c.
int sub_i2c_status |
Definition at line 112 of file lib/libsub.c.