diff --git a/os/hal/include/i2c_albi.h b/os/hal/include/i2c_albi.h deleted file mode 100644 index 30ec38548..000000000 --- a/os/hal/include/i2c_albi.h +++ /dev/null @@ -1,185 +0,0 @@ -/* - 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_ - -#include "ch.h" -#include "hal.h" - -#if HAL_USE_I2C || defined(__DOXYGEN__) - -/*===========================================================================*/ -/* Driver constants. */ -/*===========================================================================*/ -#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 pre-compile time settings. */ -/*===========================================================================*/ -/** - * @brief Enables synchronous APIs. - * @note Disabling this option saves both code and data space. - */ -#if !defined(I2C_USE_WAIT) || defined(__DOXYGEN__) -#define I2C_USE_WAIT TRUE -#endif - -/** - * @brief Enables the mutual exclusion APIs on the I2C bus. - */ -#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) -#define I2C_USE_MUTUAL_EXCLUSION FALSE -#endif - -/*===========================================================================*/ -/* Derived constants and error checks. */ -/*===========================================================================*/ - -#if I2C_USE_MUTUAL_EXCLUSION && !CH_USE_MUTEXES && !CH_USE_SEMAPHORES -#error "I2C_USE_MUTUAL_EXCLUSION requires CH_USE_MUTEXES and/or CH_USE_SEMAPHORES" -#endif - -/** - * @brief Driver state machine possible states. - */ -typedef enum { - I2C_UNINIT = 0, /**< @brief Not initialized. */ - I2C_STOP = 1, /**< @brief Stopped. */ - I2C_READY = 2, /**< @brief Ready. */ - I2C_ACTIVE = 3, /**< @brief In communication. */ - I2C_COMPLETE = 4 /**< @brief Asynchronous operation complete. */ -} i2cstate_t; - -#include "i2c_lld.h" - -#if I2C_USE_WAIT || defined(__DOXYGEN__) -/** - * @brief Waits for operation completion. - * @details This function waits for the driver to complete the current - * operation. - * @pre An operation must be running while the function is invoked. - * @note No more than one thread can wait on a I2C driver using - * this function. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @notapi - */ -#define _i2c_wait_s(i2cp) { \ - chDbgAssert((i2cp)->thread == NULL, \ - "_i2c_wait(), #1", "already waiting"); \ - (i2cp)->thread = chThdSelf(); \ - chSchGoSleepS(THD_STATE_SUSPENDED); \ -} - -/** - * @brief Wakes up the waiting thread. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @notapi - */ -#define _i2c_wakeup_isr(i2cp) { \ - if ((i2cp)->thread != NULL) { \ - Thread *tp = (i2cp)->thread; \ - (i2cp)->thread = NULL; \ - chSysLockFromIsr(); \ - chSchReadyI(tp); \ - chSysUnlockFromIsr(); \ - } \ -} -#else /* !I2C_USE_WAIT */ -#define _i2c_wait_s(i2cp) -#define _i2c_wakeup_isr(i2cp) -#endif /* !I2C_USE_WAIT */ - -/** - * @brief Common ISR code. - * @details This code handles the portable part of the ISR code: - * - Callback invocation. - * - Waiting thread wakeup, if any. - * - Driver state transitions. - * . - * @note This macro is meant to be used in the low level drivers - * implementation only. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @notapi - */ -#define _i2c_isr_code(i2cp) { \ - (i2cp)->state = I2C_COMPLETE; \ - if((i2cp)->endcb) { \ - (i2cp)->endcb(i2cp); \ - } \ - _i2c_wakeup_isr(i2cp); \ -} - -/*===========================================================================*/ -/* External declarations. */ -/*===========================================================================*/ - -#ifdef __cplusplus -extern "C" { -#endif - void i2cInit(void); - void i2cObjectInit(I2CDriver *i2cp); - void i2cStart(I2CDriver *i2cp, const I2CConfig *config); - void i2cStop(I2CDriver *i2cp); - void i2cMasterTransmit(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *txbuf); - void i2cMasterReceive(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *rxbuf); - void i2cAddFlagsI(I2CDriver *i2cp, i2cflags_t mask); - i2cflags_t i2cGetAndClearFlags(I2CDriver *i2cp); - uint16_t i2cSMBusAlertResponse(I2CDriver *i2cp); - -#if I2C_USE_MUTUAL_EXCLUSION - void i2cAcquireBus(I2CDriver *i2cp); - void i2cReleaseBus(I2CDriver *i2cp); -#endif /* I2C_USE_MUTUAL_EXCLUSION */ -#ifdef __cplusplus -} -#endif - - -#endif /* CH_HAL_USE_I2C */ - -#endif /* I2C_H_ */ diff --git a/os/hal/include/i2c_brts.h b/os/hal/include/i2c_brts.h deleted file mode 100644 index a01606a18..000000000 --- a/os/hal/include/i2c_brts.h +++ /dev/null @@ -1,248 +0,0 @@ -/* - 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_albi.c b/os/hal/platforms/STM32/i2c_lld_albi.c deleted file mode 100644 index cd6a851db..000000000 --- a/os/hal/platforms/STM32/i2c_lld_albi.c +++ /dev/null @@ -1,574 +0,0 @@ -/* - 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 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" - -#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 - - -static uint32_t i2c_get_event(I2CDriver *i2cp){ - uint32_t regSR1 = i2cp->i2c_register->SR1; - uint32_t regSR2 = i2cp->i2c_register->SR2; - /* return the last event value from I2C status registers */ - return (I2C_EV_MASK & (regSR1 | (regSR2 << 16))); -} - -static void i2c_serve_event_interrupt(I2CDriver *i2cp) { - static __IO uint8_t *txBuffp, *rxBuffp, *datap; - - I2C_TypeDef *dp = i2cp->i2c_register; - - switch(i2c_get_event(i2cp)) { - case I2C_EV5_MASTER_MODE_SELECT: - i2cp->flags &= ~I2C_FLG_HEADER_SENT; - dp->DR = i2cp->slave_addr1; - break; - case I2C_EV9_MASTER_ADDR_10BIT: - if(i2cp->flags & I2C_FLG_MASTER_RECEIVER) { - i2cp->slave_addr1 |= 0x01; - i2cp->flags |= I2C_FLG_HEADER_SENT; - } - dp->DR = i2cp->slave_addr2; - break; - //------------------------------------------------------------------------ - // Master Transmitter ---------------------------------------------------- - //------------------------------------------------------------------------ - case I2C_EV6_MASTER_TRA_MODE_SELECTED: - if(i2cp->flags & I2C_FLG_HEADER_SENT){ - dp->CR1 |= I2C_CR1_START; // re-send the start in 10-Bit address mode - break; - } - //Initialize the transmit buffer pointer - txBuffp = (uint8_t*)i2cp->txbuf; - datap = txBuffp; - txBuffp++; - i2cp->remaining_bytes--; - /* If no further data to be sent, disable the I2C ITBUF in order to not have a TxE interrupt */ - if(i2cp->remaining_bytes == 0) { - dp->CR2 &= (uint16_t)~I2C_CR2_ITBUFEN; - } - //EV8_1 write the first data - dp->DR = *datap; - break; - case I2C_EV8_MASTER_BYTE_TRANSMITTING: - if(i2cp->remaining_bytes > 0) { - datap = txBuffp; - txBuffp++; - i2cp->remaining_bytes--; - if(i2cp->remaining_bytes == 0) { - /* If no further data to be sent, disable the ITBUF in order to not have a TxE interrupt */ - dp->CR2 &= (uint16_t)~I2C_CR2_ITBUFEN; - } - dp->DR = *datap; - } - break; - case I2C_EV8_2_MASTER_BYTE_TRANSMITTED: - dp->CR1 |= I2C_CR1_STOP; // stop generation - /* Disable ITEVT In order to not have again a BTF IT */ - dp->CR2 &= (uint16_t)~I2C_CR2_ITEVTEN; - /* Portable I2C ISR code defined in the high level driver, note, it is a macro.*/ - _i2c_isr_code(i2cp); - break; - //------------------------------------------------------------------------ - // Master Receiver ------------------------------------------------------- - //------------------------------------------------------------------------ - case I2C_EV6_MASTER_REC_MODE_SELECTED: - chSysLockFromIsr(); - switch(i2cp->flags & EV6_SUBEV_MASK) { - case I2C_EV6_3_MASTER_REC_1BTR_MODE_SELECTED: // only an single byte to receive - /* Clear ACK */ - dp->CR1 &= (uint16_t)~I2C_CR1_ACK; - /* Program the STOP */ - dp->CR1 |= I2C_CR1_STOP; - break; - case I2C_EV6_1_MASTER_REC_2BTR_MODE_SELECTED: // only two bytes to receive - /* Clear ACK */ - dp->CR1 &= (uint16_t)~I2C_CR1_ACK; - /* Disable the ITBUF in order to have only the BTF interrupt */ - dp->CR2 &= (uint16_t)~I2C_CR2_ITBUFEN; - break; - } - chSysUnlockFromIsr(); - /* Initialize receive buffer pointer */ - rxBuffp = i2cp->rxbuf; - break; - case I2C_EV7_MASTER_REC_BYTE_RECEIVED: - if(i2cp->remaining_bytes != 3) { - /* Read the data register */ - *rxBuffp = dp->DR; - rxBuffp++; - i2cp->remaining_bytes--; - switch(i2cp->remaining_bytes){ - case 3: - /* Disable the ITBUF in order to have only the BTF interrupt */ - dp->CR2 &= (uint16_t)~I2C_CR2_ITBUFEN; - i2cp->flags |= I2C_FLG_3BTR; - break; - case 0: - /* Portable I2C ISR code defined in the high level driver, note, it is a macro.*/ - _i2c_isr_code(i2cp); - break; - } - } - // when remaining 3 bytes do nothing, wait until RXNE and BTF are set (until 2 bytes are received) - break; - case I2C_EV7_MASTER_REC_BYTE_QUEUED: - switch(i2cp->flags & EV7_SUBEV_MASK) { - case I2C_EV7_2_MASTER_REC_3BYTES_TO_PROCESS: - // DataN-2 and DataN-1 are received - chSysLockFromIsr(); - dp->CR2 |= I2C_CR2_ITBUFEN; - /* Clear ACK */ - dp->CR1 &= (uint16_t)~I2C_CR1_ACK; - /* Read the DataN-2*/ - *rxBuffp = dp->DR; //This clear the RXE & BFT flags and launch the DataN reception in the shift register (ending the SCL stretch) - rxBuffp++; - /* Program the STOP */ - dp->CR1 |= I2C_CR1_STOP; - /* Read the DataN-1 */ - *rxBuffp = dp->DR; - chSysUnlockFromIsr(); - rxBuffp++; - /* Decrement the number of readed bytes */ - i2cp->remaining_bytes -= 2; - i2cp->flags = 0; - // ready for read DataN on the next EV7 - break; - case I2C_EV7_3_MASTER_REC_2BYTES_TO_PROCESS: // only for case of two bytes to be received - // DataN-1 and DataN are received - chSysLockFromIsr(); - /* Program the STOP */ - dp->CR1 |= I2C_CR1_STOP; - /* Read the DataN-1*/ - *rxBuffp = dp->DR; - chSysUnlockFromIsr(); - rxBuffp++; - /* Read the DataN*/ - *rxBuffp = dp->DR; - i2cp->remaining_bytes = 0; - i2cp->flags = 0; - /* Portable I2C ISR code defined in the high level driver, note, it is a macro.*/ - _i2c_isr_code(i2cp); - break; - } - break; - } -} - -static void i2c_serve_error_interrupt(I2CDriver *i2cp) { - i2cflags_t flags; - I2C_TypeDef *reg; - - reg = i2cp->i2c_register; - flags = I2CD_NO_ERROR; - - if(reg->SR1 & I2C_SR1_BERR) { // Bus error - reg->SR1 &= ~I2C_SR1_BERR; - flags |= I2CD_BUS_ERROR; - } - if(reg->SR1 & I2C_SR1_ARLO) { // Arbitration lost - reg->SR1 &= ~I2C_SR1_ARLO; - flags |= I2CD_ARBITRATION_LOST; - } - if(reg->SR1 & I2C_SR1_AF) { // Acknowledge fail - reg->SR1 &= ~I2C_SR1_AF; - reg->CR1 |= I2C_CR1_STOP; // setting stop bit - flags |= I2CD_ACK_FAILURE; - } - if(reg->SR1 & I2C_SR1_OVR) { // Overrun - reg->SR1 &= ~I2C_SR1_OVR; - flags |= I2CD_OVERRUN; - } - if(reg->SR1 & I2C_SR1_PECERR) { // PEC error - reg->SR1 &= ~I2C_SR1_PECERR; - flags |= I2CD_PEC_ERROR; - } - if(reg->SR1 & I2C_SR1_TIMEOUT) { // SMBus Timeout - reg->SR1 &= ~I2C_SR1_TIMEOUT; - flags |= I2CD_TIMEOUT; - } - if(reg->SR1 & I2C_SR1_SMBALERT) { // SMBus alert - reg->SR1 &= ~I2C_SR1_SMBALERT; - flags |= I2CD_SMB_ALERT; - } - - if(flags != I2CD_NO_ERROR) { - // send communication end signal - _i2c_isr_code(i2cp); - chSysLockFromIsr(); - i2cAddFlagsI(i2cp, flags); - chSysUnlockFromIsr(); - } -} - -#if STM32_I2C_USE_I2C1 || defined(__DOXYGEN__) -/** - * @brief I2C1 event interrupt handler. - */ -CH_IRQ_HANDLER(I2C1_EV_IRQHandler) { - - CH_IRQ_PROLOGUE(); - i2c_serve_event_interrupt(&I2CD1); - CH_IRQ_EPILOGUE(); -} - -/** - * @brief I2C1 error interrupt handler. - */ -CH_IRQ_HANDLER(I2C1_ER_IRQHandler) { - - 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(I2C2_EV_IRQHandler) { - - CH_IRQ_PROLOGUE(); - i2c_serve_event_interrupt(&I2CD2); - CH_IRQ_EPILOGUE(); -} - -/** - * @brief I2C2 error interrupt handler. - */ -CH_IRQ_HANDLER(I2C2_ER_IRQHandler) { - - CH_IRQ_PROLOGUE(); - i2c_serve_error_interrupt(&I2CD2); - CH_IRQ_EPILOGUE(); -} -#endif - -void i2c_lld_reset(I2CDriver *i2cp){ - chDbgCheck((i2cp->state == I2C_STOP)||(i2cp->state == I2C_READY), - "i2c_lld_reset: invalid state"); - - RCC->APB1RSTR = RCC_APB1RSTR_I2C1RST; // reset I2C 1 - RCC->APB1RSTR = 0; -} - -void i2c_lld_set_clock(I2CDriver *i2cp, int32_t clock_speed, I2C_DutyCycle_t duty) { - volatile uint16_t regCCR, regCR2, freq, clock_div; - volatile uint16_t pe_bit_saved; - - chDbgCheck((i2cp != NULL) && (clock_speed > 0) && (clock_speed <= 4000000), - "i2c_lld_set_clock"); - - /*---------------------------- CR2 Configuration ------------------------*/ - /* Get the I2Cx CR2 value */ - regCR2 = i2cp->i2c_register->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->i2c_register->CR2 = regCR2; - - /*---------------------------- CCR Configuration ------------------------*/ - pe_bit_saved = (i2cp->i2c_register->CR1 & I2C_CR1_PE); - /* Disable the selected I2C peripheral to configure TRISE */ - i2cp->i2c_register->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(), #3", "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->i2c_register->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(), #3", "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->i2c_register->TRISE = (freq * 300 / 1000) + 1; - } - chDbgAssert((clock_div <= I2C_CCR_CCR), - "i2c_lld_set_clock(), #2", "Too low clock clock speed selected"); - - /* Write to I2Cx CCR */ - i2cp->i2c_register->CCR = regCCR; - - /* restore the I2C peripheral enabled state */ - i2cp->i2c_register->CR1 |= pe_bit_saved; -} - -void i2c_lld_set_opmode(I2CDriver *i2cp, I2C_opMode_t opmode) { - uint16_t regCR1; - - /*---------------------------- CR1 Configuration ------------------------*/ - /* Get the I2Cx CR1 value */ - regCR1 = i2cp->i2c_register->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->i2c_register->CR1 = regCR1; -} - -void i2c_lld_set_own_address(I2CDriver *i2cp, int16_t address, int8_t nbit_addr) { - /*---------------------------- OAR1 Configuration -----------------------*/ - /* Set the Own Address1 and bit number address acknowledged */ - i2cp->i2c_register->OAR1 = address & I2C_OAR1_ADD0_9; - switch(nbit_addr) { - case 10: - i2cp->i2c_register->OAR1 |= I2C_OAR1_ADDMODE; // set ADDMODE bit and bit 14. - case 7: - i2cp->i2c_register->OAR1 |= I2C_OAR1_BIT14; // set only bit 14. - } -} - -/** - * @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.i2c_register = I2C1; -#endif -#if STM32_I2C_USE_I2C2 - RCC->APB1RSTR = RCC_APB1RSTR_I2C2RST; // reset I2C 2 - RCC->APB1RSTR = 0; - i2cObjectInit(&I2CD2); - I2CD2.i2c_register = I2C2; -#endif -} - -/** - * @brief Configures and activates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - */ -void i2c_lld_start(I2CDriver *i2cp) { - chDbgCheck((i2cp->state == I2C_STOP)||(i2cp->state == I2C_READY), - "i2c_lld_start: invalid state"); - - /* If in stopped state then enables the I2C clock.*/ - if (i2cp->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 - i2cp->i2c_register->CR1 |= I2C_CR1_PE; // enable I2C peripheral - } -} - -/** - * @brief Deactivates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - */ -void i2c_lld_stop(I2CDriver *i2cp) { - - chDbgCheck((i2cp->state == I2C_READY), - "i2c_lld_stop: invalid state"); - - /* I2C disable.*/ - i2cp->i2c_register->CR1 = 0; - - /* If in ready state then disables the I2C clock.*/ - if (i2cp->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 - } -} - -/** - * @brief Transmits data ever the I2C bus as master. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] n number of words to send - * @param[in] slave_addr1 the 7-bit address of the slave (should be aligned to left) - * @param[in] slave_addr2 used in 10 bit address mode - * @param[in] txbuf the pointer to the transmit buffer - * - */ -void i2c_lld_master_transmit(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *txbuf) { - - // enable ERR, EVT & BUF ITs - i2cp->i2c_register->CR2 |= (I2C_CR2_ITERREN|I2C_CR2_ITEVTEN|I2C_CR2_ITBUFEN); - i2cp->i2c_register->CR1 &= ~I2C_CR1_POS; - - switch(i2cp->nbit_address){ - case 7: - i2cp->slave_addr1 = ((slave_addr <<1) & 0x00FE); // LSB = 0 -> write - break; - case 10: - i2cp->slave_addr1 = ((slave_addr >>7) & 0x0006); // add the two msb of 10-bit address to the header - i2cp->slave_addr1 |= 0xF0; // add the header bits with LSB = 0 -> write - i2cp->slave_addr2 = slave_addr & 0x00FF; // the remaining 8 bit of 10-bit address - break; - } - - i2cp->txbuf = txbuf; - i2cp->remaining_bytes = n; - i2cp->flags = 0; - i2cp->errors = 0; - - i2cp->i2c_register->CR1 |= I2C_CR1_START; // send start bit - -#if !I2C_USE_WAIT - /* Wait until the START condition is generated on the bus: the START bit is cleared by hardware */ - uint32_t tmo = 0xfffff; - while((i2cp->i2c_register->CR1 & I2C_CR1_START) && tmo--) - ; -#endif /* I2C_USE_WAIT */ -} - -/** - * @brief Receives data from the I2C bus. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] slave_addr1 7-bit address of he slave - * @param[in] slave_addr2 used in 10-bit address mode - * @param[in] n number of words to receive - * @param[out] rxbuf the pointer to the receive buffer - * - */ -void i2c_lld_master_receive(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *rxbuf) { - // enable ERR, EVT & BUF ITs - i2cp->i2c_register->CR2 |= (I2C_CR2_ITERREN|I2C_CR2_ITEVTEN|I2C_CR2_ITBUFEN); - i2cp->i2c_register->CR1 |= I2C_CR1_ACK; // acknowledge returned - i2cp->i2c_register->CR1 &= ~I2C_CR1_POS; - - switch(i2cp->nbit_address){ - case 7: - i2cp->slave_addr1 = ((slave_addr <<1) | 0x01); // LSB = 1 -> receive - break; - case 10: - i2cp->slave_addr1 = ((slave_addr >>7) & 0x0006); // add the two msb of 10-bit address to the header - i2cp->slave_addr1 |= 0xF0; // add the header bits (the LSB -> 1 will be add to second - i2cp->slave_addr2 = slave_addr & 0x00FF; // the remaining 8 bit of 10-bit address - break; - } - - i2cp->rxbuf = rxbuf; - i2cp->remaining_bytes = n; - i2cp->flags = I2C_FLG_MASTER_RECEIVER; - i2cp->errors = 0; - - // Only one byte to be received - if(i2cp->remaining_bytes == 1) { - i2cp->flags |= I2C_FLG_1BTR; - } - // Only two bytes to be received - else if(i2cp->remaining_bytes == 2) { - i2cp->flags |= I2C_FLG_2BTR; - i2cp->i2c_register->CR1 |= I2C_CR1_POS; // Acknowledge Position - } - - i2cp->i2c_register->CR1 |= I2C_CR1_START; // send start bit - -#if !I2C_USE_WAIT - /* Wait until the START condition is generated on the bus: the START bit is cleared by hardware */ - uint32_t tmo = 0xfffff; - while((i2cp->i2c_register->CR1 & I2C_CR1_START) && tmo--) - ; -#endif /* I2C_USE_WAIT */ -} - -#endif // HAL_USE_I2C - diff --git a/os/hal/platforms/STM32/i2c_lld_albi.h b/os/hal/platforms/STM32/i2c_lld_albi.h deleted file mode 100644 index 2b63afec9..000000000 --- a/os/hal/platforms/STM32/i2c_lld_albi.h +++ /dev/null @@ -1,263 +0,0 @@ -/* - 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 STM32/i2c_lld.h - * @brief STM32 I2C subsystem low level driver header. - * @addtogroup STM32_I2C - * @{ - */ - -#ifndef _I2C_LLD_H_ -#define _I2C_LLD_H_ - -#include "ch.h" -#include "hal.h" - -#if HAL_USE_I2C || defined(__DOXYGEN__) - -/*===========================================================================*/ -/* Driver constants. */ -/*===========================================================================*/ -#define I2C_OAR1_ADD0_9 ((uint16_t)0x03FF) /*!= @p STM32_I2C1_IRQ_PRIORITY > @p PRIORITY_PENDSV. - */ -#if !defined(STM32_I2C1_IRQ_PRIORITY) || defined(__DOXYGEN__) -#define STM32_I2C1_IRQ_PRIORITY 0xA0 -#endif - -/** - * @brief I2C2 interrupt priority level setting. - * @note @p BASEPRI_KERNEL >= @p STM32_I2C2_IRQ_PRIORITY > @p PRIORITY_PENDSV. - */ -#if !defined(STM32_I2C2_IRQ_PRIORITY) || defined(__DOXYGEN__) -#define STM32_I2C2_IRQ_PRIORITY 0xA0 -#endif - -/*===========================================================================*/ -/* Derived constants and error checks. */ -/*===========================================================================*/ - -/** @brief EV5 */ -#define I2C_EV5_MASTER_MODE_SELECT ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY)<< 16)|I2C_SR1_SB)) /* BUSY, MSL and SB flag */ -/** @brief EV6 */ -#define I2C_EV6_MASTER_TRA_MODE_SELECTED ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY|I2C_SR2_TRA)<< 16)|I2C_SR1_ADDR|I2C_SR1_TXE)) /* BUSY, MSL, ADDR, TXE and TRA flags */ -#define I2C_EV6_MASTER_REC_MODE_SELECTED ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY)<< 16)|I2C_SR1_ADDR)) /* BUSY, MSL and ADDR flags */ -/** @brief EV7 */ -#define I2C_EV7_MASTER_REC_BYTE_RECEIVED ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY)<< 16)|I2C_SR1_RXNE)) /* BUSY, MSL and RXNE flags */ -#define I2C_EV7_MASTER_REC_BYTE_QUEUED ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY)<< 16)|I2C_SR1_BTF|I2C_SR1_RXNE)) /* BUSY, MSL, RXNE and BTF flags*/ -/** @brief EV8 */ -#define I2C_EV8_MASTER_BYTE_TRANSMITTING ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY|I2C_SR2_TRA)<< 16)|I2C_SR1_TXE)) /* TRA, BUSY, MSL, TXE flags */ -/** @brief EV8_2 */ -#define I2C_EV8_2_MASTER_BYTE_TRANSMITTED ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY|I2C_SR2_TRA)<< 16)|I2C_SR1_BTF|I2C_SR1_TXE)) /* TRA, BUSY, MSL, TXE and BTF flags */ -/** @brief EV9 */ -#define I2C_EV9_MASTER_ADDR_10BIT ((uint32_t)(((I2C_SR2_MSL|I2C_SR2_BUSY)<< 16)|I2C_SR1_ADD10)) /* BUSY, MSL and ADD10 flags */ -#define I2C_EV_MASK 0x00FFFFFF - -#define I2C_FLG_1BTR 0x01 // Single byte to be received and processed -#define I2C_FLG_2BTR 0x02 // Two bytes to be received and processed -#define I2C_FLG_3BTR 0x04 // Last three received bytes to be processed -#define I2C_FLG_MASTER_RECEIVER 0x10 -#define I2C_FLG_HEADER_SENT 0x80 - -#define EV6_SUBEV_MASK (I2C_FLG_1BTR|I2C_FLG_2BTR|I2C_FLG_MASTER_RECEIVER) -#define EV7_SUBEV_MASK (I2C_FLG_2BTR|I2C_FLG_3BTR|I2C_FLG_MASTER_RECEIVER) - -#define I2C_EV6_1_MASTER_REC_2BTR_MODE_SELECTED (I2C_FLG_2BTR|I2C_FLG_MASTER_RECEIVER) -#define I2C_EV6_3_MASTER_REC_1BTR_MODE_SELECTED (I2C_FLG_1BTR|I2C_FLG_MASTER_RECEIVER) -#define I2C_EV7_2_MASTER_REC_3BYTES_TO_PROCESS (I2C_FLG_3BTR|I2C_FLG_MASTER_RECEIVER) -#define I2C_EV7_3_MASTER_REC_2BYTES_TO_PROCESS (I2C_FLG_2BTR|I2C_FLG_MASTER_RECEIVER) - -/*===========================================================================*/ -/* Driver data structures and types. */ -/*===========================================================================*/ -/** - * @brief Serial Driver condition flags type. - */ -typedef uint32_t i2cflags_t; - -typedef enum { - opmodeI2C, - opmodeSMBusDevice, - opmodeSMBusHost, -} I2C_opMode_t; - -typedef enum { - stdDutyCycle, - fastDutyCycle_2, - fastDutyCycle_16_9, -} I2C_DutyCycle_t; - -/** - * @brief Type of a structure representing an SPI driver. - */ -typedef struct I2CDriver I2CDriver; - -/** - * @brief I2C notification callback type. - * - * @param[in] i2cp pointer to the @p I2CDriver object triggering the - * callback - */ -typedef void (*i2ccallback_t)(I2CDriver *i2cp); - -/** - * @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 */ - - uint16_t OwnAddress1; /*!< Specifies the first device own address. Can be a 7-bit or 10-bit address. */ - - uint16_t Ack; /*!< Enables or disables the acknowledgement. */ - - uint8_t nBitAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged */ - -} I2CConfig; - -/** - * @brief Structure representing an I2C driver. - */ -struct I2CDriver { - /** - * @brief Driver state. - */ - i2cstate_t state; - /** - * @brief Operation complete callback or @p NULL. - */ - i2ccallback_t endcb; -#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 mutex; -#elif CH_USE_SEMAPHORES - Semaphore semaphore; -#endif -#endif /* I2C_USE_MUTUAL_EXCLUSION */ - - /* End of the mandatory fields.*/ - /** - * @brief Pointer to the I2Cx registers block. - */ - I2C_TypeDef *i2c_register; - size_t remaining_bytes; - uint8_t *rxbuf; - uint8_t *txbuf; - uint8_t slave_addr1; // 7-bit address of the slave - uint8_t slave_addr2; // used in 10-bit address mode - uint8_t nbit_address; - i2cflags_t errors; - i2cflags_t flags; - /* Status Change @p EventSource.*/ - EventSource sevent; -}; - -/*===========================================================================*/ -/* Driver macros. */ -/*===========================================================================*/ - -#define i2c_lld_bus_is_busy(i2cp) \ - (i2cp->i2c_register->SR2 & I2C_SR2_BUSY) - - -/* Wait until BUSY flag is reset: a STOP has been generated on the bus - * signaling the end of transmission - */ -#define i2c_lld_wait_bus_free(i2cp) { \ - uint32_t tmo = 0xffff; \ - while((i2cp->i2c_register->SR2 & I2C_SR2_BUSY) && tmo--) \ - ; \ -} - -/*===========================================================================*/ -/* 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_reset(I2CDriver *i2cp); -void i2c_lld_set_clock(I2CDriver *i2cp, int32_t clock_speed, I2C_DutyCycle_t duty); -void i2c_lld_set_opmode(I2CDriver *i2cp, I2C_opMode_t opmode); -void i2c_lld_set_own_address(I2CDriver *i2cp, int16_t address, int8_t nr_bit); -void i2c_lld_start(I2CDriver *i2cp); -void i2c_lld_stop(I2CDriver *i2cp); -void i2c_lld_master_transmit(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *txbuf); -void i2c_lld_master_receive(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *rxbuf); - -#ifdef __cplusplus -} -#endif -/** @endcond*/ - -#endif // CH_HAL_USE_I2C - -#endif // _I2C_LLD_H_ diff --git a/os/hal/platforms/STM32/i2c_lld_brts.c b/os/hal/platforms/STM32/i2c_lld_brts.c deleted file mode 100644 index 1ac7e4309..000000000 --- a/os/hal/platforms/STM32/i2c_lld_brts.c +++ /dev/null @@ -1,626 +0,0 @@ -/** - * @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 deleted file mode 100644 index 76f7068e2..000000000 --- a/os/hal/platforms/STM32/i2c_lld_btrts.h +++ /dev/null @@ -1,201 +0,0 @@ -/** - * @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_albi.c b/os/hal/src/i2c_albi.c deleted file mode 100644 index 64bed78eb..000000000 --- a/os/hal/src/i2c_albi.c +++ /dev/null @@ -1,268 +0,0 @@ -/* - 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 . -*/ - -#include "ch.h" -#include "hal.h" - -#if HAL_USE_I2C || defined(__DOXYGEN__) - -/** - * @brief I2C Driver initialization. - */ -void i2cInit(void) { - - i2c_lld_init(); -} - -/** - * @brief Initializes the standard part of a @p I2CDriver structure. - * - * @param[in] i2cp pointer to the @p I2CDriver object - */ -void i2cObjectInit(I2CDriver *i2cp) { - chEvtInit(&i2cp->sevent); - i2cp->errors = I2CD_NO_ERROR; - i2cp->state = I2C_STOP; -// i2cp->i2cd_config = NULL; -#if I2C_USE_WAIT - i2cp->thread = NULL; -#endif /* I2C_USE_WAIT */ -#if I2C_USE_MUTUAL_EXCLUSION -#if CH_USE_MUTEXES - chMtxInit(&i2cp->mutex); -#elif CH_USE_SEMAPHORES - chSemInit(&i2cp->semaphore, 1); -#endif -#endif /* I2C_USE_MUTUAL_EXCLUSION */ -#if defined(I2C_DRIVER_EXT_INIT_HOOK) - I2C_DRIVER_EXT_INIT_HOOK(i2cp); -#endif -} - -/** - * @brief Configures and activates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] config pointer to the @p I2CConfig object - */ -void i2cStart(I2CDriver *i2cp, const I2CConfig *config) { - - chDbgCheck((i2cp != NULL) && (config != NULL), "i2cStart"); - - chSysLock(); - chDbgAssert((i2cp->state == I2C_STOP)||(i2cp->state == I2C_READY), - "i2cStart(), #1", "invalid state"); - - i2cp->nbit_address = config->nBitAddress; - i2c_lld_start(i2cp); - i2c_lld_set_clock(i2cp, config->ClockSpeed, config->FastModeDutyCycle); - i2c_lld_set_opmode(i2cp, config->opMode); - i2c_lld_set_own_address(i2cp, config->OwnAddress1, config->nBitAddress); - i2cp->state = I2C_READY; - chSysUnlock(); -} - -/** - * @brief Deactivates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - */ -void i2cStop(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cStop"); - - chSysLock(); - chDbgAssert((i2cp->state == I2C_STOP) || (i2cp->state == I2C_READY), - "i2cStop(), #1", "invalid state"); - i2c_lld_stop(i2cp); - i2cp->state = I2C_STOP; - chSysUnlock(); -} - -/** - * @brief Sends data ever the I2C bus. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] slave_addr 7-bit or 10-bit address of the slave - * @param[in] n number of words to send - * @param[in] txbuf the pointer to the transmit buffer - * - */ -void i2cMasterTransmit(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *txbuf) { - - chDbgCheck((i2cp != NULL) && (n > 0) && (txbuf != NULL), - "i2cMasterTransmit"); - -#if I2C_USE_WAIT - i2c_lld_wait_bus_free(i2cp); - if(i2c_lld_bus_is_busy(i2cp)) { -#ifdef PRINTTRACE - print("I2C Bus busy!\n"); -#endif - return; - }; -#endif - - chSysLock(); - chDbgAssert(i2cp->state == I2C_READY, - "i2cMasterTransmit(), #1", "not ready"); - - i2cp->state = I2C_ACTIVE; - i2c_lld_master_transmit(i2cp, slave_addr, n, txbuf); - _i2c_wait_s(i2cp); -#if !I2C_USE_WAIT - i2c_lld_wait_bus_free(i2cp); -#endif - if (i2cp->state == I2C_COMPLETE) - i2cp->state = I2C_READY; - chSysUnlock(); -} - -/** - * @brief Receives data from the I2C bus. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] slave_addr 7-bit or 10-bit address of the slave - * @param[in] n number of bytes to receive - * @param[out] rxbuf the pointer to the receive buffer - * - */ -void i2cMasterReceive(I2CDriver *i2cp, uint16_t slave_addr, size_t n, void *rxbuf) { - - chDbgCheck((i2cp != NULL) && (n > 0) && (rxbuf != NULL), - "i2cMasterReceive"); - -#if I2C_USE_WAIT - i2c_lld_wait_bus_free(i2cp); - if(i2c_lld_bus_is_busy(i2cp)) { -#ifdef PRINTTRACE - print("I2C Bus busy!\n"); -#endif - return; - }; -#endif - - chSysLock(); - chDbgAssert(i2cp->state == I2C_READY, - "i2cMasterReceive(), #1", "not ready"); - - i2cp->state = I2C_ACTIVE; - i2c_lld_master_receive(i2cp, slave_addr, n, rxbuf); - _i2c_wait_s(i2cp); -#if !I2C_USE_WAIT - i2c_lld_wait_bus_free(i2cp); -#endif - if (i2cp->state == I2C_COMPLETE) - i2cp->state = I2C_READY; - chSysUnlock(); -} - -uint16_t i2cSMBusAlertResponse(I2CDriver *i2cp) { - uint16_t slv_addr; - - i2cMasterReceive(i2cp, 0x0C, 2, &slv_addr); - return slv_addr; -} - - -/** - * @brief Handles communication events/errors. - * @details Must be called from the I/O interrupt service routine in order to - * notify I/O conditions as errors, signals change etc. - * - * @param[in] i2cp pointer to a @p I2CDriver structure - * @param[in] mask condition flags to be added to the mask - * - * @iclass - */ -void i2cAddFlagsI(I2CDriver *i2cp, i2cflags_t mask) { - - chDbgCheck(i2cp != NULL, "i2cAddFlagsI"); - - i2cp->errors |= mask; - chEvtBroadcastI(&i2cp->sevent); -} - -/** - * @brief Returns and clears the errors mask associated to the driver. - * - * @param[in] i2cp pointer to a @p I2CDriver structure - * @return The condition flags modified since last time this - * function was invoked. - * - * @api - */ -i2cflags_t i2cGetAndClearFlags(I2CDriver *i2cp) { - i2cflags_t mask; - - chDbgCheck(i2cp != NULL, "i2cGetAndClearFlags"); - - chSysLock(); - mask = i2cp->errors; - i2cp->errors = I2CD_NO_ERROR; - chSysUnlock(); - return mask; -} - - - -#if I2C_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__) -/** - * @brief Gains exclusive access to the I2C bus. - * @details This function tries to gain ownership to the I2C bus, if the bus - * is already being used then the invoking thread is queued. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @note This function is only available when the @p I2C_USE_MUTUAL_EXCLUSION - * option is set to @p TRUE. - */ -void i2cAcquireBus(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cAcquireBus"); - -#if CH_USE_MUTEXES - chMtxLock(&i2cp->mutex); -#elif CH_USE_SEMAPHORES - chSemWait(&i2cp->semaphore); -#endif -} - -/** - * @brief Releases exclusive access to the I2C bus. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @note This function is only available when the @p I2C_USE_MUTUAL_EXCLUSION - * option is set to @p TRUE. - */ -void i2cReleaseBus(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cReleaseBus"); - -#if CH_USE_MUTEXES - (void)i2cp; - chMtxUnlock(); -#elif CH_USE_SEMAPHORES - chSemSignal(&i2cp->semaphore); -#endif -} -#endif /* I2C_USE_MUTUAL_EXCLUSION */ - -#endif /* CH_HAL_USE_I2C */ diff --git a/os/hal/src/i2c_brts.c b/os/hal/src/i2c_brts.c deleted file mode 100644 index ad9a5d0ac..000000000 --- a/os/hal/src/i2c_brts.c +++ /dev/null @@ -1,249 +0,0 @@ -/* - 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.c - * @brief I2C Driver code. - * - * @addtogroup I2C - * @{ - */ - -#include "ch.h" -#include "hal.h" - -#if HAL_USE_I2C || defined(__DOXYGEN__) - -/*===========================================================================*/ -/* Driver exported variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local variables. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver local functions. */ -/*===========================================================================*/ - -/*===========================================================================*/ -/* Driver exported functions. */ -/*===========================================================================*/ - -/** - * @brief I2C Driver initialization. - * @note This function is implicitly invoked by @p halInit(), there is - * no need to explicitly initialize the driver. - * - * @init - */ -void i2cInit(void) { - i2c_lld_init(); -} - -/** - * @brief Initializes the standard part of a @p I2CDriver structure. - * - * @param[out] i2cp pointer to the @p I2CDriver object - * - * @init - */ -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 -} - -/** - * @brief Configures and activates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * @param[in] config pointer to the @p I2CConfig object - * - * @api - */ -void i2cStart(I2CDriver *i2cp, I2CConfig *config) { - - chDbgCheck((i2cp != NULL) && (config != NULL), "i2cStart"); - - chSysLock(); - chDbgAssert((i2cp->id_state == I2C_STOP) || (i2cp->id_state == I2C_READY), - "i2cStart(), #1", - "invalid state"); - i2cp->id_config = config; - i2c_lld_start(i2cp); - i2cp->id_state = I2C_READY; - chSysUnlock(); -} - -/** - * @brief Deactivates the I2C peripheral. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @api - */ -void i2cStop(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cStop"); - - chSysLock(); - chDbgAssert((i2cp->id_state == I2C_STOP) || (i2cp->id_state == I2C_READY), - "i2cStop(), #1", - "invalid state"); - i2c_lld_stop(i2cp); - i2cp->id_state = I2C_STOP; - 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] i2cscfg pointer to the @p I2CSlaveConfig object - * - */ -void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { - - chDbgCheck((i2cp != NULL) && (i2cscfg != NULL), - "i2cMasterTransmit"); - chDbgAssert(i2cp->id_state == I2C_READY, - "i2cMasterTransmit(), #1", - "not active"); - - 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] i2cscfg pointer to the @p I2CSlaveConfig object - */ -void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) { - - chDbgCheck((i2cp != NULL) && (i2cscfg != NULL), - "i2cMasterReceive"); - chDbgAssert(i2cp->id_state == I2C_READY, - "i2cMasterReceive(), #1", - "not active"); - - chSysLock(); - i2c_lld_master_receive(i2cp, i2cscfg); - chSysUnlock(); -} - - - -#if I2C_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__) -/** - * @brief Gains exclusive access to the I2C bus. - * @details This function tries to gain ownership to the I2C bus, if the bus - * is already being used then the invoking thread is queued. - * @pre In order to use this function the option @p I2C_USE_MUTUAL_EXCLUSION - * must be enabled. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @api - * - */ -void i2cAcquireBus(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cAcquireBus"); - -#if CH_USE_MUTEXES - chMtxLock(&i2cp->id_mutex); -#elif CH_USE_SEMAPHORES - chSemWait(&i2cp->id_semaphore); -#endif -} - -/** - * @brief Releases exclusive access to the I2C bus. - * @pre In order to use this function the option @p I2C_USE_MUTUAL_EXCLUSION - * must be enabled. - * - * @param[in] i2cp pointer to the @p I2CDriver object - * - * @api - */ -void i2cReleaseBus(I2CDriver *i2cp) { - - chDbgCheck(i2cp != NULL, "i2cReleaseBus"); - -#if CH_USE_MUTEXES - (void)i2cp; - chMtxUnlock(); -#elif CH_USE_SEMAPHORES - chSemSignal(&i2cp->id_semaphore); -#endif -} -#endif /* I2C_USE_MUTUAL_EXCLUSION */ - -#endif /* HAL_USE_I2C */ - -/** @} */