aboutsummaryrefslogtreecommitdiff
path: root/apps/systemcmds
diff options
context:
space:
mode:
Diffstat (limited to 'apps/systemcmds')
-rw-r--r--apps/systemcmds/eeprom/24xxxx_mtd.c18
-rw-r--r--apps/systemcmds/eeprom/eeprom.c39
2 files changed, 42 insertions, 15 deletions
diff --git a/apps/systemcmds/eeprom/24xxxx_mtd.c b/apps/systemcmds/eeprom/24xxxx_mtd.c
index b5144512b..1b8c59f77 100644
--- a/apps/systemcmds/eeprom/24xxxx_mtd.c
+++ b/apps/systemcmds/eeprom/24xxxx_mtd.c
@@ -138,6 +138,8 @@ struct at24c_dev_s
perf_counter_t perf_reads;
perf_counter_t perf_writes;
+ perf_counter_t perf_resets;
+ perf_counter_t perf_read_retries;
};
/************************************************************************************
@@ -267,6 +269,7 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
for (;;)
{
+ unsigned tries = 50;
perf_begin(priv->perf_reads);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
@@ -274,9 +277,20 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
if (ret >= 0)
break;
- /* XXX probably want a bus reset in here and an eventual timeout */
fvdbg("read stall");
usleep(1000);
+ perf_count(priv->perf_read_retries);
+
+ /*
+ * Kick the bus in case it's stuck.
+ */
+ if (--tries == 0)
+ {
+ tries = 50;
+ up_i2creset(priv->dev);
+ perf_count(priv->perf_resets);
+ }
+
}
startblock++;
@@ -480,6 +494,8 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read");
priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write");
+ priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset");
+ priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries");
}
/* Return the implementation-specific state structure as the MTD device */
diff --git a/apps/systemcmds/eeprom/eeprom.c b/apps/systemcmds/eeprom/eeprom.c
index 6d1037a13..a0b15f77b 100644
--- a/apps/systemcmds/eeprom/eeprom.c
+++ b/apps/systemcmds/eeprom/eeprom.c
@@ -67,13 +67,16 @@
__EXPORT int eeprom_main(int argc, char *argv[]);
+static void eeprom_attach(void);
static void eeprom_start(void);
static void eeprom_erase(void);
static void eeprom_ioctl(unsigned operation);
static void eeprom_save(const char *name);
static void eeprom_load(const char *name);
+static bool attached = false;
static bool started = false;
+static struct mtd_dev_s *eeprom_mtd;
int eeprom_main(int argc, char *argv[])
{
@@ -105,13 +108,8 @@ int eeprom_main(int argc, char *argv[])
static void
-eeprom_start(void)
+eeprom_attach(void)
{
- int ret;
-
- if (started)
- errx(1, "EEPROM service already started");
-
/* find the right I2C */
struct i2c_dev_s *i2c = up_i2cinitialize(PX4_I2C_BUS_ONBOARD);
/* this resets the I2C bus, set correct bus speed again */
@@ -121,16 +119,27 @@ eeprom_start(void)
errx(1, "failed to locate I2C bus");
/* start the MTD driver */
- struct mtd_dev_s *mtd = at24c_initialize(i2c);
+ eeprom_mtd = at24c_initialize(i2c);
- if (mtd == NULL)
+ if (eeprom_mtd == NULL)
errx(1, "failed to initialize EEPROM driver");
- /* driver is started, even if NXFFS fails to mount */
- started = true;
+ attached = true;
+}
+
+static void
+eeprom_start(void)
+{
+ int ret;
+
+ if (started)
+ errx(1, "EEPROM already mounted");
+
+ if (!attached)
+ eeprom_attach();
/* start NXFFS */
- ret = nxffs_initialize(mtd);
+ ret = nxffs_initialize(eeprom_mtd);
if (ret < 0)
errx(1, "failed to initialize NXFFS - erase EEPROM to reformat");
@@ -141,7 +150,9 @@ eeprom_start(void)
if (ret < 0)
errx(1, "failed to mount /eeprom - erase EEPROM to reformat");
- errx(0, "mounted EEPROM at /eeprom");
+ started = true;
+ warnx("mounted EEPROM at /eeprom");
+ exit(0);
}
extern int at24c_nuke(void);
@@ -149,8 +160,8 @@ extern int at24c_nuke(void);
static void
eeprom_erase(void)
{
- if (!started)
- errx(1, "must be started first");
+ if (!attached)
+ eeprom_attach();
if (at24c_nuke())
errx(1, "erase failed");