diff --git a/os/hal/include/i2c_brts.h b/os/hal/include/i2c_brts.h new file mode 100644 index 000000000..a01606a18 --- /dev/null +++ b/os/hal/include/i2c_brts.h @@ -0,0 +1,248 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file i2c.h + * @brief I2C Driver macros and structures. + * + * @addtogroup I2C + * @{ + */ + +#ifndef _I2C_H_ +#define _I2C_H_ + +#if HAL_USE_I2C || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the mutual exclusion APIs on the I2C bus. + */ +#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define I2C_USE_MUTUAL_EXCLUSION TRUE +#endif + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +/** + * @brief Driver state machine possible states. + */ +typedef enum { + I2C_UNINIT = 0, /**< Not initialized. */ + I2C_STOP = 1, /**< Stopped. */ + I2C_READY = 2, /**< Ready. Start condition generated. */ + I2C_MACTIVE = 3, /**< I2C configured and waiting start cond. */ + I2C_10BIT_HANDSHAKE = 4, /**< 10-bit address sending */ + I2C_MWAIT_ADDR_ACK = 5, /**< Waiting ACK on address sending. */ + I2C_MTRANSMIT = 6, /**< Master transmitting. */ + I2C_MRECEIVE = 7, /**< Master receiving. */ + I2C_MWAIT_TF = 8, /**< Master wait Transmission Finished */ + I2C_MERROR = 9, /**< Error condition. */ + + // slave part + I2C_SACTIVE = 10, + I2C_STRANSMIT = 11, + I2C_SRECEIVE = 12, +} i2cstate_t; + + +#include "i2c_lld.h" + +/** + * @brief I2C notification callback type. + * @details This callback invoked when byte transfer finish event occurs, + * No matter sending or reading. This function designed + * for sending (re)start or stop events to I2C bus from user level. + * + * If callback function is set to NULL - driver atomaticcaly + * generate stop condition after the transfer finish. + * + * @param[in] i2cp pointer to the @p I2CDriver object triggering the + * callback + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object triggering the + * callback + */ +typedef void (*i2ccallback_t)(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + + +/** + * @brief I2C error notification callback type. + * + * @param[in] i2cp pointer to the @p I2CDriver object triggering the + * callback + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object triggering the + * callback + */ +typedef void (*i2cerrorcallback_t)(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + + +/** + * @brief I2C transmission data block size. + */ +typedef uint8_t i2cblock_t; + + +/** + * @brief Structure representing an I2C slave configuration. + * @details Each slave device has its own config structure with input and + * output buffers for temporally storing data. + */ +struct I2CSlaveConfig{ + /** + * @brief Callback pointer. + * @note Transfer finished callback. Invoke when all data transferred, or + * by DMA buffer events + * If set to @p NULL then the callback is disabled. + */ + i2ccallback_t id_callback; + + /** + * @brief Callback pointer. + * @note This callback will be invoked when error condition occur. + * If set to @p NULL then the callback is disabled. + */ + i2cerrorcallback_t id_err_callback; + + /** + * @brief Receive and transmit buffers. + */ + i2cblock_t *rxbuf; /*!< Pointer to receive buffer. */ + size_t rxdepth; /*!< Depth of buffer. */ + size_t rxbytes; /*!< Number of bytes to be receive in one transmission. */ + size_t rxbufhead; /*!< Pointer to current data byte. */ + + i2cblock_t *txbuf; /*!< Pointer to transmit buffer.*/ + size_t txdepth; /*!< Depth of buffer. */ + size_t txbytes; /*!< Number of bytes to be transmit in one transmission. */ + size_t txbufhead; /*!< Pointer to current data byte. */ + + /** + * @brief Contain slave address and some flags. + * @details Bits 0..9 contain slave address in 10-bit mode. + * + * Bits 0..6 contain slave address in 7-bit mode. + * + * Bits 10..14 are not used in 10-bit mode. + * Bits 7..14 are not used in 7-bit mode. + * + * Bit 15 is used to switch between 10-bit and 7-bit modes + * (0 denotes 7-bit mode). + */ + uint16_t address; + + /** + * @brief Boolean flag for dealing with start/stop conditions. + * @note This flag destined to use in callback functions. It place here + * for convenience and flexibility reasons, but you can use your + * own variable from user level code. + */ + bool_t restart; + + +#if I2C_USE_WAIT + /** + * @brief Thread waiting for I/O completion. + */ + Thread *thread; +#endif /* I2C_USE_WAIT */ +}; + + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/** + * @brief Read mode. + */ +#define I2C_READ 1 + +/** + * @brief Write mode. + */ +#define I2C_WRITE 0 + +/** + * @brief Seven bits addresses header builder. + * + * @param[in] addr seven bits address value + * @param[in] rw read/write flag + * + * @return A 16 bit value representing the header, the most + * significant byte is always zero. + */ +#define I2C_ADDR7(addr, rw) (uint16_t)((addr) << 1 | (rw)) + + +/** + * @brief Ten bits addresses header builder. + * + * @param[in] addr ten bits address value + * @param[in] rw read/write flag + * + * @return A 16 bit value representing the header, the most + * significant byte is the first one to be transmitted. + */ +#define I2C_ADDR10(addr, rw) \ + (uint16_t)(0xF000 | \ + (((addr) & 0x0300) << 1) | \ + (((rw) << 8)) | \ + ((addr) & 0x00FF)) + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ +#ifdef __cplusplus +extern "C" { +#endif + void i2cInit(void); + void i2cObjectInit(I2CDriver *i2cp); + void i2cStart(I2CDriver *i2cp, I2CConfig *config); + void i2cStop(I2CDriver *i2cp); + void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + void i2cMasterStart(I2CDriver *i2cp); + void i2cMasterStop(I2CDriver *i2cp); + +#if I2C_USE_MUTUAL_EXCLUSION + void i2cAcquireBus(I2CDriver *i2cp); + void i2cReleaseBus(I2CDriver *i2cp); +#endif /* I2C_USE_MUTUAL_EXCLUSION */ +#ifdef __cplusplus +} +#endif + +#endif /* HAL_USE_I2C */ + +#endif /* _I2C_H_ */ + +/** @} */ diff --git a/os/hal/platforms/STM32/i2c_lld_brts.c b/os/hal/platforms/STM32/i2c_lld_brts.c new file mode 100644 index 000000000..1ac7e4309 --- /dev/null +++ b/os/hal/platforms/STM32/i2c_lld_brts.c @@ -0,0 +1,626 @@ +/** + * @file STM32/i2c_lld.c + * @brief STM32 I2C subsystem low level driver source. Slave mode not implemented. + * @addtogroup STM32_I2C + * @{ + */ + +#include "ch.h" +#include "hal.h" +#include "i2c_lld.h" + +#if HAL_USE_I2C || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver exported variables. */ +/*===========================================================================*/ + +/** @brief I2C1 driver identifier.*/ +#if STM32_I2C_USE_I2C1 || defined(__DOXYGEN__) +I2CDriver I2CD1; +#endif + +/** @brief I2C2 driver identifier.*/ +#if STM32_I2C_USE_I2C2 || defined(__DOXYGEN__) +I2CDriver I2CD2; +#endif + +/*===========================================================================*/ +/* Driver local variables. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver local functions. */ +/*===========================================================================*/ + +/** + * @brief Interrupt service routine. + * @details This function handle all ERROR interrupt conditions. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +static void i2c_serve_error_interrupt(I2CDriver *i2cp) { + //TODO: more robust error handling + chSysLockFromIsr(); + i2cp->id_slave_config->id_err_callback(i2cp, i2cp->id_slave_config); + chSysUnlockFromIsr(); +} + +/* helper function, not API + * write bytes in DR register + * return TRUE if last byte written + */ +inline bool_t i2c_lld_txbyte(I2CDriver *i2cp) { +#define _txbufhead (i2cp->id_slave_config->txbufhead) +#define _txbytes (i2cp->id_slave_config->txbytes) +#define _txbuf (i2cp->id_slave_config->txbuf) + + if (_txbufhead < _txbytes){ + /* disable interrupt to avoid jumping to ISR */ + if ( _txbytes - _txbufhead == 1) + i2cp->id_i2c->CR2 &= (~I2C_CR2_ITBUFEN); + i2cp->id_i2c->DR = _txbuf[_txbufhead]; + (_txbufhead)++; + return(FALSE); + } + _txbufhead = 0; + return(TRUE); // last byte written +#undef _txbufhead +#undef _txbytes +#undef _txbuf +} + + +/* helper function, not API + * read bytes from DR register + * return TRUE if last byte read + */ +inline bool_t i2c_lld_rxbyte(I2CDriver *i2cp) { + // temporal variables +#define _rxbuf (i2cp->id_slave_config->rxbuf) +#define _rxbufhead (i2cp->id_slave_config->rxbufhead) +#define _rxbytes (i2cp->id_slave_config->rxbytes) + + /* In order to generate the non-acknowledge pulse after the last received + * data byte, the ACK bit must be cleared just after reading the second + * last data byte (after second last RxNE event). + */ + if (_rxbufhead < (_rxbytes - 1)){ + _rxbuf[_rxbufhead] = i2cp->id_i2c->DR; + if ((_rxbytes - _rxbufhead) <= 2){ + // clear ACK bit for automatically send NACK + i2cp->id_i2c->CR1 &= (~I2C_CR1_ACK); + } + (_rxbufhead)++; + return(FALSE); + } + /* disable interrupt to avoid jumping to ISR */ + i2cp->id_i2c->CR2 &= (~I2C_CR2_ITBUFEN); + + _rxbuf[_rxbufhead] = i2cp->id_i2c->DR; // read last byte + _rxbufhead = 0; + return(TRUE); // last byte read + +#undef _rxbuf +#undef _rxbufhead +#undef _rxbytes +} + + +/** + * @brief Interrupt service routine. + * @details This function handle all regular interrupt conditions. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +static void i2c_serve_event_interrupt(I2CDriver *i2cp) { + +#if CH_DBG_ENABLE_CHECKS + // debug variables + int i = 0; + int n = 0; + int m = 0; +#endif + + /* In 10-bit addressing mode, + – To enter Transmitter mode, a master sends the header (11110xx0) and then the + slave address, (where xx denotes the two most significant bits of the address). + – To enter Receiver mode, a master sends the header (11110xx0) and then the + slave address. Then it should send a repeated Start condition followed by the + header (11110xx1), (where xx denotes the two most significant bits of the + address). + The TRA bit indicates whether the master is in Receiver or Transmitter mode.*/ + + if ((i2cp->id_state == I2C_READY) && (i2cp->id_i2c->SR1 & I2C_SR1_SB)){// start bit sent + i2cp->id_state = I2C_MACTIVE; + + if(!(i2cp->id_slave_config->address & 0x8000)){ // slave address is 7-bit + i2cp->id_i2c->DR = ((i2cp->id_slave_config->address & 0x7F) << 1) | + i2cp->rw_bit; + i2cp->id_state = I2C_MWAIT_ADDR_ACK; + return; + } + else{ // slave address is 10-bit + i2cp->id_state = I2C_10BIT_HANDSHAKE; + // send MSB with header. LSB = 0. + i2cp->id_i2c->DR = ((i2cp->id_slave_config->address >> 7) & 0x6) | 0xF0; + return; + } + } + + // "wait" interrupt with ADD10 flag + if ((i2cp->id_state == I2C_10BIT_HANDSHAKE) && (i2cp->id_i2c->SR1 & I2C_SR1_ADD10)){ + i2cp->id_i2c->DR = i2cp->id_slave_config->address & 0x00FF; // send remaining bits of address + if (!(i2cp->rw_bit)) + // in transmit mode there is nothing to do with 10-bit handshaking + i2cp->id_state = I2C_MWAIT_ADDR_ACK; + return; + } + + // "wait" interrupt with ADDR flag + if ((i2cp->id_state == I2C_10BIT_HANDSHAKE) && (i2cp->id_i2c->SR1 & I2C_SR1_ADDR)){// address ACKed + i2cp->id_i2c->CR1 |= I2C_CR1_START; + return; + } + + if ((i2cp->id_state == I2C_10BIT_HANDSHAKE) && (i2cp->id_i2c->SR1 & I2C_SR1_SB)){// restart generated + // send MSB with header. LSB = 1 + i2cp->id_i2c->DR = ((i2cp->id_slave_config->address >> 7) & 0x6) | 0xF1; + i2cp->id_state = I2C_MWAIT_ADDR_ACK; + return; + } + + // "wait" interrupt with ADDR (ADD10 in 10-bit receiver mode) flag + if ((i2cp->id_state == I2C_MWAIT_ADDR_ACK) && (i2cp->id_i2c->SR1 & (I2C_SR1_ADDR | I2C_SR1_ADD10))){// address ACKed + if(i2cp->id_i2c->SR2 & I2C_SR2_TRA){// I2C is transmitting data + i2cp->id_state = I2C_MTRANSMIT; // change state + i2c_lld_txbyte(i2cp); // send first byte + return; + } + else {// I2C is receiving data + /* In order to generate the non-acknowledge pulse after the last received + * data byte, the ACK bit must be cleared just after reading the second + * last data byte (after second last RxNE event). + */ + if (i2cp->id_slave_config->rxbytes > 1) + i2cp->id_i2c->CR1 |= I2C_CR1_ACK; // set ACK bit + i2cp->id_state = I2C_MRECEIVE; // change state + return; + } + } + + // transmitting bytes one by one + if ((i2cp->id_state == I2C_MTRANSMIT) && (i2cp->id_i2c->SR1 & I2C_SR1_TXE)){ + if (i2c_lld_txbyte(i2cp)) + i2cp->id_state = I2C_MWAIT_TF; // last byte written + return; + } + + //receiving bytes one by one + if ((i2cp->id_state == I2C_MRECEIVE) && (i2cp->id_i2c->SR1 & I2C_SR1_RXNE)){ + if (i2c_lld_rxbyte(i2cp)) + i2cp->id_state = I2C_MWAIT_TF; // last byte read + return; + } + + // "wait" BTF bit in status register + if ((i2cp->id_state == I2C_MWAIT_TF) && (i2cp->id_i2c->SR1 & I2C_SR1_BTF)){ + chSysLockFromIsr(); + i2cp->id_i2c->CR2 &= (~I2C_CR2_ITEVTEN); // disable BTF interrupt + chSysUnlockFromIsr(); + /* now driver is ready to generate (re)start/stop condition. + * Callback function is good place to do that. If not callback was + * set - driver only generate stop condition. */ + i2cp->id_state = I2C_READY; + + if (i2cp->id_slave_config->id_callback != NULL) + i2cp->id_slave_config->id_callback(i2cp, i2cp->id_slave_config); + else /* No callback function set. Generate stop */ + i2c_lld_master_stop(i2cp); + + return; + } +#if CH_DBG_ENABLE_CHECKS + else{ // debugging trap + i = i2cp->id_i2c->SR1; + n = i2cp->id_i2c->SR2; + m = i2cp->id_i2c->CR1; + while(TRUE); + } +#endif /* CH_DBG_ENABLE_CHECKS */ +} + +#if STM32_I2C_USE_I2C1 || defined(__DOXYGEN__) +/** + * @brief I2C1 event interrupt handler. + */ +CH_IRQ_HANDLER(VectorBC) { + + CH_IRQ_PROLOGUE(); + i2c_serve_event_interrupt(&I2CD1); + CH_IRQ_EPILOGUE(); +} + +/** + * @brief I2C1 error interrupt handler. + */ +CH_IRQ_HANDLER(VectorC0) { + + CH_IRQ_PROLOGUE(); + i2c_serve_error_interrupt(&I2CD1); + CH_IRQ_EPILOGUE(); +} +#endif + +#if STM32_I2C_USE_I2C2 || defined(__DOXYGEN__) +/** + * @brief I2C2 event interrupt handler. + */ +CH_IRQ_HANDLER(VectorC4) { + + CH_IRQ_PROLOGUE(); + i2c_serve_event_interrupt(&I2CD2); + CH_IRQ_EPILOGUE(); +} + +/** + * @brief I2C2 error interrupt handler. + */ +CH_IRQ_HANDLER(VectorC8) { + + CH_IRQ_PROLOGUE(); + i2c_serve_error_interrupt(&I2CD2); + CH_IRQ_EPILOGUE(); +} +#endif + +/** + * @brief Low level I2C driver initialization. + */ +void i2c_lld_init(void) { + +#if STM32_I2C_USE_I2C1 + RCC->APB1RSTR = RCC_APB1RSTR_I2C1RST; // reset I2C 1 + RCC->APB1RSTR = 0; + i2cObjectInit(&I2CD1); + I2CD1.id_i2c = I2C1; +#endif + +#if STM32_I2C_USE_I2C2 + RCC->APB1RSTR = RCC_APB1RSTR_I2C2RST; // reset I2C 2 + RCC->APB1RSTR = 0; + i2cObjectInit(&I2CD2); + I2CD2.id_i2c = I2C2; +#endif +} + +/** + * @brief Configures and activates the I2C peripheral. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_start(I2CDriver *i2cp) { + + /* If in stopped state then enables the I2C clock.*/ + if (i2cp->id_state == I2C_STOP) { +#if STM32_I2C_USE_I2C1 + if (&I2CD1 == i2cp) { + NVICEnableVector(I2C1_EV_IRQn, STM32_I2C_I2C1_IRQ_PRIORITY); + NVICEnableVector(I2C1_ER_IRQn, STM32_I2C_I2C1_IRQ_PRIORITY); + RCC->APB1ENR |= RCC_APB1ENR_I2C1EN; // I2C 1 clock enable + } +#endif +#if STM32_I2C_USE_I2C2 + if (&I2CD2 == i2cp) { + NVICEnableVector(I2C2_EV_IRQn, STM32_I2C_I2C2_IRQ_PRIORITY); + NVICEnableVector(I2C2_ER_IRQn, STM32_I2C_I2C2_IRQ_PRIORITY); + RCC->APB1ENR |= RCC_APB1ENR_I2C2EN; // I2C 2 clock enable + } +#endif + } + + /* I2C setup.*/ + i2cp->id_i2c->CR1 = I2C_CR1_SWRST; // reset i2c peripherial + i2cp->id_i2c->CR1 = 0; + + i2c_lld_set_clock(i2cp); + i2c_lld_set_opmode(i2cp); + i2cp->id_i2c->CR2 |= I2C_CR2_ITERREN | I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN;// enable interrupts + i2cp->id_i2c->CR1 |= 1; // enable interface +} + +/** + * @brief Set clock speed. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_set_clock(I2CDriver *i2cp) { + volatile uint16_t regCCR, regCR2, freq, clock_div; + volatile uint16_t pe_bit_saved; + int32_t clock_speed = i2cp->id_config->ClockSpeed; + I2C_DutyCycle_t duty = i2cp->id_config->FastModeDutyCycle; + + chDbgCheck((i2cp != NULL) && (clock_speed > 0) && (clock_speed <= 4000000), + "i2c_lld_set_clock"); + + /*---------------------------- CR2 Configuration ------------------------*/ + /* Get the I2Cx CR2 value */ + regCR2 = i2cp->id_i2c->CR2; + + /* Clear frequency FREQ[5:0] bits */ + regCR2 &= (uint16_t)~I2C_CR2_FREQ; + /* Set frequency bits depending on pclk1 value */ + freq = (uint16_t)(STM32_PCLK1 / 1000000); + chDbgCheck((freq >= 2) && (freq <= 36), + "i2c_lld_set_clock() : Peripheral clock freq. out of range"); + regCR2 |= freq; + i2cp->id_i2c->CR2 = regCR2; + + /*---------------------------- CCR Configuration ------------------------*/ + pe_bit_saved = (i2cp->id_i2c->CR1 & I2C_CR1_PE); + /* Disable the selected I2C peripheral to configure TRISE */ + i2cp->id_i2c->CR1 &= (uint16_t)~I2C_CR1_PE; + + /* Clear F/S, DUTY and CCR[11:0] bits */ + regCCR = 0; + clock_div = I2C_CCR_CCR; + /* Configure clock_div in standard mode */ + if (clock_speed <= 100000) { + chDbgAssert(duty == stdDutyCycle, + "i2c_lld_set_clock(), #1", "Invalid standard mode duty cycle"); + /* Standard mode clock_div calculate: Tlow/Thigh = 1/1 */ + clock_div = (uint16_t)(STM32_PCLK1 / (clock_speed * 2)); + /* Test if CCR value is under 0x4, and set the minimum allowed value */ + if (clock_div < 0x04) clock_div = 0x04; + /* Set clock_div value for standard mode */ + regCCR |= (clock_div & I2C_CCR_CCR); + /* Set Maximum Rise Time for standard mode */ + i2cp->id_i2c->TRISE = freq + 1; + } + /* Configure clock_div in fast mode */ + else if(clock_speed <= 400000) { + chDbgAssert((duty == fastDutyCycle_2) || (duty == fastDutyCycle_16_9), + "i2c_lld_set_clock(), #2", "Invalid fast mode duty cycle"); + if(duty == fastDutyCycle_2) { + /* Fast mode clock_div calculate: Tlow/Thigh = 2/1 */ + clock_div = (uint16_t)(STM32_PCLK1 / (clock_speed * 3)); + } + else if(duty == fastDutyCycle_16_9) { + /* Fast mode clock_div calculate: Tlow/Thigh = 16/9 */ + clock_div = (uint16_t)(STM32_PCLK1 / (clock_speed * 25)); + /* Set DUTY bit */ + regCCR |= I2C_CCR_DUTY; + } + /* Test if CCR value is under 0x1, and set the minimum allowed value */ + if(clock_div < 0x01) clock_div = 0x01; + /* Set clock_div value and F/S bit for fast mode*/ + regCCR |= (I2C_CCR_FS | (clock_div & I2C_CCR_CCR)); + /* Set Maximum Rise Time for fast mode */ + i2cp->id_i2c->TRISE = (freq * 300 / 1000) + 1; + } + chDbgAssert((clock_div <= I2C_CCR_CCR), + "i2c_lld_set_clock(), #3", "Too low clock clock speed selected"); + + /* Write to I2Cx CCR */ + i2cp->id_i2c->CCR = regCCR; + + /* restore the I2C peripheral enabled state */ + i2cp->id_i2c->CR1 |= pe_bit_saved; +} + +/** + * @brief Set operation mode of I2C hardware. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_set_opmode(I2CDriver *i2cp) { + I2C_opMode_t opmode = i2cp->id_config->opMode; + uint16_t regCR1; + + /*---------------------------- CR1 Configuration ------------------------*/ + /* Get the I2Cx CR1 value */ + regCR1 = i2cp->id_i2c->CR1; + switch(opmode){ + case opmodeI2C: + regCR1 &= (uint16_t)~(I2C_CR1_SMBUS|I2C_CR1_SMBTYPE); + break; + case opmodeSMBusDevice: + regCR1 |= I2C_CR1_SMBUS; + regCR1 &= (uint16_t)~(I2C_CR1_SMBTYPE); + break; + case opmodeSMBusHost: + regCR1 |= (I2C_CR1_SMBUS|I2C_CR1_SMBTYPE); + break; + } + /* Write to I2Cx CR1 */ + i2cp->id_i2c->CR1 = regCR1; +} + +/** + * @brief Set own address. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_set_own_address(I2CDriver *i2cp) { + //TODO: dual address mode + + /*---------------------------- OAR1 Configuration -----------------------*/ + i2cp->id_i2c->OAR1 |= 1 << 14; + + if (&(i2cp->id_config->OwnAddress10) == NULL){// only 7-bit address + i2cp->id_i2c->OAR1 &= (~I2C_OAR1_ADDMODE); + i2cp->id_i2c->OAR1 |= i2cp->id_config->OwnAddress7 << 1; + } + else { + chDbgAssert((i2cp->id_config->OwnAddress10 < 1024), + "i2c_lld_set_own_address(), #1", "10-bit address longer then 10 bit") + i2cp->id_i2c->OAR1 |= I2C_OAR1_ADDMODE; + i2cp->id_i2c->OAR1 |= i2cp->id_config->OwnAddress10; + } +} + + +/** + * @brief Deactivates the I2C peripheral. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_stop(I2CDriver *i2cp) { + + /* If in ready state then disables the I2C clock.*/ + if (i2cp->id_state == I2C_READY) { +#if STM32_I2C_USE_I2C1 + if (&I2CD1 == i2cp) { + NVICDisableVector(I2C1_EV_IRQn); + NVICDisableVector(I2C1_ER_IRQn); + RCC->APB1ENR &= ~RCC_APB1ENR_I2C1EN; + } +#endif +#if STM32_I2C_USE_I2C2 + if (&I2CD2 == i2cp) { + NVICDisableVector(I2C2_EV_IRQn); + NVICDisableVector(I2C2_ER_IRQn); + RCC->APB1ENR &= ~RCC_APB1ENR_I2C2EN; + } +#endif + } + i2cp->id_state = I2C_STOP; +} + +/** + * @brief Generate start condition. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_master_start(I2CDriver *i2cp){ + i2cp->id_i2c->CR1 |= I2C_CR1_START; + while (i2cp->id_i2c->CR1 & I2C_CR1_START); + + /* enable interrupts from I2C hardware. They will disable in driver state + machine after the transfer finish.*/ + i2cp->id_i2c->CR2 |= I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN; +} + +/** + * @brief Generate stop condition. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2c_lld_master_stop(I2CDriver *i2cp){ + i2cp->id_i2c->CR1 |= I2C_CR1_STOP; + while (i2cp->id_i2c->CR1 & I2C_CR1_STOP); +} + +/** + * @brief Begin data transmitting. + * + * @param[in] i2cp pointer to the @p I2CDriver object + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object + */ +void i2c_lld_master_transmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg){ + + i2cp->id_slave_config = i2cscfg; + i2cp->rw_bit = I2C_WRITE; + + // generate start condition. Later transmission goes in background + i2c_lld_master_start(i2cp); +} + +/** + * @brief Begin data receiving. + * + * @param[in] i2cp pointer to the @p I2CDriver object + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object + */ +void i2c_lld_master_receive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg){ + + i2cp->id_slave_config = i2cscfg; + i2cp->rw_bit = I2C_READ; + + // generate (re)start condition. Later connection goes asynchronously + i2c_lld_master_start(i2cp); +} + + + +/** + * @brief Transmits data via I2C bus. + * + * @note This function does not use interrupts + * + * @param[in] i2cp pointer to the @p I2CDriver object + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object + * @param[in] restart bool. If TRUE then generate restart condition instead of stop + */ +void i2c_lld_master_transmit_NI(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg, bool_t restart) { + + int i = 0; + + i2cp->id_slave_config = i2cscfg; + i2cp->rw_bit = I2C_WRITE; + + + i2cp->id_i2c->CR1 |= I2C_CR1_START; // generate start condition + while (!(i2cp->id_i2c->SR1 & I2C_SR1_SB)); // wait Address sent + + i2cp->id_i2c->DR = (i2cp->id_slave_config->address << 1) | I2C_WRITE; // write slave addres in DR + while (!(i2cp->id_i2c->SR1 & I2C_SR1_ADDR)); // wait Address sent + i = i2cp->id_i2c->SR2; + i = i2cp->id_i2c->SR1; //i2cp->id_i2c->SR1 &= (~I2C_SR1_ADDR); // clear ADDR bit + + // now write data byte by byte in DR register + uint32_t n = 0; + for (n = 0; n < i2cp->id_slave_config->txbytes; n++){ + i2cp->id_i2c->DR = i2cscfg->txbuf[n]; + while (!(i2cp->id_i2c->SR1 & I2C_SR1_TXE)); + } + + while (!(i2cp->id_i2c->SR1 & I2C_SR1_BTF)); + + if (restart){ + i2cp->id_i2c->CR1 |= I2C_CR1_START; // generate restart condition + while (!(i2cp->id_i2c->SR1 & I2C_SR1_SB)); // wait start bit + } + else i2cp->id_i2c->CR1 |= I2C_CR1_STOP; // generate stop condition +} + + +/** + * @brief Receives data from the I2C bus. + * @note This function does not use interrupts + * + * @param[in] i2cp pointer to the @p I2CDriver object + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object + */ +void i2c_lld_master_receive_NI(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { + + i2cp->id_slave_config = i2cscfg; + + uint16_t i = 0; + + // send slave addres with read-bit + i2cp->id_i2c->DR = (i2cp->id_slave_config->address << 1) | I2C_READ; + while (!(i2cp->id_i2c->SR1 & I2C_SR1_ADDR)); // wait Address sent + + i = i2cp->id_i2c->SR2; + i = i2cp->id_i2c->SR1; //i2cp->id_i2c->SR1 &= (~I2C_SR1_ADDR); // clear ADDR bit + + // set ACK bit + i2cp->id_i2c->CR1 |= I2C_CR1_ACK; + + // collect data from slave + for (i = 0; i < i2cp->id_slave_config->rxbytes; i++){ + if ((i2cp->id_slave_config->rxbytes - i) == 1){ + // clear ACK bit for automatically send NACK + i2cp->id_i2c->CR1 &= (~I2C_CR1_ACK);} + while (!(i2cp->id_i2c->SR1 & I2C_SR1_RXNE)); + + i2cp->id_slave_config->rxbuf[i] = i2cp->id_i2c->DR; + } + // generate STOP + i2cp->id_i2c->CR1 |= I2C_CR1_STOP; +} + + + +#endif // HAL_USE_I2C diff --git a/os/hal/platforms/STM32/i2c_lld_btrts.h b/os/hal/platforms/STM32/i2c_lld_btrts.h new file mode 100644 index 000000000..76f7068e2 --- /dev/null +++ b/os/hal/platforms/STM32/i2c_lld_btrts.h @@ -0,0 +1,201 @@ +/** + * @file STM32/i2c_lld.h + * @brief STM32 I2C subsystem low level driver header. + * @addtogroup STM32_I2C + * @{ + */ + +#ifndef _I2C_LLD_H_ +#define _I2C_LLD_H_ + +#if HAL_USE_I2C || defined(__DOXYGEN__) + +/*===========================================================================*/ +/* Driver constants. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* Driver pre-compile time settings. */ +/*===========================================================================*/ + +/** + * @brief I2C1 driver enable switch. + * @details If set to @p TRUE the support for I2C1 is included. + * @note The default is @p TRUE. + */ +#if !defined(STM32_I2C_USE_I2C1) || defined(__DOXYGEN__) +#define STM32_I2C_USE_I2C1 TRUE +#endif + +/** + * @brief I2C2 driver enable switch. + * @details If set to @p TRUE the support for I2C2 is included. + * @note The default is @p TRUE. + */ +#if !defined(STM32_I2C_USE_I2C2) || defined(__DOXYGEN__) +#define STM32_I2C_USE_I2C2 TRUE +#endif + +/** + * @brief I2C1 interrupt priority level setting. + * @note @p BASEPRI_KERNEL >= @p STM32_I2C_I2C1_IRQ_PRIORITY > @p PRIORITY_PENDSV. + */ +#if !defined(STM32_I2C_I2C1_IRQ_PRIORITY) || defined(__DOXYGEN__) +#define STM32_I2C_I2C1_IRQ_PRIORITY 0xA0 +#endif + +/** + * @brief I2C2 interrupt priority level setting. + * @note @p BASEPRI_KERNEL >= @p STM32_I2C_I2C2_IRQ_PRIORITY > @p PRIORITY_PENDSV. + */ +#if !defined(STM32_I2C_I2C2_IRQ_PRIORITY) || defined(__DOXYGEN__) +#define STM32_I2C_I2C2_IRQ_PRIORITY 0xA0 +#endif + +/*===========================================================================*/ +/* Derived constants and error checks. */ +/*===========================================================================*/ +#define I2CD_NO_ERROR 0 +/** @brief Bus Error.*/ +#define I2CD_BUS_ERROR 0x01 +/** @brief Arbitration Lost (master mode).*/ +#define I2CD_ARBITRATION_LOST 0x02 +/** @brief Acknowledge Failure.*/ +#define I2CD_ACK_FAILURE 0x04 +/** @brief Overrun/Underrun.*/ +#define I2CD_OVERRUN 0x08 +/** @brief PEC Error in reception.*/ +#define I2CD_PEC_ERROR 0x10 +/** @brief Timeout or Tlow Error.*/ +#define I2CD_TIMEOUT 0x20 +/** @brief SMBus Alert.*/ +#define I2CD_SMB_ALERT 0x40 +/*===========================================================================*/ +/* Driver data structures and types. */ +/*===========================================================================*/ + +typedef enum { + opmodeI2C, + opmodeSMBusDevice, + opmodeSMBusHost, +} I2C_opMode_t; + +typedef enum { + stdDutyCycle, + fastDutyCycle_2, + fastDutyCycle_16_9, +} I2C_DutyCycle_t; + +/** + * @brief Driver configuration structure. + */ +typedef struct { + I2C_opMode_t opMode; /*!< Specifies the I2C mode.*/ + uint32_t ClockSpeed; /*!< Specifies the clock frequency. Must be set to a value lower than 400kHz */ + I2C_DutyCycle_t FastModeDutyCycle;/*!< Specifies the I2C fast mode duty cycle */ + uint8_t OwnAddress7; /*!< Specifies the first device 7-bit own address. */ + uint16_t OwnAddress10; /*!< Specifies the second part of device own address in 10-bit mode. Set to NULL if not used. */ +} I2CConfig; + + +/** + * @brief Type of a structure representing an I2C driver. + */ +typedef struct I2CDriver I2CDriver; + +/** + * @brief Type of a structure representing an I2C slave config. + */ +typedef struct I2CSlaveConfig I2CSlaveConfig; + +/** + * @brief Structure representing an I2C driver. + */ +struct I2CDriver{ + /** + * @brief Driver state. + */ + i2cstate_t id_state; +#if I2C_USE_WAIT + /** + * @brief Thread waiting for I/O completion. + */ + Thread *thread; +#endif /* I2C_USE_WAIT */ +#if I2C_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__) +#if CH_USE_MUTEXES || defined(__DOXYGEN__) + /** + * @brief Mutex protecting the bus. + */ + Mutex id_mutex; +#elif CH_USE_SEMAPHORES + Semaphore id_semaphore; +#endif +#endif /* I2C_USE_MUTUAL_EXCLUSION */ + /** + * @brief Current configuration data. + */ + I2CConfig *id_config; + /** + * @brief Current slave configuration data. + */ + I2CSlaveConfig *id_slave_config; + /** + * @brief RW-bit sent to slave. + */ + uint8_t rw_bit; + + /*********** End of the mandatory fields. **********************************/ + + /** + * @brief Pointer to the I2Cx registers block. + */ + I2C_TypeDef *id_i2c; +} ; + + +/*===========================================================================*/ +/* Driver macros. */ +/*===========================================================================*/ + +/*===========================================================================*/ +/* External declarations. */ +/*===========================================================================*/ + +/** @cond never*/ +#if STM32_I2C_USE_I2C1 +extern I2CDriver I2CD1; +#endif + +#if STM32_I2C_USE_I2C2 +extern I2CDriver I2CD2; +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +void i2c_lld_init(void); +void i2c_lld_start(I2CDriver *i2cp); +void i2c_lld_stop(I2CDriver *i2cp); +void i2c_lld_set_clock(I2CDriver *i2cp); +void i2c_lld_set_opmode(I2CDriver *i2cp); +void i2c_lld_set_own_address(I2CDriver *i2cp); + +void i2c_lld_master_start(I2CDriver *i2cp); +void i2c_lld_master_stop(I2CDriver *i2cp); + +void i2c_lld_master_transmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); +void i2c_lld_master_receive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + +void i2c_lld_master_transmit_NI(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg, bool_t restart); +void i2c_lld_master_receive_NI(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg); + +#ifdef __cplusplus +} +#endif +/** @endcond*/ + +#endif // CH_HAL_USE_I2C + +#endif // _I2C_LLD_H_ diff --git a/os/hal/src/i2c_brts.c b/os/hal/src/i2c_brts.c index 5a0471e0f..ad9a5d0ac 100644 --- a/os/hal/src/i2c_brts.c +++ b/os/hal/src/i2c_brts.c @@ -69,6 +69,19 @@ void i2cObjectInit(I2CDriver *i2cp) { i2cp->id_state = I2C_STOP; i2cp->id_config = NULL; i2cp->id_slave_config = NULL; + +#if I2C_USE_WAIT + i2cp->id_thread = NULL; +#endif /* I2C_USE_WAIT */ + +#if I2C_USE_MUTUAL_EXCLUSION +#if CH_USE_MUTEXES + chMtxInit(&i2cp->id_mutex); +#else + chSemInit(&i2cp->id_semaphore, 1); +#endif /* CH_USE_MUTEXES */ +#endif /* I2C_USE_MUTUAL_EXCLUSION */ + #if defined(I2C_DRIVER_EXT_INIT_HOOK) I2C_DRIVER_EXT_INIT_HOOK(i2cp); #endif @@ -116,14 +129,38 @@ void i2cStop(I2CDriver *i2cp) { chSysUnlock(); } +/** + * @brief Generate (re)start on the bus. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2cMasterStart(I2CDriver *i2cp){ + + chDbgCheck((i2cp != NULL), "i2cMasterTransmit"); + + chSysLock(); + i2c_lld_master_start(i2cp); + chSysUnlock(); +} + +/** + * @brief Generate stop on the bus. + * + * @param[in] i2cp pointer to the @p I2CDriver object + */ +void i2cMasterStop(I2CDriver *i2cp){ + + chDbgCheck((i2cp != NULL), "i2cMasterTransmit"); + chSysLock(); + i2c_lld_master_stop(i2cp); + chSysUnlock(); +} + /** * @brief Sends data ever the I2C bus. * * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] slave_addr1 7-bit address of the slave - * @param[in] slave_addr1 used in 10-bit address mode - * @param[in] n number of words to send - * @param[in] txbuf the pointer to the transmit buffer + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object * */ void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { @@ -134,19 +171,17 @@ void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { "i2cMasterTransmit(), #1", "not active"); - i2c_lld_master_transmitI(i2cp, i2cscfg); + chSysLock(); + i2c_lld_master_transmit(i2cp, i2cscfg); + chSysUnlock(); } /** * @brief Receives data from the I2C bus. * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] slave_addr1 7-bit address of the slave - * @param[in] slave_addr1 used in 10-bit address mode - * @param[in] n number of words to receive - * @param[out] rxbuf the pointer to the receive buffer - * + * @param[in] i2cp pointer to the @p I2CDriver object + * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object */ void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { @@ -156,14 +191,13 @@ void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { "i2cMasterReceive(), #1", "not active"); - i2c_lld_master_receiveI(i2cp, i2cscfg); + chSysLock(); + i2c_lld_master_receive(i2cp, i2cscfg); + chSysUnlock(); } - - - #if I2C_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__) /** * @brief Gains exclusive access to the I2C bus.