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 |