Bringing back old I2C code, just temporary workaround

This commit is contained in:
Lorenz Meier 2013-01-19 12:52:25 +01:00
parent bc35bb23dd
commit c15093bb55
1 changed files with 190 additions and 205 deletions

View File

@ -116,14 +116,8 @@
/* Interrupt wait time timeout in system timer ticks */ /* Interrupt wait time timeout in system timer ticks */
#ifndef CONFIG_STM32_I2CTIMEOTICKS #define CONFIG_STM32_I2CTIMEOTICKS \
# define CONFIG_STM32_I2CTIMEOTICKS \
(SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS)) (SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
#endif
#ifndef CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP
# define CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP TICK2USEC(CONFIG_STM32_I2CTIMEOTICKS)
#endif
/* On the STM32F103ZE, there is an internal conflict between I2C1 and FSMC. In that /* On the STM32F103ZE, there is an internal conflict between I2C1 and FSMC. In that
* case, it is necessary to disable FSMC before each I2C1 access and re-enable FSMC * case, it is necessary to disable FSMC before each I2C1 access and re-enable FSMC
@ -135,18 +129,6 @@
# define I2C1_FSMC_CONFLICT # define I2C1_FSMC_CONFLICT
#endif #endif
/* Macros to convert a I2C pin to a GPIO output */
#if defined(CONFIG_STM32_STM32F10XX)
# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_CNF_OUTOD | \
GPIO_MODE_50MHz)
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_FLOAT | GPIO_OPENDRAIN |\
GPIO_SPEED_50MHz | GPIO_OUTPUT_SET)
#endif
#define MKI2C_OUTPUT(p) (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT)
/* Debug ****************************************************************************/ /* Debug ****************************************************************************/
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */ /* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */
@ -219,15 +201,17 @@ struct stm32_trace_s
struct stm32_i2c_config_s struct stm32_i2c_config_s
{ {
uint32_t base; /* I2C base address */ uint32_t base; /* I2C base address */
#ifndef CONFIG_I2C_POLLED
int ( *isr)(int, void *); /* Interrupt handler */
#endif
uint32_t clk_bit; /* Clock enable bit */ uint32_t clk_bit; /* Clock enable bit */
uint32_t reset_bit; /* Reset bit */ uint32_t reset_bit; /* Reset bit */
uint32_t scl_pin; /* GPIO configuration for SCL as SCL */ uint32_t scl_pin; /* GPIO configuration for SCL as SCL */
uint32_t scl_gpio; /* GPIO configuration for SCL as a GPIO */
uint32_t sda_pin; /* GPIO configuration for SDA as SDA */ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */
#ifndef CONFIG_I2C_POLLED uint32_t sda_gpio; /* GPIO configuration for SDA as a GPIO */
int (*isr)(int, void *); /* Interrupt handler */
uint32_t ev_irq; /* Event IRQ */ uint32_t ev_irq; /* Event IRQ */
uint32_t er_irq; /* Error IRQ */ uint32_t er_irq; /* Error IRQ */
#endif
}; };
/* I2C Device Private Data */ /* I2C Device Private Data */
@ -286,11 +270,8 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits, uint8_t offset, uint16_t clearbits,
uint16_t setbits); uint16_t setbits);
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev); static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
#ifdef CONFIG_STM32_I2C_DYNTIMEO static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us);
static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs); static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv, int timeout_us);
#endif /* CONFIG_STM32_I2C_DYNTIMEO */
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev); static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev);
static inline void stm32_i2c_sem_init(FAR struct i2c_dev_s *dev); static inline void stm32_i2c_sem_init(FAR struct i2c_dev_s *dev);
static inline void stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev); static inline void stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev);
@ -300,7 +281,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv, static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm); enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv); static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
#endif /* CONFIG_I2C_TRACE */ #endif
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency); uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv); static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@ -310,7 +291,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT #ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv); static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr); static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
#endif /* I2C1_FSMC_CONFLICT */ #endif
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv); static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED #ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1 #ifdef CONFIG_STM32_I2C1
@ -348,18 +329,27 @@ static int stm32_i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *m
************************************************************************************/ ************************************************************************************/
#ifdef CONFIG_STM32_I2C1 #ifdef CONFIG_STM32_I2C1
# ifndef GPIO_I2C1_SCL_GPIO
# define GPIO_I2C1_SCL_GPIO 0
# endif
# ifndef GPIO_I2C1_SDA_GPIO
# define GPIO_I2C1_SDA_GPIO 0
# endif
static const struct stm32_i2c_config_s stm32_i2c1_config = static const struct stm32_i2c_config_s stm32_i2c1_config =
{ {
.base = STM32_I2C1_BASE, .base = STM32_I2C1_BASE,
#ifndef CONFIG_I2C_POLLED
.isr = stm32_i2c1_isr,
#endif
.clk_bit = RCC_APB1ENR_I2C1EN, .clk_bit = RCC_APB1ENR_I2C1EN,
.reset_bit = RCC_APB1RSTR_I2C1RST, .reset_bit = RCC_APB1RSTR_I2C1RST,
.scl_pin = GPIO_I2C1_SCL, .scl_pin = GPIO_I2C1_SCL,
.scl_gpio = GPIO_I2C1_SCL_GPIO,
.sda_pin = GPIO_I2C1_SDA, .sda_pin = GPIO_I2C1_SDA,
#ifndef CONFIG_I2C_POLLED .sda_gpio = GPIO_I2C1_SDA_GPIO,
.isr = stm32_i2c1_isr,
.ev_irq = STM32_IRQ_I2C1EV, .ev_irq = STM32_IRQ_I2C1EV,
.er_irq = STM32_IRQ_I2C1ER .er_irq = STM32_IRQ_I2C1ER
#endif
}; };
struct stm32_i2c_priv_s stm32_i2c1_priv = struct stm32_i2c_priv_s stm32_i2c1_priv =
@ -377,18 +367,27 @@ struct stm32_i2c_priv_s stm32_i2c1_priv =
#endif #endif
#ifdef CONFIG_STM32_I2C2 #ifdef CONFIG_STM32_I2C2
# ifndef GPIO_I2C2_SCL_GPIO
# define GPIO_I2C2_SCL_GPIO 0
# endif
# ifndef GPIO_I2C2_SDA_GPIO
# define GPIO_I2C2_SDA_GPIO 0
# endif
static const struct stm32_i2c_config_s stm32_i2c2_config = static const struct stm32_i2c_config_s stm32_i2c2_config =
{ {
.base = STM32_I2C2_BASE, .base = STM32_I2C2_BASE,
#ifndef CONFIG_I2C_POLLED
.isr = stm32_i2c2_isr,
#endif
.clk_bit = RCC_APB1ENR_I2C2EN, .clk_bit = RCC_APB1ENR_I2C2EN,
.reset_bit = RCC_APB1RSTR_I2C2RST, .reset_bit = RCC_APB1RSTR_I2C2RST,
.scl_pin = GPIO_I2C2_SCL, .scl_pin = GPIO_I2C2_SCL,
.scl_gpio = GPIO_I2C2_SCL_GPIO,
.sda_pin = GPIO_I2C2_SDA, .sda_pin = GPIO_I2C2_SDA,
#ifndef CONFIG_I2C_POLLED .sda_gpio = GPIO_I2C2_SDA_GPIO,
.isr = stm32_i2c2_isr,
.ev_irq = STM32_IRQ_I2C2EV, .ev_irq = STM32_IRQ_I2C2EV,
.er_irq = STM32_IRQ_I2C2ER .er_irq = STM32_IRQ_I2C2ER
#endif
}; };
struct stm32_i2c_priv_s stm32_i2c2_priv = struct stm32_i2c_priv_s stm32_i2c2_priv =
@ -406,18 +405,27 @@ struct stm32_i2c_priv_s stm32_i2c2_priv =
#endif #endif
#ifdef CONFIG_STM32_I2C3 #ifdef CONFIG_STM32_I2C3
# ifndef GPIO_I2C3_SCL_GPIO
# define GPIO_I2C3_SCL_GPIO 0
# endif
# ifndef GPIO_I2C3_SDA_GPIO
# define GPIO_I2C3_SDA_GPIO 0
# endif
static const struct stm32_i2c_config_s stm32_i2c3_config = static const struct stm32_i2c_config_s stm32_i2c3_config =
{ {
.base = STM32_I2C3_BASE, .base = STM32_I2C3_BASE,
#ifndef CONFIG_I2C_POLLED
.isr = stm32_i2c3_isr,
#endif
.clk_bit = RCC_APB1ENR_I2C3EN, .clk_bit = RCC_APB1ENR_I2C3EN,
.reset_bit = RCC_APB1RSTR_I2C3RST, .reset_bit = RCC_APB1RSTR_I2C3RST,
.scl_pin = GPIO_I2C3_SCL, .scl_pin = GPIO_I2C3_SCL,
.scl_gpio = GPIO_I2C3_SCL_GPIO,
.sda_pin = GPIO_I2C3_SDA, .sda_pin = GPIO_I2C3_SDA,
#ifndef CONFIG_I2C_POLLED .sda_gpio = GPIO_I2C3_SDA_GPIO,
.isr = stm32_i2c3_isr,
.ev_irq = STM32_IRQ_I2C3EV, .ev_irq = STM32_IRQ_I2C3EV,
.er_irq = STM32_IRQ_I2C3ER .er_irq = STM32_IRQ_I2C3ER
#endif
}; };
struct stm32_i2c_priv_s stm32_i2c3_priv = struct stm32_i2c_priv_s stm32_i2c3_priv =
@ -517,35 +525,6 @@ static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
} }
} }
/************************************************************************************
* Name: stm32_i2c_tousecs
*
* Description:
* Return a micro-second delay based on the number of bytes left to be processed.
*
************************************************************************************/
#ifdef CONFIG_STM32_I2C_DYNTIMEO
static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs)
{
size_t bytecount = 0;
int i;
/* Count the number of bytes left to process */
for (i = 0; i < msgc; i++)
{
bytecount += msgs[i].length;
}
/* Then return a number of microseconds based on a user provided scaling
* factor.
*/
return (useconds_t)(CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE * bytecount);
}
#endif
/************************************************************************************ /************************************************************************************
* Name: stm32_i2c_sem_waitdone * Name: stm32_i2c_sem_waitdone
* *
@ -555,7 +534,7 @@ static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs)
************************************************************************************/ ************************************************************************************/
#ifndef CONFIG_I2C_POLLED #ifndef CONFIG_I2C_POLLED
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
{ {
struct timespec abstime; struct timespec abstime;
irqstate_t flags; irqstate_t flags;
@ -587,24 +566,31 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
#if CONFIG_STM32_I2CTIMEOSEC > 0 #if CONFIG_STM32_I2CTIMEOSEC > 0
abstime.tv_sec += CONFIG_STM32_I2CTIMEOSEC; abstime.tv_sec += CONFIG_STM32_I2CTIMEOSEC;
#endif #endif
#if CONFIG_STM32_I2CTIMEOUS_PER_BYTE > 0
/* Add a value proportional to the number of bytes in the transfer */ /* Count the number of bytes left to process */
int i;
int bytecount = 0;
for (i = 0; i < priv->msgc; i++)
{
bytecount += priv->msgv[i].length;
}
#ifdef CONFIG_STM32_I2C_DYNTIMEO abstime.tv_nsec += (CONFIG_STM32_I2CTIMEOUS_PER_BYTE * bytecount) * 1000;
abstime.tv_nsec += 1000 * stm32_i2c_tousecs(priv->msgc, priv->msgv);
if (abstime.tv_nsec > 1000 * 1000 * 1000) if (abstime.tv_nsec > 1000 * 1000 * 1000)
{ {
abstime.tv_sec++; abstime.tv_sec++;
abstime.tv_nsec -= 1000 * 1000 * 1000; abstime.tv_nsec -= 1000 * 1000 * 1000;
} }
#else
#elif CONFIG_STM32_I2CTIMEOMS > 0 #if CONFIG_STM32_I2CTIMEOMS > 0
abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000; abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
if (abstime.tv_nsec > 1000 * 1000 * 1000) if (abstime.tv_nsec > 1000 * 1000 * 1000)
{ {
abstime.tv_sec++; abstime.tv_sec++;
abstime.tv_nsec -= 1000 * 1000 * 1000; abstime.tv_nsec -= 1000 * 1000 * 1000;
} }
#endif
#endif #endif
/* Wait until either the transfer is complete or the timeout expires */ /* Wait until either the transfer is complete or the timeout expires */
@ -638,21 +624,12 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
return ret; return ret;
} }
#else #else
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv) static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
{ {
uint32_t timeout;
uint32_t start; uint32_t start;
uint32_t elapsed; uint32_t elapsed;
int ret; int ret;
/* Get the timeout value */
#ifdef CONFIG_STM32_I2C_DYNTIMEO
timeout = USEC2TICK(stm32_i2c_tousecs(priv->msgc, priv->msgv));
#else
timeout = CONFIG_STM32_I2CTIMEOTICKS;
#endif
/* Signal the interrupt handler that we are waiting. NOTE: Interrupts /* Signal the interrupt handler that we are waiting. NOTE: Interrupts
* are currently disabled but will be temporarily re-enabled below when * are currently disabled but will be temporarily re-enabled below when
* sem_timedwait() sleeps. * sem_timedwait() sleeps.
@ -675,11 +652,10 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
} }
/* Loop until the transfer is complete. */ /* Loop until the transfer is complete. */
while (priv->intstate != INTSTATE_DONE && elapsed < USEC2TICK(timeout_us));
while (priv->intstate != INTSTATE_DONE && elapsed < timeout);
i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n", i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n",
priv->intstate, elapsed, timeout, priv->status); priv->intstate, elapsed, USEC2TICK(timeout_us), priv->status);
/* Set the interrupt state back to IDLE */ /* Set the interrupt state back to IDLE */
@ -697,22 +673,13 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
* *
************************************************************************************/ ************************************************************************************/
static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv) static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
{ {
uint32_t start; uint32_t start;
uint32_t elapsed; uint32_t elapsed;
uint32_t timeout;
uint32_t cr1; uint32_t cr1;
uint32_t sr1; uint32_t sr1;
/* Select a timeout */
#ifdef CONFIG_STM32_I2C_DYNTIMEO
timeout = USEC2TICK(CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP);
#else
timeout = CONFIG_STM32_I2CTIMEOTICKS;
#endif
/* Wait as stop might still be in progress; but stop might also /* Wait as stop might still be in progress; but stop might also
* be set because of a timeout error: "The [STOP] bit is set and * be set because of a timeout error: "The [STOP] bit is set and
* cleared by software, cleared by hardware when a Stop condition is * cleared by software, cleared by hardware when a Stop condition is
@ -745,7 +712,7 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
/* Loop until the stop is complete or a timeout occurs. */ /* Loop until the stop is complete or a timeout occurs. */
while (elapsed < timeout); while (elapsed < USEC2TICK(timeout_us));
/* If we get here then a timeout occurred with the STOP condition /* If we get here then a timeout occurred with the STOP condition
* still pending. * still pending.
@ -965,7 +932,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{ {
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */ /* Fast mode speed calculation with Tlow/Thigh = 16/9 */
#ifdef CONFIG_STM32_I2C_DUTY16_9 #ifdef CONFIG_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25)); speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */ /* Set DUTY and fast speed bits */
@ -1104,7 +1071,7 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */ /* Is this I2C1 */
#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) #ifdef CONFIG_STM32_I2C2
if (priv->config->base == STM32_I2C1_BASE) if (priv->config->base == STM32_I2C1_BASE)
#endif #endif
{ {
@ -1231,29 +1198,26 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{ {
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt); stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
/* No interrupts or context switches may occur in the following
* sequence. Otherwise, additional bytes may be sent by the
* device.
*/
#ifdef CONFIG_I2C_POLLED #ifdef CONFIG_I2C_POLLED
irqstate_t state = irqsave(); irqstate_t state = irqsave();
#endif #endif
/* Receive a byte */ /* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET); *priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
/* Disable acknowledge when last byte is to be received */ /* Disable acknowledge when last byte is to be received */
priv->dcnt--;
if (priv->dcnt == 1) if (priv->dcnt == 1)
{ {
stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0); stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0);
} }
priv->dcnt--;
#ifdef CONFIG_I2C_POLLED #ifdef CONFIG_I2C_POLLED
irqrestore(state); irqrestore(state);
#endif #endif
} }
} }
@ -1444,6 +1408,7 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Enable power and reset the peripheral */ /* Enable power and reset the peripheral */
modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit); modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit); modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0); modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
@ -1496,23 +1461,17 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0); stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
/* Unconfigure GPIO pins */
stm32_unconfiggpio(priv->config->scl_pin); stm32_unconfiggpio(priv->config->scl_pin);
stm32_unconfiggpio(priv->config->sda_pin); stm32_unconfiggpio(priv->config->sda_pin);
/* Disable and detach interrupts */
#ifndef CONFIG_I2C_POLLED #ifndef CONFIG_I2C_POLLED
up_disable_irq(priv->config->ev_irq); up_disable_irq(priv->config->ev_irq);
up_disable_irq(priv->config->er_irq); up_disable_irq(priv->config->er_irq);
irq_detach(priv->config->ev_irq); irq_detach(priv->config->ev_irq);
irq_detach(priv->config->er_irq); irq_detach(priv->config->er_irq);
#endif #endif
/* Disable clocking */
modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0); modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK; return OK;
} }
@ -1574,14 +1533,14 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
struct stm32_i2c_inst_s *inst = (struct stm32_i2c_inst_s *)dev; struct stm32_i2c_inst_s *inst = (struct stm32_i2c_inst_s *)dev;
FAR struct stm32_i2c_priv_s *priv = inst->priv; FAR struct stm32_i2c_priv_s *priv = inst->priv;
uint32_t status = 0; uint32_t status = 0;
uint32_t ahbenr; //uint32_t ahbenr;
int errval = 0; int errval = 0;
ASSERT(count); ASSERT(count);
/* Disable FSMC that shares a pin with I2C1 (LBAR) */ /* Disable FSMC that shares a pin with I2C1 (LBAR) */
ahbenr = stm32_i2c_disablefsmc(priv); (void)stm32_i2c_disablefsmc(priv);
/* Wait for any STOP in progress. NOTE: If we have to disable the FSMC /* Wait for any STOP in progress. NOTE: If we have to disable the FSMC
* then we cannot do this at the top of the loop, unfortunately. The STOP * then we cannot do this at the top of the loop, unfortunately. The STOP
@ -1589,7 +1548,11 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/ */
#ifndef I2C1_FSMC_CONFLICT #ifndef I2C1_FSMC_CONFLICT
stm32_i2c_sem_waitstop(priv); #if CONFIG_STM32_I2CTIMEOUS_START_STOP > 0
stm32_i2c_sem_waitstop(priv, CONFIG_STM32_I2CTIMEOUS_START_STOP);
#else
stm32_i2c_sem_waitstop(priv, CONFIG_STM32_I2CTIMEOMS + CONFIG_STM32_I2CTIMEOSEC * 1000000);
#endif
#endif #endif
/* Clear any pending error interrupts */ /* Clear any pending error interrupts */
@ -1610,6 +1573,22 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
priv->msgv = msgs; priv->msgv = msgs;
priv->msgc = count; priv->msgc = count;
/* Calculate timeout values */
int timeout_us = 0;
#if CONFIG_STM32_I2CTIMEOUS_PER_BYTE > 0
/* Count the number of bytes left to process */
int i;
int bytecount = 10;
for (i = 0; i < count; i++)
{
bytecount += msgs[i].length;
}
timeout_us = CONFIG_STM32_I2CTIMEOUS_PER_BYTE * bytecount;
//i2cvdbg("i2c wait: %d\n", timeout_us);
#else
timeout_us = CONFIG_STM32_I2CTIMEOMS + CONFIG_STM32_I2CTIMEOSEC * 1000000;
#endif
/* Reset I2C trace logic */ /* Reset I2C trace logic */
stm32_i2c_tracereset(priv); stm32_i2c_tracereset(priv);
@ -1629,7 +1608,7 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
* the BUSY flag. * the BUSY flag.
*/ */
if (stm32_i2c_sem_waitdone(priv) < 0) if (stm32_i2c_sem_waitdone(priv, timeout_us) < 0)
{ {
status = stm32_i2c_getstatus(priv); status = stm32_i2c_getstatus(priv);
errval = ETIMEDOUT; errval = ETIMEDOUT;
@ -1644,9 +1623,7 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/ */
stm32_i2c_clrstart(priv); stm32_i2c_clrstart(priv);
// XXX also clear busy flag in case of timeout
/* Clear busy flag in case of timeout */
status = priv->status & 0xffff; status = priv->status & 0xffff;
} }
else else
@ -1976,15 +1953,13 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
* *
************************************************************************************/ ************************************************************************************/
#ifdef CONFIG_I2C_RESET
int up_i2creset(FAR struct i2c_dev_s * dev) int up_i2creset(FAR struct i2c_dev_s * dev)
{ {
struct stm32_i2c_priv_s * priv; struct stm32_i2c_priv_s * priv;
unsigned int clock_count; unsigned clock_count;
unsigned int stretch_count; unsigned stretch_count;
uint32_t scl_gpio;
uint32_t sda_gpio;
int ret = ERROR; int ret = ERROR;
irqstate_t state;
ASSERT(dev); ASSERT(dev);
@ -2004,72 +1979,82 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
stm32_i2c_deinit(priv); stm32_i2c_deinit(priv);
/* Use GPIO configuration to un-wedge the bus */ /* If possible, use GPIO configuration to un-wedge the bus */
scl_gpio = MKI2C_OUTPUT(priv->config->scl_pin); if ((priv->config->scl_gpio != 0) && (priv->config->sda_gpio != 0))
sda_gpio = MKI2C_OUTPUT(priv->config->sda_pin); {
stm32_configgpio(priv->config->scl_gpio);
stm32_configgpio(priv->config->sda_gpio);
/* Let SDA go high */ /*
stm32_gpiowrite(sda_gpio, 1); * Clock the bus until any slaves currently driving it let it go.
*/
/* Clock the bus until any slaves currently driving it let it go. */
clock_count = 0; clock_count = 0;
while (!stm32_gpioread(sda_gpio)) while (!stm32_gpioread(priv->config->sda_gpio))
{ {
/* Give up if we have tried too hard */ /* Give up if we have tried too hard */
if (clock_count++ > 10) if (clock_count++ > 1000)
{ {
goto out; goto out;
} }
/* Sniff to make sure that clock stretching has finished. /*
* Sniff to make sure that clock stretching has finished.
* *
* If the bus never relaxes, the reset has failed. * If the bus never relaxes, the reset has failed.
*/ */
stretch_count = 0; stretch_count = 0;
while (!stm32_gpioread(scl_gpio)) while (!stm32_gpioread(priv->config->scl_gpio))
{ {
/* Give up if we have tried too hard */ /* Give up if we have tried too hard */
if (stretch_count++ > 10) if (stretch_count++ > 1000)
{ {
goto out; goto out;
} }
up_udelay(10); up_udelay(10);
} }
/* Drive SCL low */ /* Drive SCL low */
stm32_gpiowrite(scl_gpio, 0); stm32_gpiowrite(priv->config->scl_gpio, 0);
up_udelay(10); up_udelay(10);
/* Drive SCL high again */ /* Drive SCL high again */
stm32_gpiowrite(scl_gpio, 1); stm32_gpiowrite(priv->config->scl_gpio, 1);
up_udelay(10); up_udelay(10);
} }
/* Generate a start followed by a stop to reset slave /*
* Generate a start followed by a stop to reset slave
* state machines. * state machines.
*/ */
stm32_gpiowrite(sda_gpio, 0); stm32_gpiowrite(priv->config->sda_gpio, 0);
up_udelay(10); up_udelay(10);
stm32_gpiowrite(scl_gpio, 0); stm32_gpiowrite(priv->config->scl_gpio, 0);
up_udelay(10); up_udelay(10);
stm32_gpiowrite(scl_gpio, 1); stm32_gpiowrite(priv->config->scl_gpio, 1);
up_udelay(10); up_udelay(10);
stm32_gpiowrite(sda_gpio, 1); stm32_gpiowrite(priv->config->sda_gpio, 1);
up_udelay(10); up_udelay(10);
/* Revert the GPIO configuration. */ /*
* Revert the GPIO configuration.
*/
stm32_unconfiggpio(priv->config->sda_gpio);
stm32_unconfiggpio(priv->config->scl_gpio);
stm32_unconfiggpio(sda_gpio); }
stm32_unconfiggpio(scl_gpio);
/* Re-init the port */ /* Re-init the port */
@ -2078,11 +2063,11 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
out: out:
/* Release the port for re-use by other clients */ /* release the port for re-use by other clients */
stm32_i2c_sem_post(dev); stm32_i2c_sem_post(dev);
return ret; return ret;
} }
#endif /* CONFIG_I2C_RESET */
#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */ #endif /* defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) */