9 #pragma GCC optimize ("O2") 36 I2C_State I2CDevice::log[I2C_LOG_SIZE]
IN_CCM;
37 uint8_t I2CDevice::log_ptr=0;
90 #if defined(I2C1_SDA) && defined(I2C1_SCL) && !defined(BOARD_I2C1_DISABLE) 92 #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==0 96 #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C1) 116 #if defined(I2C2_SDA) && defined(I2C2_SCL) && !defined( BOARD_I2C2_DISABLE) && !defined(BOARD_HAS_UART3) // in this case I2C on FlexiPort will be bus 2 119 #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==1 123 #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C2) 143 #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==2 147 #ifdef BOARD_I2C_FLEXI 148 if(hal_param_helper->_flexi_i2c){
149 #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C3) 166 #if defined(BOARD_SOFT_SCL) && defined(BOARD_SOFT_SDA) 178 #if defined(I2C3_SDA) && defined(I2C3_SCL) 236 if(recv_len) memset(recv, 0, recv_len);
240 }
else if(send_len==1){
261 if(retries--)
goto again;
269 I2C_State &sp = log[log_ptr];
296 I2C_State &sp = log[log_ptr];
301 sp.send_len = send_len;
302 sp.recv_len = recv_len;
309 if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
349 _dev->
I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST);
371 if(retries--)
goto again;
386 _dev->
I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST);
400 uint32_t recv_len, uint8_t times){
404 if(!ret)
return false;
434 if(ret!=
I2C_OK)
return ret;
453 uint32_t timeout =
i2c_bit_time * 9 * (len+1) * 8 + 100;
460 _dev->
I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN;
476 uint32_t
I2CDevice::i2c_read(uint8_t addr,
const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
479 if(ret!=
I2C_OK)
return ret;
497 uint32_t timeout =
i2c_bit_time * 9 * (txlen+rxlen) * 8 + 100;
503 I2C_State &sp = log[log_ptr];
511 if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
518 _dev->
I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN;
521 I2C_State &sp = log[log_ptr];
529 if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
550 asm volatile(
"MOV %0, r1\n\t" :
"=rm" (err));
552 uint32_t sr1itflags =
_dev->
I2Cx->SR1;
553 uint32_t itsources =
_dev->
I2Cx->CR2;
559 _dev->
I2Cx->SR1 = (uint16_t)(~I2C_BIT_BERR);
563 if(((sr1itflags &
I2C_BIT_ARLO) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
567 _dev->
I2Cx->SR1 = (uint16_t)(~I2C_BIT_ARLO);
571 if(((sr1itflags &
I2C_BIT_AF) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
573 _dev->
I2Cx->SR1 = (uint16_t)(~I2C_BIT_AF);
587 I2C_State &sp = log[log_ptr];
595 if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
615 _dev->
I2Cx->CR1 &= (uint16_t)(~I2C_CR1_STOP);
635 uint32_t sr2itflags =
_dev->
I2Cx->SR2;
639 if((sr1itflags &
I2C_BIT_TXE & I2C_BIT_MASK) != RESET) {
646 _dev->
I2Cx->CR2 &= ~I2C_CR2_ITBUFEN;
650 if((sr1itflags &
I2C_BIT_RXNE & I2C_BIT_MASK) != RESET) {
669 if((sr1itflags &
I2C_BIT_BTF & I2C_BIT_MASK) != RESET) {
670 if((sr2itflags & (
I2C_BIT_TRA) & I2C_BIT_MASK) != RESET) {
679 _dev->
I2Cx->CR2 &= ~I2C_CR2_ITBUFEN;
693 I2C_State &sp = log[log_ptr];
701 if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
711 _dev->
I2Cx->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN);
713 _dev->
I2Cx->CR1 &= ~(I2C_CR1_STOP | I2C_CR1_START);
736 if( (
_dev->
I2Cx->CR1 & I2C_CR1_PE) ) {
743 while (
_dev->
I2Cx->CR1 & I2C_CR1_STOP ){
776 if(ret==
I2C_OK)
return ret;
780 _dev->
I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST);
static Handler get_handler(AP_HAL::MemberProc proc)
#define I2C_ERR_STOP_TIMEOUT
#define MAX_I2C_DEVICES
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint8_t read(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t *buf)
static void i2c_set_isr_handler(const i2c_dev *dev, Handler h)
uint8_t transfer(uint8_t addr, uint8_t send_len, const uint8_t *send, uint8_t len, uint8_t *buf)
#define LeaveCriticalSection
const i2c_dev *const _I2C2
uint32_t wait_stop_done(bool v)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
void init_hw(const gpio_dev *scl_dev, uint8_t scl_bit, const gpio_dev *sda_dev, uint8_t sda_bit, const timer_dev *tim)
static void * get_current_task()
static void task_resume(void *h)
#define HAL_SEMAPHORE_BLOCK_FOREVER
uint32_t i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len)
static void _register_io_process(Handler h, Revo_IO_Flags flags)
#define I2C_SMALL_TIMEOUT
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times)
void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
void i2c_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void register_completion_callback(Handler h)
uint32_t i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
void set_low_speed(bool s)
static void i2c_send_address(const i2c_dev *dev, uint8_t address, uint8_t direction)
#define I2C_NACKPosition_Next
static uint32_t _micros()
const i2c_dev *const _I2C1
static const timer_dev * _timers[3]
static void i2c_clear_isr_handler(const i2c_dev *dev)
#define I2C_Direction_Receiver
static F4Light::I2CDevice * devices[MAX_I2C_DEVICES]
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
#define I2C_Direction_Transmitter
static void task_pause(uint32_t t)
static void delay_ns100(uint32_t us)
void revo_call_handler(Handler h, uint32_t arg)
#define EnterCriticalSection
static F4Light::Semaphore _semaphores[3]
Stores STM32-specific information related to a given Maple pin.
const gpio_dev *const gpio_device
uint8_t writeBuffer(uint8_t addr_, uint8_t len_, const uint8_t *data)
void hal_yield(uint16_t ttw)
bool i2c_bus_reset(const i2c_dev *dev)