Two-Wire Interface (TWIHS) driver for SAM. More...
#include "twihs.h"
Go to the source code of this file.
Macros | |
#define | I2C_FAST_MODE_SPEED 400000 |
#define | LOW_LEVEL_TIME_LIMIT 384000 |
#define | TWIHS_CLK_CALC_ARGU 3 |
#define | TWIHS_CLK_DIV_MAX 0xFF |
#define | TWIHS_CLK_DIV_MIN 7 |
#define | TWIHS_CLK_DIVIDER 2 |
Functions | |
void | twihs_disable_interrupt (Twihs *p_twihs, uint32_t ul_sources) |
Disable TWIHS interrupts. More... | |
void | twihs_disable_master_mode (Twihs *p_twihs) |
Disable TWIHS master mode. More... | |
void | twihs_disable_slave_mode (Twihs *p_twihs) |
Disable TWIHS slave mode. More... | |
void | twihs_enable_interrupt (Twihs *p_twihs, uint32_t ul_sources) |
Enable TWIHS interrupts. More... | |
void | twihs_enable_master_mode (Twihs *p_twihs) |
Enable TWIHS master mode. More... | |
void | twihs_enable_slave_mode (Twihs *p_twihs) |
Enable TWIHS slave mode. More... | |
uint32_t | twihs_get_interrupt_mask (Twihs *p_twihs) |
Read TWIHS interrupt mask. More... | |
uint32_t | twihs_get_interrupt_status (Twihs *p_twihs) |
Get TWIHS interrupt status. More... | |
Pdc * | twihs_get_pdc_base (Twihs *p_twihs) |
Get TWIHS PDC base address. More... | |
void | twihs_mask_slave_addr (Twihs *p_twihs, uint32_t ul_mask) |
A mask can be applied on the slave device address in slave mode in order to allow multiple address answer. For each bit of the MASK field set to one the corresponding SADR bit will be masked. More... | |
uint32_t | twihs_master_init (Twihs *p_twihs, const twihs_options_t *p_opt) |
Initialize TWIHS master mode. More... | |
uint32_t | twihs_master_read (Twihs *p_twihs, twihs_packet_t *p_packet) |
Read multiple bytes from a TWIHS compatible slave device. More... | |
uint32_t | twihs_master_write (Twihs *p_twihs, twihs_packet_t *p_packet) |
Write multiple bytes to a TWIHS compatible slave device. More... | |
static uint32_t | twihs_mk_addr (const uint8_t *addr, int len) |
uint32_t | twihs_probe (Twihs *p_twihs, uint8_t uc_slave_addr) |
Test if a chip answers a given I2C address. More... | |
uint8_t | twihs_read_byte (Twihs *p_twihs) |
Reads a byte from the TWIHS bus. More... | |
void | twihs_read_write_protection_status (Twihs *p_twihs, uint32_t *p_status) |
Read the write protection status. More... | |
void | twihs_reset (Twihs *p_twihs) |
Reset TWIHS. More... | |
void | twihs_set_alternative_command (Twihs *p_twihs, uint32_t ul_alt_cmd) |
Set length/direction/PEC for alternative command mode. More... | |
void | twihs_set_filter (Twihs *p_twihs, uint32_t ul_filter) |
Set the filter for TWIHS. More... | |
void | twihs_set_slave_addr (Twihs *p_twihs, uint32_t ul_device_addr) |
Set TWIHS slave address. More... | |
uint32_t | twihs_set_speed (Twihs *p_twihs, uint32_t ul_speed, uint32_t ul_mck) |
Set the I2C bus speed in conjunction with the clock frequency. More... | |
void | twihs_set_write_protection (Twihs *p_twihs, bool flag) |
Enables/Disables write protection mode. More... | |
void | twihs_slave_init (Twihs *p_twihs, uint32_t ul_device_addr) |
Initialize TWIHS slave mode. More... | |
uint32_t | twihs_slave_read (Twihs *p_twihs, uint8_t *p_data) |
Read data from master. More... | |
uint32_t | twihs_slave_write (Twihs *p_twihs, uint8_t *p_data) |
Write data to TWIHS bus. More... | |
void | twihs_smbus_set_timing (Twihs *p_twihs, uint32_t ul_timing) |
Set the prescaler, TLOW:SEXT, TLOW:MEXT and clock high max cycles for SMBUS mode. More... | |
void | twihs_write_byte (Twihs *p_twihs, uint8_t uc_byte) |
Sends a byte of data to one of the TWIHS slaves on the bus. More... | |
Two-Wire Interface (TWIHS) driver for SAM.
Copyright (c) 2013-2018 Microchip Technology Inc. and its subsidiaries.
Definition in file twihs.c.