diff options
author | barthess <barthess@35acf78f-673a-0410-8e92-d51de3d6d3f4> | 2011-05-05 17:43:54 +0000 |
---|---|---|
committer | barthess <barthess@35acf78f-673a-0410-8e92-d51de3d6d3f4> | 2011-05-05 17:43:54 +0000 |
commit | 4fda4dc84fcfcfa483f10a8b5043d124ad551ba0 (patch) | |
tree | b880dfea145a9ea6c85cc592e6d24c2a65f356c4 /os/hal | |
parent | 5387a1b39fdefec625c0a285ed8fd63c9baf827f (diff) | |
download | ChibiOS-4fda4dc84fcfcfa483f10a8b5043d124ad551ba0.tar.gz ChibiOS-4fda4dc84fcfcfa483f10a8b5043d124ad551ba0.tar.bz2 ChibiOS-4fda4dc84fcfcfa483f10a8b5043d124ad551ba0.zip |
I2C. Code compiles successfully, but totally not tested.
git-svn-id: svn://svn.code.sf.net/p/chibios/svn/branches/i2c_dev@2921 35acf78f-673a-0410-8e92-d51de3d6d3f4
Diffstat (limited to 'os/hal')
-rw-r--r-- | os/hal/include/i2c.h | 125 | ||||
-rw-r--r-- | os/hal/platforms/STM32/i2c_lld.c | 136 | ||||
-rw-r--r-- | os/hal/platforms/STM32/i2c_lld.h | 17 | ||||
-rw-r--r-- | os/hal/src/i2c.c | 150 |
4 files changed, 248 insertions, 180 deletions
diff --git a/os/hal/include/i2c.h b/os/hal/include/i2c.h index 203de769c..39ba313fd 100644 --- a/os/hal/include/i2c.h +++ b/os/hal/include/i2c.h @@ -150,45 +150,16 @@ struct I2CSlaveConfig{ /**
* @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 */
+ size_t tx_remaining_bytes;
+ size_t rx_remaining_bytes;
+ i2cblock_t *rxbuf;/*!< Pointer to receive buffer. */
+ i2cblock_t *txbuf;/*!< Pointer to transmit buffer.*/
+ uint16_t slave_addr;
+ uint8_t nbit_address;
+ i2cflags_t errors;
+ i2cflags_t flags;
+ /* Status Change @p EventSource.*/
+ EventSource sevent;
};
@@ -196,42 +167,69 @@ struct I2CSlaveConfig{ /* Driver macros. */
/*===========================================================================*/
+#if I2C_USE_WAIT || defined(__DOXYGEN__)
/**
- * @brief Read mode.
- */
-#define I2C_READ 1
-
-/**
- * @brief Write mode.
+ * @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_WRITE 0
+#define _i2c_wait_s(i2cp) { \
+ chDbgAssert((i2cp)->thread == NULL, \
+ "_i2c_wait(), #1", "already waiting"); \
+ (i2cp)->thread = chThdSelf(); \
+ chSchGoSleepS(THD_STATE_SUSPENDED); \
+}
/**
- * @brief Seven bits addresses header builder.
+ * @brief Wakes up the waiting thread.
*
- * @param[in] addr seven bits address value
- * @param[in] rw read/write flag
+ * @param[in] i2cp pointer to the @p I2CDriver object
*
- * @return A 16 bit value representing the header, the most
- * significant byte is always zero.
+ * @notapi
*/
-#define I2C_ADDR7(addr, rw) (uint16_t)((addr) << 1 | (rw))
-
+#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_lld_wait_bus_free(i2cp) //TODO: remove this STUB
+#define _i2c_wait_s(i2cp)
+#define _i2c_wakeup_isr(i2cp)
+#endif /* !I2C_USE_WAIT */
/**
- * @brief Ten bits addresses header builder.
+ * @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] addr ten bits address value
- * @param[in] rw read/write flag
+ * @param[in] i2cp pointer to the @p I2CDriver object
*
- * @return A 16 bit value representing the header, the most
- * significant byte is the first one to be transmitted.
+ * @notapi
*/
-#define I2C_ADDR10(addr, rw) \
- (uint16_t)(0xF000 | \
- (((addr) & 0x0300) << 1) | \
- (((rw) << 8)) | \
- ((addr) & 0x00FF))
+#define _i2c_isr_code(i2cp, i2cscfg) { \
+ (i2cp)->id_state = I2C_COMPLETE; \
+ if(((i2cp)->id_slave_config)->id_callback) { \
+ ((i2cp)->id_slave_config)->id_callback(i2cp, i2cscfg); \
+ } \
+ _i2c_wakeup_isr(i2cp); \
+}
/*===========================================================================*/
/* External declarations. */
@@ -247,6 +245,7 @@ extern "C" { void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg);
void i2cMasterStart(I2CDriver *i2cp);
void i2cMasterStop(I2CDriver *i2cp);
+ void i2cAddFlagsI(I2CDriver *i2cp, i2cflags_t mask);
#if I2C_USE_MUTUAL_EXCLUSION
void i2cAcquireBus(I2CDriver *i2cp);
diff --git a/os/hal/platforms/STM32/i2c_lld.c b/os/hal/platforms/STM32/i2c_lld.c index 4a54632f6..6384300f7 100644 --- a/os/hal/platforms/STM32/i2c_lld.c +++ b/os/hal/platforms/STM32/i2c_lld.c @@ -35,8 +35,8 @@ I2CDriver I2CD2; static uint32_t i2c_get_event(I2CDriver *i2cp){ - uint32_t regSR1 = i2cp->i2c_register->SR1; - uint32_t regSR2 = i2cp->i2c_register->SR2; + uint32_t regSR1 = i2cp->id_i2c->SR1; + uint32_t regSR2 = i2cp->id_i2c->SR2; /* return the last event value from I2C status registers */ return (I2C_EV_MASK & (regSR1 | (regSR2 << 16))); } @@ -44,46 +44,49 @@ static uint32_t i2c_get_event(I2CDriver *i2cp){ static void i2c_serve_event_interrupt(I2CDriver *i2cp) { static __IO uint8_t *txBuffp, *rxBuffp, *datap; - I2C_TypeDef *dp = i2cp->i2c_register; + I2C_TypeDef *dp = i2cp->id_i2c; switch(i2c_get_event(i2cp)) { case I2C_EV5_MASTER_MODE_SELECT: - i2cp->flags &= ~I2C_FLG_HEADER_SENT; + i2cp->id_slave_config->flags &= ~I2C_FLG_HEADER_SENT; dp->DR = i2cp->slave_addr1; break; case I2C_EV9_MASTER_ADDR_10BIT: - if(i2cp->flags & I2C_FLG_MASTER_RECEIVER) { + if(i2cp->id_slave_config->flags & I2C_FLG_MASTER_RECEIVER) { i2cp->slave_addr1 |= 0x01; - i2cp->flags |= I2C_FLG_HEADER_SENT; + i2cp->id_slave_config->flags |= I2C_FLG_HEADER_SENT; +// i2cp->id_i2c->CR1 = (i2cp->id_i2c->CR1 & (~I2C_CR1_ACK)) | I2C_CR1_STOP; } dp->DR = i2cp->slave_addr2; break; + + //------------------------------------------------------------------------ // Master Transmitter ---------------------------------------------------- //------------------------------------------------------------------------ case I2C_EV6_MASTER_TRA_MODE_SELECTED: - if(i2cp->flags & I2C_FLG_HEADER_SENT){ + if(i2cp->id_slave_config->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; + txBuffp = (uint8_t*)i2cp->id_slave_config->txbuf; datap = txBuffp; txBuffp++; - i2cp->remaining_bytes--; + i2cp->id_slave_config->tx_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) { + if(i2cp->id_slave_config->tx_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) { + if(i2cp->id_slave_config->tx_remaining_bytes > 0) { datap = txBuffp; txBuffp++; - i2cp->remaining_bytes--; - if(i2cp->remaining_bytes == 0) { + i2cp->id_slave_config->tx_remaining_bytes--; + if(i2cp->id_slave_config->tx_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; } @@ -95,14 +98,16 @@ static void i2c_serve_event_interrupt(I2CDriver *i2cp) { /* 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); + _i2c_isr_code(i2cp, i2cp->id_slave_config); break; + + //------------------------------------------------------------------------ // Master Receiver ------------------------------------------------------- //------------------------------------------------------------------------ case I2C_EV6_MASTER_REC_MODE_SELECTED: chSysLockFromIsr(); - switch(i2cp->flags & EV6_SUBEV_MASK) { + switch(i2cp->id_slave_config->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; @@ -118,30 +123,30 @@ static void i2c_serve_event_interrupt(I2CDriver *i2cp) { } chSysUnlockFromIsr(); /* Initialize receive buffer pointer */ - rxBuffp = i2cp->rxbuf; + rxBuffp = i2cp->id_slave_config->rxbuf; break; case I2C_EV7_MASTER_REC_BYTE_RECEIVED: - if(i2cp->remaining_bytes != 3) { + if(i2cp->id_slave_config->rx_remaining_bytes != 3) { /* Read the data register */ *rxBuffp = dp->DR; rxBuffp++; - i2cp->remaining_bytes--; - switch(i2cp->remaining_bytes){ + i2cp->id_slave_config->rx_remaining_bytes--; + switch(i2cp->id_slave_config->rx_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; + i2cp->id_slave_config->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); + _i2c_isr_code(i2cp, i2cp->id_slave_config); 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) { + switch(i2cp->id_slave_config->flags & EV7_SUBEV_MASK) { case I2C_EV7_2_MASTER_REC_3BYTES_TO_PROCESS: // DataN-2 and DataN-1 are received chSysLockFromIsr(); @@ -158,8 +163,8 @@ static void i2c_serve_event_interrupt(I2CDriver *i2cp) { chSysUnlockFromIsr(); rxBuffp++; /* Decrement the number of readed bytes */ - i2cp->remaining_bytes -= 2; - i2cp->flags = 0; + i2cp->id_slave_config->rx_remaining_bytes -= 2; + i2cp->id_slave_config->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 @@ -173,10 +178,10 @@ static void i2c_serve_event_interrupt(I2CDriver *i2cp) { rxBuffp++; /* Read the DataN*/ *rxBuffp = dp->DR; - i2cp->remaining_bytes = 0; - i2cp->flags = 0; + i2cp->id_slave_config->rx_remaining_bytes = 0; + i2cp->id_slave_config->flags = 0; /* Portable I2C ISR code defined in the high level driver, note, it is a macro.*/ - _i2c_isr_code(i2cp); + _i2c_isr_code(i2cp, i2cp->id_slave_config); break; } break; @@ -187,7 +192,7 @@ static void i2c_serve_error_interrupt(I2CDriver *i2cp) { i2cflags_t flags; I2C_TypeDef *reg; - reg = i2cp->i2c_register; + reg = i2cp->id_i2c; flags = I2CD_NO_ERROR; if(reg->SR1 & I2C_SR1_BERR) { // Bus error @@ -222,7 +227,7 @@ static void i2c_serve_error_interrupt(I2CDriver *i2cp) { if(flags != I2CD_NO_ERROR) { // send communication end signal - _i2c_isr_code(i2cp); + _i2c_isr_code(i2cp, i2cp->id_slave_config); chSysLockFromIsr(); i2cAddFlagsI(i2cp, flags); chSysUnlockFromIsr(); @@ -330,7 +335,7 @@ void i2c_lld_start(I2CDriver *i2cp) { } void i2c_lld_reset(I2CDriver *i2cp){ - chDbgCheck((i2cp->state == I2C_STOP)||(i2cp->state == I2C_READY), + chDbgCheck((i2cp->id_state == I2C_STOP)||(i2cp->id_state == I2C_READY), "i2c_lld_reset: invalid state"); RCC->APB1RSTR = RCC_APB1RSTR_I2C1RST; // reset I2C 1 @@ -500,92 +505,81 @@ void i2c_lld_stop(I2CDriver *i2cp) { * @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) { +void i2c_lld_master_transmit(I2CDriver *i2cp) { // 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; + i2cp->id_i2c->CR2 |= (I2C_CR2_ITERREN|I2C_CR2_ITEVTEN|I2C_CR2_ITBUFEN); + i2cp->id_i2c->CR1 &= ~I2C_CR1_POS; - switch(i2cp->nbit_address){ + switch(i2cp->id_slave_config->nbit_address){ case 7: - i2cp->slave_addr1 = ((slave_addr <<1) & 0x00FE); // LSB = 0 -> write + i2cp->slave_addr1 = ((i2cp->id_slave_config->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 = ((i2cp->id_slave_config->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 + i2cp->slave_addr2 = i2cp->id_slave_config->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->id_slave_config->flags = 0; + i2cp->id_slave_config->errors = 0; - i2cp->i2c_register->CR1 |= I2C_CR1_START; // send start bit + i2cp->id_i2c->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--) + uint32_t timeout = 0xfffff; + while((i2cp->id_i2c->CR1 & I2C_CR1_START) && timeout--) ; #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) { +void i2c_lld_master_receive(I2CDriver *i2cp){ // 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; + i2cp->id_i2c->CR2 |= (I2C_CR2_ITERREN|I2C_CR2_ITEVTEN|I2C_CR2_ITBUFEN); + i2cp->id_i2c->CR1 |= I2C_CR1_ACK; // acknowledge returned + i2cp->id_i2c->CR1 &= ~I2C_CR1_POS; switch(i2cp->nbit_address){ case 7: - i2cp->slave_addr1 = ((slave_addr <<1) | 0x01); // LSB = 1 -> receive + i2cp->slave_addr1 = ((i2cp->id_slave_config->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 = ((i2cp->id_slave_config->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 + i2cp->slave_addr2 = i2cp->id_slave_config->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; + i2cp->id_slave_config->flags = I2C_FLG_MASTER_RECEIVER; + i2cp->id_slave_config->errors = 0; // Only one byte to be received - if(i2cp->remaining_bytes == 1) { - i2cp->flags |= I2C_FLG_1BTR; + if(i2cp->id_slave_config->rx_remaining_bytes == 1) { + i2cp->id_slave_config->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 + else if(i2cp->id_slave_config->rx_remaining_bytes == 2) { + i2cp->id_slave_config->flags |= I2C_FLG_2BTR; + i2cp->id_i2c->CR1 |= I2C_CR1_POS; // Acknowledge Position } - i2cp->i2c_register->CR1 |= I2C_CR1_START; // send start bit + i2cp->id_i2c->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--) + uint32_t timeout = 0xfffff; + while((i2cp->id_i2c->CR1 & I2C_CR1_START) && timeout--) ; #endif /* I2C_USE_WAIT */ } diff --git a/os/hal/platforms/STM32/i2c_lld.h b/os/hal/platforms/STM32/i2c_lld.h index 2c926b1dd..268e7264d 100644 --- a/os/hal/platforms/STM32/i2c_lld.h +++ b/os/hal/platforms/STM32/i2c_lld.h @@ -115,6 +115,8 @@ typedef struct { 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. */ + uint16_t Ack; /*!< Enables or disables the acknowledgement. */ + uint8_t nBitAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged */ } I2CConfig; @@ -165,6 +167,11 @@ struct I2CDriver{ */ uint8_t rw_bit; + uint8_t slave_addr1; // 7-bit address of the slave + uint8_t slave_addr2; // used in 10-bit address mode + uint8_t nbit_address; + + /*********** End of the mandatory fields. **********************************/ /** @@ -197,13 +204,13 @@ extern "C" { 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_set_clock(I2CDriver *i2cp); +void i2c_lld_set_opmode(I2CDriver *i2cp); +void i2c_lld_set_own_address(I2CDriver *i2cp); 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); +void i2c_lld_master_transmit(I2CDriver *i2cp); +void i2c_lld_master_receive(I2CDriver *i2cp); #ifdef __cplusplus } diff --git a/os/hal/src/i2c.c b/os/hal/src/i2c.c index ad9a5d0ac..50767b3a9 100644 --- a/os/hal/src/i2c.c +++ b/os/hal/src/i2c.c @@ -130,106 +130,174 @@ void i2cStop(I2CDriver *i2cp) { }
/**
- * @brief Generate (re)start on the bus.
+ * @brief Sends data ever the I2C bus.
*
* @param[in] i2cp pointer to the @p I2CDriver object
+ * @param[in] i2cscfg pointer to the @p I2C slave config
+ *
*/
-void i2cMasterStart(I2CDriver *i2cp){
+void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) {
+
+ size_t n;
+ i2cblock_t *txbuf;
+
+ txbuf = i2cscfg->txbuf;
+ n = i2cscfg->tx_remaining_bytes;
+
+ chDbgCheck((i2cp != NULL) && (i2cscfg != NULL) && (n > 0) && (txbuf != NULL),
+ "i2cMasterTransmit");
- chDbgCheck((i2cp != NULL), "i2cMasterTransmit");
+ // init slave config field in driver
+ i2cp->id_slave_config = i2cscfg;
+
+#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();
- i2c_lld_master_start(i2cp);
+ chDbgAssert(i2cp->id_state == I2C_READY,
+ "i2cMasterTransmit(), #1", "not ready");
+
+ i2cp->id_state = I2C_ACTIVE;
+ i2c_lld_master_transmit(i2cp);
+ _i2c_wait_s(i2cp);
+#if !I2C_USE_WAIT
+ i2c_lld_wait_bus_free(i2cp);
+#endif
+ if (i2cp->id_state == I2C_COMPLETE)
+ i2cp->id_state = I2C_READY;
chSysUnlock();
}
/**
- * @brief Generate stop on the bus.
+ * @brief Receives data from the I2C bus.
*
* @param[in] i2cp pointer to the @p I2CDriver object
+ * @param[in] i2cscfg pointer to the @p I2C slave config
+ *
*/
-void i2cMasterStop(I2CDriver *i2cp){
+void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg){
+
+ size_t n;
+ i2cblock_t *rxbuf;
+
+ rxbuf = i2cscfg->rxbuf;
+ n = i2cscfg->rx_remaining_bytes;
+
+ chDbgCheck((i2cp != NULL) && (n > 0) && (rxbuf != NULL),
+ "i2cMasterReceive");
+
+ // init slave config field in driver
+ i2cp->id_slave_config = i2cscfg;
+
+#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
- chDbgCheck((i2cp != NULL), "i2cMasterTransmit");
chSysLock();
- i2c_lld_master_stop(i2cp);
+ chDbgAssert(i2cp->id_state == I2C_READY,
+ "i2cMasterReceive(), #1", "not ready");
+
+ i2cp->id_state = I2C_ACTIVE;
+ i2c_lld_master_receive(i2cp);
+ _i2c_wait_s(i2cp);
+#if !I2C_USE_WAIT
+ i2c_lld_wait_bus_free(i2cp);
+#endif
+ if (i2cp->id_state == I2C_COMPLETE)
+ i2cp->id_state = I2C_READY;
chSysUnlock();
}
+uint16_t i2cSMBusAlertResponse(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) {
+
+ i2cMasterReceive(i2cp, i2cscfg);
+ return i2cp->id_slave_config->slave_addr;
+}
+
+
/**
- * @brief Sends data ever the I2C bus.
+ * @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 the @p I2CDriver object
- * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object
+ * @param[in] i2cp pointer to a @p I2CDriver structure
+ * @param[in] mask condition flags to be added to the mask
*
+ * @iclass
*/
-void i2cMasterTransmit(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) {
+void i2cAddFlagsI(I2CDriver *i2cp, i2cflags_t mask) {
- chDbgCheck((i2cp != NULL) && (i2cscfg != NULL),
- "i2cMasterTransmit");
- chDbgAssert(i2cp->id_state == I2C_READY,
- "i2cMasterTransmit(), #1",
- "not active");
+ chDbgCheck(i2cp != NULL, "i2cAddFlagsI");
- chSysLock();
- i2c_lld_master_transmit(i2cp, i2cscfg);
- chSysUnlock();
+ i2cp->id_slave_config->errors |= mask;
+ chEvtBroadcastI(&i2cp->id_slave_config->sevent);
}
-
/**
- * @brief Receives data from the I2C bus.
+ * @brief Returns and clears the errors mask associated to the driver.
*
- * @param[in] i2cp pointer to the @p I2CDriver object
- * @param[in] i2cscfg pointer to the @p I2CSlaveConfig object
+ * @param[in] i2cp pointer to a @p I2CDriver structure
+ * @return The condition flags modified since last time this
+ * function was invoked.
+ *
+ * @api
*/
-void i2cMasterReceive(I2CDriver *i2cp, I2CSlaveConfig *i2cscfg) {
+i2cflags_t i2cGetAndClearFlags(I2CDriver *i2cp) {
+ i2cflags_t mask;
- chDbgCheck((i2cp != NULL) && (i2cscfg != NULL),
- "i2cMasterReceive");
- chDbgAssert(i2cp->id_state == I2C_READY,
- "i2cMasterReceive(), #1",
- "not active");
+ chDbgCheck(i2cp != NULL, "i2cGetAndClearFlags");
chSysLock();
- i2c_lld_master_receive(i2cp, i2cscfg);
+ mask = i2cp->id_slave_config->errors;
+ i2cp->id_slave_config->errors = I2CD_NO_ERROR;
chSysUnlock();
+ return mask;
}
#if I2C_USE_MUTUAL_EXCLUSION || defined(__DOXYGEN__)
/**
- * @brief Gains exclusive access to the I2C bus.
+ * @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
- *
+ * @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->id_mutex);
+ chMtxLock(&i2cp->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.
+ * @brief Releases exclusive access to the I2C bus.
*
* @param[in] i2cp pointer to the @p I2CDriver object
*
- * @api
+ * @note This function is only available when the @p I2C_USE_MUTUAL_EXCLUSION
+ * option is set to @p TRUE.
*/
void i2cReleaseBus(I2CDriver *i2cp) {
|