37 #ifndef TWIHS_H_INCLUDED 38 #define TWIHS_H_INCLUDED 51 #define TWIHS_TIMEOUT 30000 57 #define TWIHS_SUCCESS 0 58 #define TWIHS_INVALID_ARGUMENT 1 59 #define TWIHS_ARBITRATION_LOST 2 60 #define TWIHS_NO_CHIP_FOUND 3 61 #define TWIHS_RECEIVE_OVERRUN 4 62 #define TWIHS_RECEIVE_NACK 5 63 #define TWIHS_SEND_OVERRUN 6 64 #define TWIHS_SEND_NACK 7 66 #define TWIHS_ERROR_TIMEOUT 9 191 #if !(SAMV70 || SAMV71 || SAME70 || SAMS70) 293 #if (SAMG53 || SAMG54 || SAMV70 || SAMV71 || SAME70 || SAMS70) 299 static inline void twihs_disable_slave_addr1_matching(
Twihs *p_twihs)
309 static inline void twihs_enable_slave_addr1_matching(
Twihs *p_twihs)
319 static inline void twihs_disable_slave_addr2_matching(
Twihs *p_twihs)
329 static inline void twihs_enable_slave_addr2_matching(
Twihs *p_twihs)
339 static inline void twihs_disable_slave_addr3_matching(
Twihs *p_twihs)
349 static inline void twihs_enable_slave_addr3_matching(
Twihs *p_twihs)
359 static inline void twihs_disable_slave_data_matching(
Twihs *p_twihs)
369 static inline void twihs_enable_slave_data_matching(
Twihs *p_twihs)
374 void twihs_set_sleepwalking(
Twihs *p_twihs,
375 uint32_t ul_matching_addr1,
bool flag1,
376 uint32_t ul_matching_addr2,
bool flag2,
377 uint32_t ul_matching_addr3,
bool flag3,
378 uint32_t ul_matching_data,
bool flag);
401 #if !(SAMV70 || SAMV71 || SAME70 || SAMS70) 407 #if !(SAMV70 || SAMV71 || SAME70 || SAMS70) #define TWIHS_CR_PECDIS
(TWIHS_CR) Packet Error Checking Disable
void * buffer
Where to find the data to be transferred.
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.
uint8_t twihs_read_byte(Twihs *p_twihs)
Reads a byte from the TWIHS bus.
void twihs_set_filter(Twihs *p_twihs, uint32_t ul_filter)
Set the filter for TWIHS.
void twihs_read_write_protection_status(Twihs *p_twihs, uint32_t *p_status)
Read the write protection status.
static void twihs_disable_smbus(Twihs *p_twihs)
Disable SMBus mode.
static void twihs_disable_slave_nack(Twihs *p_twihs)
Normal value to be returned in the ACK cycle of the data phase in slave receiver mode.
#define TWIHS_CR_SMBDIS
(TWIHS_CR) SMBus Mode Disabled
#define TWIHS_SMR_DATAMEN
(TWIHS_SMR) Data Matching Enable
Information concerning the data transmission.
#define TWIHS_SMR_SADR1EN
(TWIHS_SMR) Slave Address 1 Enable
#define TWIHS_CR_HSEN
(TWIHS_CR) TWIHS High-Speed Mode Enabled
#define TWIHS_CR_SMBEN
(TWIHS_CR) SMBus Mode Enabled
struct twihs_options twihs_options_t
Input parameters when initializing the TWIHS module mode.
#define TWIHS_CR_CLEAR
(TWIHS_CR) Bus CLEAR Command
void twihs_slave_init(Twihs *p_twihs, uint32_t ul_device_addr)
Initialize TWIHS slave mode.
#define TWIHS_SMR_SMDA
(TWIHS_SMR) SMBus Default Address
void twihs_set_write_protection(Twihs *p_twihs, bool flag)
Enables/Disables write protection mode.
uint32_t master_clk
MCK for TWIHS.
void twihs_set_slave_addr(Twihs *p_twihs, uint32_t ul_device_addr)
Set TWIHS slave address.
uint32_t addr_length
Length of the TWIHS data address segment (1-3 bytes).
#define TWIHS_SMR_SCLWSDIS
(TWIHS_SMR) Clock Wait State Disable
__O uint32_t TWIHS_CR
(Twihs Offset: 0x00) Control Register
#define TWIHS_CR_PECRQ
(TWIHS_CR) PEC Request
static void twihs_clear_disable_clock_wait_state(Twihs *p_twihs)
Clear clock wait state disable mode.
static void twihs_disable_smbus_host_header(Twihs *p_twihs)
Acknowledge of the SMBus Host Header disabled.
static void twihs_enable_smbus_quick_command(Twihs *p_twihs)
If Master mode is enabled, a SMBUS Quick Command is sent.
uint32_t twihs_probe(Twihs *p_twihs, uint8_t uc_slave_addr)
Test if a chip answers a given I2C address.
static void twihs_send_clear(Twihs *p_twihs)
If master mode is enabled, send a bus clear command.
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.
uint8_t chip
The desired address.
uint32_t twihs_master_init(Twihs *p_twihs, const twihs_options_t *p_opt)
Initialize TWIHS master mode.
Commonly used includes, types and macros.
__IO uint32_t TWIHS_SMR
(Twihs Offset: 0x08) Slave Mode Register
#define TWIHS_CR_QUICK
(TWIHS_CR) SMBus Quick Command
void twihs_enable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
Enable TWIHS interrupts.
uint32_t twihs_get_interrupt_mask(Twihs *p_twihs)
Read TWIHS interrupt mask.
static void twihs_enable_highspeed(Twihs *p_twihs)
Enable high speed mode.
static void twihs_enable_smbus(Twihs *p_twihs)
Enable SMBus mode.
static void twihs_request_pec(Twihs *p_twihs)
Request a packet error checking.
static void twihs_enable_slave_nack(Twihs *p_twihs)
NACK value to be returned in the ACK cycle of the data phase in slave receiver mode.
void twihs_reset(Twihs *p_twihs)
Reset TWIHS.
uint32_t twihs_get_interrupt_status(Twihs *p_twihs)
Get TWIHS interrupt status.
#define TWIHS_CR_ACMEN
(TWIHS_CR) Alternative Command Mode Enable
static void twihs_enable_smbus_host_header(Twihs *p_twihs)
Acknowledge of the SMBus Host Header enabled.
uint32_t twihs_slave_read(Twihs *p_twihs, uint8_t *p_data)
Read data from master.
static void twihs_enable_pec(Twihs *p_twihs)
Enable packet error checking.
static void twihs_disable_clock_wait_state(Twihs *p_twihs)
Clock stretching disabled in slave mode, OVRE and UNRE will indicate overrun and underrun.
#define TWIHS_SMR_SMHH
(TWIHS_SMR) SMBus Host Header
static void twihs_disable_pec(Twihs *p_twihs)
Disable packet error checking.
static void twihs_enable_alternative_command(Twihs *p_twihs)
Enable alternative command mode.
Twihs hardware registers.
static void twihs_enable_slave_default_addr(Twihs *p_twihs)
Acknowledge of the SMBus Default Address enabled.
uint32_t length
How many bytes do we want to transfer.
#define TWIHS_CR_PECEN
(TWIHS_CR) Packet Error Checking Enable
#define TWIHS_CR_ACMDIS
(TWIHS_CR) Alternative Command Mode Disable
#define TWIHS_SMR_SADR2EN
(TWIHS_SMR) Slave Address 2 Enable
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. ...
struct twihs_packet twihs_packet_t
Information concerning the data transmission.
uint32_t twihs_master_read(Twihs *p_twihs, twihs_packet_t *p_packet)
Read multiple bytes from a TWIHS compatible slave device.
static void twihs_disable_slave_default_addr(Twihs *p_twihs)
Acknowledge of the SMBus Default Address disabled.
uint8_t smbus
SMBUS mode (set 1 to use SMBUS quick command, otherwise don't).
uint32_t twihs_slave_write(Twihs *p_twihs, uint8_t *p_data)
Write data to TWIHS bus.
void twihs_set_alternative_command(Twihs *p_twihs, uint32_t ul_alt_cmd)
Set length/direction/PEC for alternative command mode.
#define TWIHS_SMR_NACKEN
(TWIHS_SMR) Slave Receiver Data Phase NACK enable
uint8_t chip
TWIHS chip address to communicate with.
void twihs_disable_slave_mode(Twihs *p_twihs)
Disable TWIHS slave mode.
uint32_t speed
The baud rate of the TWIHS bus.
void twihs_disable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
Disable TWIHS interrupts.
void twihs_enable_slave_mode(Twihs *p_twihs)
Enable TWIHS slave mode.
Input parameters when initializing the TWIHS module mode.
static void twihs_disable_alternative_command(Twihs *p_twihs)
Enable alternative command mode.
uint32_t twihs_master_write(Twihs *p_twihs, twihs_packet_t *p_packet)
Write multiple bytes to a TWIHS compatible slave device.
Pdc * twihs_get_pdc_base(Twihs *p_twihs)
Get TWIHS PDC base address.
static void twihs_disable_highspeed(Twihs *p_twihs)
Disable high speed mode.
void twihs_disable_master_mode(Twihs *p_twihs)
Disable TWIHS master mode.
#define TWIHS_CR_HSDIS
(TWIHS_CR) TWIHS High-Speed Mode Disabled
void twihs_enable_master_mode(Twihs *p_twihs)
Enable TWIHS master mode.
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 an...
#define TWIHS_SMR_SADR3EN
(TWIHS_SMR) Slave Address 3 Enable