Skip to content

Commit

Permalink
arch: cxd56xx: Add logic for i2c reset
Browse files Browse the repository at this point in the history
Add ARCH_HAVE_I2CRESET configration to ARCH_CHIP_CXD56XX
and implement i2c reset function.
  • Loading branch information
SPRESENSE authored and jerpelea committed Aug 27, 2024
1 parent de8829f commit 2cc9221
Show file tree
Hide file tree
Showing 2 changed files with 120 additions and 1 deletion.
1 change: 1 addition & 0 deletions arch/arm/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -635,6 +635,7 @@ config ARCH_CHIP_CXD56XX
select ARCH_HAVE_TEXT_HEAP
select ARCH_HAVE_SDIO if MMCSD
select ARCH_HAVE_MATH_H
select ARCH_HAVE_I2CRESET
---help---
Sony CXD56XX (ARM Cortex-M4) architectures

Expand Down
120 changes: 119 additions & 1 deletion arch/arm/src/cxd56xx/cxd56_i2c.c
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include "cxd56_i2c.h"
#include "hardware/cxd56_i2c.h"
#include "cxd56_pinconfig.h"
#include "cxd56_gpio.h"

#if defined(CONFIG_CXD56_I2C0_SCUSEQ) || defined(CONFIG_CXD56_I2C1_SCUSEQ)
#include <arch/chip/scu.h>
Expand Down Expand Up @@ -702,7 +703,124 @@ static int cxd56_i2c_transfer(struct i2c_master_s *dev,
#ifdef CONFIG_I2C_RESET
static int cxd56_i2c_reset(struct i2c_master_s *dev)
{
return OK;
struct cxd56_i2cdev_s *priv = (struct cxd56_i2cdev_s *)dev;
unsigned int clock_count;
unsigned int stretch_count;
uint32_t scl_gpio;
uint32_t sda_gpio;
int ret = -EIO;

DEBUGASSERT(dev != NULL);

/* Our caller must own a ref */

DEBUGASSERT(priv->refs > 0);

/* Lock out other clients */

nxmutex_lock(&priv->lock);

/* Use GPIO configuration to un-wedge the bus */

cxd56_i2c_pincontrol(priv->port, false);

switch (priv->port)
{
case 0:
scl_gpio = PIN_I2C0_BCK;
sda_gpio = PIN_I2C0_BDT;
break;
case 1:
scl_gpio = PIN_PWM2;
sda_gpio = PIN_PWM3;
break;
case 2:
default:
scl_gpio = PIN_SPI0_MOSI;
sda_gpio = PIN_SPI0_MISO;
break;
}

/* Enable input of SCL and SDA pins */

cxd56_gpio_config(scl_gpio, true);
cxd56_gpio_config(sda_gpio, true);

/* Let SDA go high */

cxd56_gpio_write(sda_gpio, true);

/* Clock the bus until any slaves currently driving it let it go. */

clock_count = 0;
while (!cxd56_gpio_read(sda_gpio))
{
/* Give up if we have tried too hard */

if (clock_count++ > 10)
{
goto out;
}

/* Sniff to make sure that clock stretching has finished.
*
* If the bus never relaxes, the reset has failed.
*/

stretch_count = 0;
while (!cxd56_gpio_read(scl_gpio))
{
/* Give up if we have tried too hard */

if (stretch_count++ > 10)
{
goto out;
}

up_udelay(10);
}

/* Drive SCL low */

cxd56_gpio_write(scl_gpio, false);
up_udelay(10);

/* Drive SCL high again */

cxd56_gpio_write(scl_gpio, true);
up_udelay(10);
}

/* Generate a start followed by a stop to reset slave
* state machines.
*/

cxd56_gpio_write(sda_gpio, false);
up_udelay(10);
cxd56_gpio_write(scl_gpio, false);
up_udelay(10);
cxd56_gpio_write(scl_gpio, true);
up_udelay(10);
cxd56_gpio_write(sda_gpio, true);
up_udelay(10);

ret = OK;

out:

/* Disable output of SCL and SDA pins */

cxd56_gpio_write_hiz(scl_gpio);
cxd56_gpio_write_hiz(sda_gpio);

/* Revert the GPIO configuration. */

cxd56_i2c_pincontrol(priv->port, true);

/* Release the port for re-use by other clients */

nxmutex_unlock(&priv->lock);
return ret;
}
#endif /* CONFIG_I2C_RESET */

Expand Down

0 comments on commit 2cc9221

Please sign in to comment.