Add I2C trace capability; Fix another STM32 I2C/FSMC bug; add verify command to the I2C tool
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@3961 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
24ef9fdbf6
commit
78a589fd55
|
@ -106,3 +106,8 @@
|
|||
show or set the time (only if CONFIG_RTC is set).
|
||||
|
||||
6.10 2011-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
|
||||
* apps/system/i2c: Add repitition and address auto-incrementing so that
|
||||
and command can be executed numerous times. Add a new verify command
|
||||
that will write to a register, read from register, and verify that
|
||||
returned value.
|
||||
|
|
|
@ -40,7 +40,7 @@ include $(APPDIR)/Make.defs
|
|||
# I2C tool
|
||||
|
||||
ASRCS =
|
||||
CSRCS = i2c_bus.c i2c_common.c i2c_dev.c i2c_get.c i2c_main.c i2c_set.c
|
||||
CSRCS = i2c_bus.c i2c_common.c i2c_dev.c i2c_get.c i2c_main.c i2c_set.c i2c_verf.c
|
||||
|
||||
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
|
|
@ -21,6 +21,7 @@ CONTENTS
|
|||
- dev
|
||||
- get
|
||||
- set
|
||||
- verf
|
||||
o I2C Build Configuration
|
||||
- NuttX Configuration Requirements
|
||||
- I2C Tool Configuration Options
|
||||
|
@ -74,12 +75,13 @@ options.
|
|||
Usage: i2c <cmd> [arguments]
|
||||
Where <cmd> is one of:
|
||||
|
||||
Show help: ?
|
||||
List buses: bus
|
||||
List devices: dev [OPTIONS] <first> <last>
|
||||
Read register: get [OPTIONS]
|
||||
Show help: help
|
||||
Write register: set [OPTIONS] <value>
|
||||
Show help : ?
|
||||
List buses : bus
|
||||
List devices : dev [OPTIONS] <first> <last>
|
||||
Read register : get [OPTIONS] [<repititions>]
|
||||
Show help : help
|
||||
Write register: set [OPTIONS] <value> [<repititions>]
|
||||
Verify access : verf [OPTIONS] <value> [<repititions>]
|
||||
|
||||
Where common "sticky" OPTIONS include:
|
||||
[-a addr] is the I2C device address (hex). Default: 03 Current: 03
|
||||
|
@ -87,6 +89,7 @@ options.
|
|||
[-r regaddr] is the I2C device register address (hex). Default: 00 Current: 00
|
||||
[-w width] is the data width (8 or 16 decimal). Default: 8 Current: 8
|
||||
[-s|n], send/don't send start between command and data. Default: -n Current: -n
|
||||
[-i|j], Auto increment|don't increment regaddr on repititions. Default: NO Current: NO
|
||||
[-f freq] I2C frequency. Default: 100000 Current: 100000
|
||||
|
||||
NOTES:
|
||||
|
@ -195,6 +198,11 @@ Common Option Summary
|
|||
This determines whether or not there should be a new I2C START between
|
||||
sending of the register address and sending/receiving of the register data.
|
||||
|
||||
[-i|j], Auto increment|don't increment regaddr on repititions. Default: NO Current: NO
|
||||
|
||||
On commands that take a optional number of repetitions, the option can be
|
||||
used to temporarily increment the regaddr value by one on each repitition.
|
||||
|
||||
[-f freq] I2C frequency. Default: 400000 Current: 400000
|
||||
|
||||
The [-f freq] sets the frequency of the I2C device.
|
||||
|
@ -257,6 +265,13 @@ Read register: get [OPTIONS]
|
|||
data value from the device. Optionally, it may re-start the transfer
|
||||
before obtaining the data.
|
||||
|
||||
An optional <repititions> argument can be supplied to repeat the
|
||||
read operation an arbitrary number of times (up to 2 billion). If
|
||||
auto-increment is select (-i), then the register address will be
|
||||
temporarily incremented on each repitions. The increment is temporary
|
||||
in the since that it will not alter the "sticky" value of the
|
||||
register address.
|
||||
|
||||
On success, the output will look like the following (the data value
|
||||
read will be shown as a 4-character hexadecimal number if the 16-bit
|
||||
data width option is selected).
|
||||
|
@ -274,10 +289,17 @@ Write register: set [OPTIONS] <value>
|
|||
range 00-ff) or a 16-bit value (in the range 0000-ffff), depending upon
|
||||
the selected data width.
|
||||
|
||||
This command with write the 8-bit address value then write the 8- or 16-bit
|
||||
This command will write the 8-bit address value then write the 8- or 16-bit
|
||||
data value to the device. Optionally, it may re-start the transfer
|
||||
before writing the data.
|
||||
|
||||
An optional <repititions> argument can be supplied to repeat the
|
||||
write operation an arbitrary number of times (up to 2 billion). If
|
||||
auto-increment is select (-i), then the register address will be
|
||||
temporarily incremented on each repitions. The increment is temporary
|
||||
in the since that it will not alter the "sticky" value of the
|
||||
register address.
|
||||
|
||||
On success, the output will look like the following (the data value
|
||||
written will be shown as a 4-character hexadecimal number if the 16-bit
|
||||
data width option is selected).
|
||||
|
@ -286,6 +308,35 @@ Write register: set [OPTIONS] <value>
|
|||
|
||||
All values (except the bus numbers) are hexadecimal.
|
||||
|
||||
Verify access : verf [OPTIONS] <value> [<repititions>]
|
||||
------------------------------------------------------
|
||||
|
||||
This command combines writing and reading from an I2C device register.
|
||||
It will write a value to an will write a value to an I2C register using
|
||||
the selected I2C parameters in the common options just as described for
|
||||
tie 'set' command. Then this command will read the value back just
|
||||
as described with the 'get' command. Finally, this command will compare
|
||||
the value read and against the value written and emit an error message
|
||||
if they do not match.
|
||||
|
||||
If no value is provided, then this command will use the register address
|
||||
itself as the data, providing for a address-in-address test.
|
||||
|
||||
An optional <repititions> argument can be supplied to repeat the
|
||||
verify operation an arbitrary number of times (up to 2 billion). If
|
||||
auto-increment is select (-i), then the register address will be
|
||||
temporarily incremented on each repitions. The increment is temporary
|
||||
in the since that it will not alter the "sticky" value of the
|
||||
register address.
|
||||
|
||||
On success, the output will look like the following (the data value
|
||||
written will be shown as a 4-character hexadecimal number if the 16-bit
|
||||
data width option is selected).
|
||||
|
||||
VERIFY Bus: 1 Addr: 49 Subaddr: 04 Wrote: 96 Read: 92 FAILURE
|
||||
|
||||
All values (except the bus numbers) are hexadecimal.
|
||||
|
||||
I2C BUILD CONFIGURATION
|
||||
=======================
|
||||
|
||||
|
|
|
@ -72,10 +72,10 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_bus
|
||||
* Name: i2ccmd_bus
|
||||
****************************************************************************/
|
||||
|
||||
int cmd_bus(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
int i2ccmd_bus(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
{
|
||||
FAR struct i2c_dev_s *dev;
|
||||
int i;
|
||||
|
|
|
@ -118,6 +118,14 @@ int common_args(FAR struct i2ctool_s *i2ctool, FAR char **arg)
|
|||
i2ctool->freq = value;
|
||||
return ret;
|
||||
|
||||
case 'i':
|
||||
i2ctool->autoincr = true;
|
||||
return 1;
|
||||
|
||||
case 'j':
|
||||
i2ctool->autoincr = false;
|
||||
return 1;
|
||||
|
||||
case 'n':
|
||||
i2ctool->start = false;
|
||||
return 1;
|
||||
|
|
|
@ -74,10 +74,10 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_dev
|
||||
* Name: i2ccmd_dev
|
||||
****************************************************************************/
|
||||
|
||||
int cmd_dev(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
int i2ccmd_dev(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
{
|
||||
FAR struct i2c_dev_s *dev;
|
||||
struct i2c_msg_s msg[2];
|
||||
|
|
|
@ -39,6 +39,8 @@
|
|||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
|
||||
#include "i2ctool.h"
|
||||
|
@ -72,33 +74,64 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_get
|
||||
* Name: i2ccmd_get
|
||||
****************************************************************************/
|
||||
|
||||
int cmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
||||
int i2ccmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
||||
{
|
||||
FAR struct i2c_dev_s *dev;
|
||||
struct i2c_msg_s msg[2];
|
||||
union
|
||||
{
|
||||
uint16_t data16;
|
||||
uint8_t data8;
|
||||
} u;
|
||||
|
||||
FAR char *ptr;
|
||||
uint16_t result;
|
||||
uint8_t regaddr;
|
||||
long repititions;
|
||||
int nargs;
|
||||
int argndx;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Parse any command line arguments */
|
||||
|
||||
for (i = 1; i < argc; )
|
||||
for (argndx = 1; argndx < argc; )
|
||||
{
|
||||
nargs = common_args(i2ctool, &argv[i]);
|
||||
/* Break out of the look when the last option has been parsed */
|
||||
|
||||
ptr = argv[argndx];
|
||||
if (*ptr != '-')
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
/* Otherwise, check for common options */
|
||||
|
||||
nargs = common_args(i2ctool, &argv[argndx]);
|
||||
if (nargs < 0)
|
||||
{
|
||||
return ERROR;
|
||||
}
|
||||
i += nargs;
|
||||
argndx += nargs;
|
||||
}
|
||||
|
||||
/* There may be one more thing on the command line: The repitition
|
||||
* count.
|
||||
*/
|
||||
|
||||
repititions = 1;
|
||||
if (argndx < argc)
|
||||
{
|
||||
repititions = strtol(argv[argndx], NULL, 16);
|
||||
if (repititions < 1)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cargrange, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
argndx++;
|
||||
}
|
||||
|
||||
if (argndx != argc)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2ctoomanyargs, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Get a handle to the I2C bus */
|
||||
|
@ -110,16 +143,75 @@ int cmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set the frequency and address (NOTE: Only 7-bit address supported now) */
|
||||
/* Set the frequency and the address (NOTE: Only 7-bit address supported now) */
|
||||
|
||||
I2C_SETFREQUENCY(dev, i2ctool->freq);
|
||||
I2C_SETADDRESS(dev, i2ctool->addr, 7);
|
||||
|
||||
/* Loop for the requested number of repititions */
|
||||
|
||||
regaddr = i2ctool->regaddr;
|
||||
ret = OK;
|
||||
|
||||
for (i = 0; i < repititions; i++)
|
||||
{
|
||||
/* Read from the I2C bus */
|
||||
|
||||
ret = i2ctool_get(i2ctool, dev, regaddr, &result);
|
||||
|
||||
/* Display the result */
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "READ Bus: %d Addr: %02x Subaddr: %02x Value: ",
|
||||
i2ctool->bus, i2ctool->addr, i2ctool->regaddr);
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%02x\n", result);
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%04x\n", result);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Auto-increment the address if so configured */
|
||||
|
||||
if (i2ctool->autoincr)
|
||||
{
|
||||
regaddr++;
|
||||
}
|
||||
}
|
||||
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: i2ctool_get
|
||||
****************************************************************************/
|
||||
|
||||
int i2ctool_get(FAR struct i2ctool_s *i2ctool, FAR struct i2c_dev_s *dev,
|
||||
uint8_t regaddr, uint16_t *result)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
union
|
||||
{
|
||||
uint16_t data16;
|
||||
uint8_t data8;
|
||||
} u;
|
||||
int ret;
|
||||
|
||||
/* Set up data structures */
|
||||
|
||||
msg[0].addr = i2ctool->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = &i2ctool->regaddr;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].addr = i2ctool->addr;
|
||||
|
@ -138,43 +230,28 @@ int cmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
if (i2ctool->start)
|
||||
{
|
||||
ret = I2C_TRANSFER(dev, &msg[0], 1);
|
||||
if (ret < 0)
|
||||
if (ret== OK)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
goto errout;
|
||||
}
|
||||
ret = I2C_TRANSFER(dev, &msg[1], 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
goto errout;
|
||||
ret = I2C_TRANSFER(dev, &msg[1], 1);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = I2C_TRANSFER(dev, msg, 2);
|
||||
if (ret < 0)
|
||||
}
|
||||
|
||||
/* Return the result of the read operation */
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
goto errout;
|
||||
*result = (uint16_t)u.data8;
|
||||
}
|
||||
else
|
||||
{
|
||||
*result = u.data16;
|
||||
}
|
||||
}
|
||||
|
||||
i2ctool_printf(i2ctool, "READ Bus: %d Addr: %02x Subaddr: %02x Value: ",
|
||||
i2ctool->bus, i2ctool->addr, i2ctool->regaddr);
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%02x\n", u.data8);
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%04x\n", u.data16);
|
||||
}
|
||||
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return OK;
|
||||
|
||||
errout:
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return ERROR;
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -64,8 +64,8 @@
|
|||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
static int cmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv);
|
||||
static int cmd_unrecognized(FAR struct i2ctool_s *i2ctool, int argc, char **argv);
|
||||
static int i2ccmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv);
|
||||
static int i2ccmd_unrecognized(FAR struct i2ctool_s *i2ctool, int argc, char **argv);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
|
@ -75,13 +75,14 @@ struct i2ctool_s g_i2ctool;
|
|||
|
||||
static const struct cmdmap_s g_i2ccmds[] =
|
||||
{
|
||||
{ "?", cmd_help, "Show help", NULL },
|
||||
{ "bus", cmd_bus, "List busses", NULL },
|
||||
{ "dev", cmd_dev, "List devices", "[OPTIONS] <first> <last>" },
|
||||
{ "get", cmd_get, "Read register", "[OPTIONS]" },
|
||||
{ "help", cmd_help, "Show help", NULL },
|
||||
{ "set", cmd_set, "Write register", "[OPTIONS] <value>" },
|
||||
{ NULL, NULL, NULL, NULL }
|
||||
{ "?", i2ccmd_help, "Show help ", NULL },
|
||||
{ "bus", i2ccmd_bus, "List busses ", NULL },
|
||||
{ "dev", i2ccmd_dev, "List devices ", "[OPTIONS] <first> <last>" },
|
||||
{ "get", i2ccmd_get, "Read register ", "[OPTIONS] [<repititions>]" },
|
||||
{ "help", i2ccmd_help, "Show help ", NULL },
|
||||
{ "set", i2ccmd_set, "Write register", "[OPTIONS] <value> [<repititions>]" },
|
||||
{ "verf", i2ccmd_verf, "Verify access ", "[OPTIONS] [<value>] [<repititions>]" },
|
||||
{ NULL, NULL, NULL, NULL }
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -103,10 +104,10 @@ const char g_i2cxfrerror[] = "i2ctool: %s: Transfer failed: %d\n";
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_help
|
||||
* Name: i2ccmd_help
|
||||
****************************************************************************/
|
||||
|
||||
static int cmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
static int i2ccmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
{
|
||||
const struct cmdmap_s *ptr;
|
||||
|
||||
|
@ -140,6 +141,9 @@ static int cmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
|||
i2ctool_printf(i2ctool, " [-s|n], send/don't send start between command and data. "
|
||||
"Default: -n Current: %s\n",
|
||||
i2ctool->start ? "-s" : "-n");
|
||||
i2ctool_printf(i2ctool, " [-i|j], Auto increment|don't increment regaddr on repititions. "
|
||||
"Default: NO Current: %s\n",
|
||||
i2ctool->autoincr ? "YES" : "NO");
|
||||
i2ctool_printf(i2ctool, " [-f freq] I2C frequency. "
|
||||
"Default: %d Current: %d\n",
|
||||
CONFIG_I2CTOOL_DEFFREQ, i2ctool->freq);
|
||||
|
@ -156,10 +160,10 @@ static int cmd_help(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
|||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_unrecognized
|
||||
* Name: i2ccmd_unrecognized
|
||||
****************************************************************************/
|
||||
|
||||
static int cmd_unrecognized(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
static int i2ccmd_unrecognized(FAR struct i2ctool_s *i2ctool, int argc, char **argv)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2ccmdnotfound, argv[0]);
|
||||
return ERROR;
|
||||
|
@ -187,7 +191,7 @@ static int i2c_execute(FAR struct i2ctool_s *i2ctool, int argc, char *argv[])
|
|||
/* See if the command is one that we understand */
|
||||
|
||||
cmd = argv[0];
|
||||
handler = cmd_unrecognized;
|
||||
handler = i2ccmd_unrecognized;
|
||||
|
||||
for (cmdmap = g_i2ccmds; cmdmap->cmd; cmdmap++)
|
||||
{
|
||||
|
@ -272,7 +276,7 @@ int i2c_parse(FAR struct i2ctool_s *i2ctool, int argc, char *argv[])
|
|||
* command status.
|
||||
*/
|
||||
|
||||
return cmd_help(i2ctool, 0, NULL);
|
||||
return i2ccmd_help(i2ctool, 0, NULL);
|
||||
}
|
||||
|
||||
/* Parse all of the arguments following the command name. */
|
||||
|
|
|
@ -74,24 +74,20 @@
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cmd_set
|
||||
* Name: i2ccmd_set
|
||||
****************************************************************************/
|
||||
|
||||
int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
||||
int i2ccmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
||||
{
|
||||
FAR struct i2c_dev_s *dev;
|
||||
struct i2c_msg_s msg[2];
|
||||
FAR char *ptr;
|
||||
union
|
||||
{
|
||||
uint16_t data16;
|
||||
uint8_t data8;
|
||||
} u;
|
||||
|
||||
uint8_t regaddr;
|
||||
long value;
|
||||
long repititions;
|
||||
int nargs;
|
||||
int argndx;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Parse any command line arguments */
|
||||
|
||||
|
@ -115,7 +111,7 @@ int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
argndx += nargs;
|
||||
}
|
||||
|
||||
/* There should be exactly one more thing on the command line: The value
|
||||
/* There must be at least one more thing on the command line: The value
|
||||
* to be written.
|
||||
*/
|
||||
|
||||
|
@ -144,6 +140,23 @@ int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
return ERROR;
|
||||
}
|
||||
|
||||
/* There may be one more thing on the command line: The repitition
|
||||
* count.
|
||||
*/
|
||||
|
||||
repititions = 1;
|
||||
if (argndx < argc)
|
||||
{
|
||||
repititions = strtol(argv[argndx], NULL, 16);
|
||||
if (repititions < 1)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cargrange, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
argndx++;
|
||||
}
|
||||
|
||||
if (argndx != argc)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2ctoomanyargs, argv[0]);
|
||||
|
@ -159,23 +172,82 @@ int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set the frequency and address (NOTE: Only 7-bit address supported now) */
|
||||
/* Set the frequency and the address (NOTE: Only 7-bit address supported now) */
|
||||
|
||||
I2C_SETFREQUENCY(dev, i2ctool->freq);
|
||||
I2C_SETADDRESS(dev, i2ctool->addr, 7);
|
||||
|
||||
/* Loop for the requested number of repititions */
|
||||
|
||||
regaddr = i2ctool->regaddr;
|
||||
ret = OK;
|
||||
|
||||
for (i = 0; i < repititions; i++)
|
||||
{
|
||||
/* Write to the I2C bus */
|
||||
|
||||
ret = i2ctool_set(i2ctool, dev, regaddr, (uint16_t)value);
|
||||
|
||||
/* Display the result */
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "WROTE Bus: %d Addr: %02x Subaddr: %02x Value: ",
|
||||
i2ctool->bus, i2ctool->addr, i2ctool->regaddr);
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%02x\n", (int)value);
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%04x\n", (int)value);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Auto-increment the address if so configured */
|
||||
|
||||
if (i2ctool->autoincr)
|
||||
{
|
||||
regaddr++;
|
||||
}
|
||||
}
|
||||
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: i2ctool_set
|
||||
****************************************************************************/
|
||||
|
||||
int i2ctool_set(FAR struct i2ctool_s *i2ctool, FAR struct i2c_dev_s *dev,
|
||||
uint8_t regaddr, uint16_t value)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
union
|
||||
{
|
||||
uint16_t data16;
|
||||
uint8_t data8;
|
||||
} u;
|
||||
int ret;
|
||||
|
||||
/* Set up data structures */
|
||||
|
||||
msg[0].addr = i2ctool->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = &i2ctool->regaddr;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].addr = i2ctool->addr;
|
||||
msg[1].flags = 0;
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
u.data8 = value;
|
||||
u.data8 = (uint8_t)value;
|
||||
msg[1].buffer = &u.data8;
|
||||
msg[1].length = 1;
|
||||
}
|
||||
|
@ -189,43 +261,15 @@ int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
|||
if (i2ctool->start)
|
||||
{
|
||||
ret = I2C_TRANSFER(dev, &msg[0], 1);
|
||||
if (ret < 0)
|
||||
if (ret == OK)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
goto errout;
|
||||
}
|
||||
ret = I2C_TRANSFER(dev, &msg[1], 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
goto errout;
|
||||
ret = I2C_TRANSFER(dev, &msg[1], 1);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = I2C_TRANSFER(dev, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
goto errout;
|
||||
}
|
||||
}
|
||||
|
||||
i2ctool_printf(i2ctool, "WROTE Bus: %d Addr: %02x Subaddr: %02x Value: ",
|
||||
i2ctool->bus, i2ctool->addr, i2ctool->regaddr);
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%02x\n", u.data8);
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%04x\n", u.data16);
|
||||
}
|
||||
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return OK;
|
||||
|
||||
errout:
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return ERROR;
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -0,0 +1,249 @@
|
|||
/****************************************************************************
|
||||
* apps/system/i2c/i2c_verf.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
|
||||
#include "i2ctool.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: i2ccmd_verf
|
||||
****************************************************************************/
|
||||
|
||||
int i2ccmd_verf(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv)
|
||||
{
|
||||
FAR struct i2c_dev_s *dev;
|
||||
FAR char *ptr;
|
||||
uint16_t rdvalue;
|
||||
uint8_t regaddr;
|
||||
bool addrinaddr;
|
||||
long wrvalue;
|
||||
long repititions;
|
||||
int nargs;
|
||||
int argndx;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Parse any command line arguments */
|
||||
|
||||
for (argndx = 1; argndx < argc; )
|
||||
{
|
||||
/* Break out of the look when the last option has been parsed */
|
||||
|
||||
ptr = argv[argndx];
|
||||
if (*ptr != '-')
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
/* Otherwise, check for common options */
|
||||
|
||||
nargs = common_args(i2ctool, &argv[argndx]);
|
||||
if (nargs < 0)
|
||||
{
|
||||
return ERROR;
|
||||
}
|
||||
argndx += nargs;
|
||||
}
|
||||
|
||||
/* The options may be followed by the optional wrvalue to be written. If omitted, then
|
||||
* the register address will be used as the wrvalue, providing an address-in-address
|
||||
* test.
|
||||
*/
|
||||
|
||||
addrinaddr = true;
|
||||
wrvalue = 0;
|
||||
|
||||
if (argndx < argc)
|
||||
{
|
||||
wrvalue = strtol(argv[argndx], NULL, 16);
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
if (wrvalue < 0 || wrvalue > 255)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cargrange, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
else if (wrvalue < 0 || wrvalue > 65535)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cargrange, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
addrinaddr = false;
|
||||
argndx++;
|
||||
}
|
||||
|
||||
/* There may be one more thing on the command line: The repitition
|
||||
* count.
|
||||
*/
|
||||
|
||||
repititions = 1;
|
||||
if (argndx < argc)
|
||||
{
|
||||
repititions = strtol(argv[argndx], NULL, 16);
|
||||
if (repititions < 1)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cargrange, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
argndx++;
|
||||
}
|
||||
|
||||
if (argndx != argc)
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2ctoomanyargs, argv[0]);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Get a handle to the I2C bus */
|
||||
|
||||
dev = up_i2cinitialize(i2ctool->bus);
|
||||
if (!dev)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "Failed to get bus %d\n", i2ctool->bus);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set the frequency and the address (NOTE: Only 7-bit address supported now) */
|
||||
|
||||
I2C_SETFREQUENCY(dev, i2ctool->freq);
|
||||
I2C_SETADDRESS(dev, i2ctool->addr, 7);
|
||||
|
||||
/* Loop for the requested number of repititions */
|
||||
|
||||
regaddr = i2ctool->regaddr;
|
||||
ret = OK;
|
||||
|
||||
for (i = 0; i < repititions; i++)
|
||||
{
|
||||
/* If we are performing an address-in-address test, then use the register
|
||||
* address as the value to write.
|
||||
*/
|
||||
|
||||
if (addrinaddr)
|
||||
{
|
||||
wrvalue = regaddr;
|
||||
}
|
||||
|
||||
/* Write to the I2C bus */
|
||||
|
||||
ret = i2ctool_set(i2ctool, dev, regaddr, (uint16_t)wrvalue);
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Read the value back from the I2C bus */
|
||||
|
||||
ret = i2ctool_get(i2ctool, dev, regaddr, &rdvalue);
|
||||
}
|
||||
|
||||
/* Display the result */
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "VERIFY Bus: %d Addr: %02x Subaddr: %02x Wrote: ",
|
||||
i2ctool->bus, i2ctool->addr, i2ctool->regaddr);
|
||||
|
||||
if (i2ctool->width == 8)
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%02x Read: %02x", (int)wrvalue, (int)rdvalue);
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "%04x Read: %04x", (int)wrvalue, (int)rdvalue);
|
||||
}
|
||||
|
||||
if (wrvalue != rdvalue)
|
||||
{
|
||||
i2ctool_printf(i2ctool, " <<< FAILURE\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, "\n");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
i2ctool_printf(i2ctool, g_i2cxfrerror, argv[0], -ret);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Auto-increment the address if so configured */
|
||||
|
||||
if (i2ctool->autoincr)
|
||||
{
|
||||
regaddr++;
|
||||
}
|
||||
}
|
||||
|
||||
(void)up_i2cuninitialize(dev);
|
||||
return ret;
|
||||
}
|
|
@ -49,6 +49,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
@ -139,7 +141,8 @@ struct i2ctool_s
|
|||
uint8_t bus; /* [-b bus] is the I2C bus number */
|
||||
uint8_t regaddr; /* [-r regaddr] is the I2C device register address */
|
||||
uint8_t width; /* [-w width] is the data width (8 or 16) */
|
||||
bool start; /* [-s|n], send/don't send start between command and data */
|
||||
bool start; /* [-s|n], send|don't send start between command and data */
|
||||
bool autoincr; /* [-i|j], Auto increment|don't increment regaddr on repititions */
|
||||
uint32_t freq; /* [-f freq] I2C frequency */
|
||||
|
||||
/* Output streams */
|
||||
|
@ -184,10 +187,18 @@ void i2ctool_flush(FAR struct i2ctool_s *i2ctool);
|
|||
|
||||
/* Command handlers */
|
||||
|
||||
int cmd_bus(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int cmd_dev(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int cmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int cmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int i2ccmd_bus(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int i2ccmd_dev(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int i2ccmd_get(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int i2ccmd_set(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
int i2ccmd_verf(FAR struct i2ctool_s *i2ctool, int argc, FAR char **argv);
|
||||
|
||||
/* I2C access functions */
|
||||
|
||||
int i2ctool_get(FAR struct i2ctool_s *i2ctool, FAR struct i2c_dev_s *dev,
|
||||
uint8_t addr, uint16_t *result);
|
||||
int i2ctool_set(FAR struct i2ctool_s *i2ctool, FAR struct i2c_dev_s *dev,
|
||||
uint8_t regaddr, uint16_t value);
|
||||
|
||||
/* Common logic */
|
||||
|
||||
|
|
|
@ -2095,3 +2095,8 @@
|
|||
fixing this bug, the Windows chkdsk utility would report these lost chains.
|
||||
* arch/arm/src/stm32/stm32_i2c.c: Driver can now operate in a faster polled
|
||||
mode (at the expense of using more cpu cycles).
|
||||
* arch/arm/src/stm32/stm32_i2c.c: Add trace debug capability. Enabled with
|
||||
CONFIG_I2C_TRACE.
|
||||
* arch/arm/src/stm32/stm32_i2c.c: Fix another bug where I2C conflicts with FSMC
|
||||
being enabled. That time at the tail end of the transaction where there is
|
||||
an unfinished stop condition.
|
||||
|
|
|
@ -122,29 +122,30 @@
|
|||
(SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
|
||||
|
||||
/* Debug ****************************************************************************/
|
||||
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output.
|
||||
*
|
||||
* If CONFIG_I2C_POLLED and CONFIG_DEBUG_VERBOSE are also defined, then some
|
||||
* additinal detailed output is generated. If CONFIG_I2C_POLLED is not defined and
|
||||
* CONFIG_DEBUG_I2CINTS, then output will ge generated from the interrupt handler
|
||||
* as well.
|
||||
*/
|
||||
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */
|
||||
|
||||
#ifdef CONFIG_DEBUG_I2C
|
||||
# define i2cdbg dbg
|
||||
# ifdef CONFIG_I2C_POLLED
|
||||
# define intdbg vdbg
|
||||
# else
|
||||
# ifdef CONFIG_DEBUG_I2CINTS
|
||||
# define intdbg lldbg
|
||||
# else
|
||||
# define intdbg(x...)
|
||||
# endif
|
||||
# endif
|
||||
# define i2cvdbg vdbg
|
||||
#else
|
||||
# undef CONFIG_DEBUG_I2CINTS
|
||||
# define i2cdbg(x...)
|
||||
# define intdbg(x...)
|
||||
# define i2cvdbg(x...)
|
||||
#endif
|
||||
|
||||
/* I2C event trace logic. NOTE: trace uses the internal, non-standard, low-level
|
||||
* debug interface lib_rawprintf() but does not require that any other debug
|
||||
* is enabled.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_I2C_TRACE
|
||||
# define stm32_i2c_tracereset(p)
|
||||
# define stm32_i2c_tracenew(p,s)
|
||||
# define stm32_i3c_traceevent(p,e,a)
|
||||
# define stm32_i2c_tracedump(p)
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_I2C_NTRACE
|
||||
# define CONFIG_I2C_NTRACE 20
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -159,6 +160,33 @@ enum stm32_intstate_e
|
|||
INTSTATE_DONE, /* Interrupt activity complete */
|
||||
};
|
||||
|
||||
/* Trace events */
|
||||
|
||||
enum stm32_trace_e
|
||||
{
|
||||
I2CEVENT_NONE = 0, /* No events have occurred with this status */
|
||||
I2CEVENT_SB, /* Start/Master, param = msgc */
|
||||
I2CEVENT_SENDBYTE, /* Send byte, param = byte sent */
|
||||
I2CEVENT_READ, /* Read data, param = dcnt */
|
||||
I2CEVENT_ITBUFEN, /* Enable buffer interrupts, param = 0 */
|
||||
I2CEVENT_RXNE, /* Read more dta, param = dcnt */
|
||||
I2CEVENT_REITBUFEN, /* Re-enable buffer interrupts, param = 0 */
|
||||
I2CEVENT_DISITBUFEN, /* Disable buffer interrupts, param = 0 */
|
||||
I2CEVENT_BTFSTART, /* Last byte sent, re-starting, param = msgc */
|
||||
I2CEVENT_BTFSTOP, /* Last byte sten, send stop, param = 0 */
|
||||
I2CEVENT_ERROR /* Error occurred, param = 0 */
|
||||
};
|
||||
|
||||
/* Trace data */
|
||||
|
||||
struct stm32_trace_s
|
||||
{
|
||||
uint32_t status; /* I2C 32-bit SR2|SR1 status */
|
||||
uint32_t count; /* Interrupt count when status change */
|
||||
enum stm32_intstate_e event; /* Last event that occurred with this status */
|
||||
uint32_t parm; /* Parameter associated with the event */
|
||||
};
|
||||
|
||||
/* I2C Device Private Data */
|
||||
|
||||
struct stm32_i2c_priv_s
|
||||
|
@ -177,6 +205,18 @@ struct stm32_i2c_priv_s
|
|||
int dcnt; /* Current message length */
|
||||
uint16_t flags; /* Current message flags */
|
||||
|
||||
/* I2C trace support */
|
||||
|
||||
#ifdef CONFIG_I2C_TRACE
|
||||
int tndx; /* Trace array index */
|
||||
uint32_t isr_count; /* Count of ISRs processed */
|
||||
uint32_t old_status; /* Last 32-bit status value */
|
||||
|
||||
/* The actual trace data */
|
||||
|
||||
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
|
||||
#endif
|
||||
|
||||
uint32_t status; /* End of transfer SR2|SR1 status */
|
||||
};
|
||||
|
||||
|
@ -203,11 +243,19 @@ static inline void stm32_i2c_putreg(FAR struct stm32_i2c_priv_s *priv, uint8_t o
|
|||
static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
|
||||
uint8_t offset, uint16_t clearbits,
|
||||
uint16_t setbits);
|
||||
static void inline stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
|
||||
static int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev);
|
||||
static void inline stm32_i2c_sem_post(FAR struct i2c_dev_s *dev);
|
||||
static void inline stm32_i2c_sem_init(FAR struct i2c_dev_s *dev);
|
||||
static void inline stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev);
|
||||
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
|
||||
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_init(FAR struct i2c_dev_s *dev);
|
||||
static inline void stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev);
|
||||
#ifdef CONFIG_I2C_TRACE
|
||||
static void stm32_i2c_tracereset(FAR struct stm32_i2c_priv_s *priv);
|
||||
static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t status);
|
||||
static void stm32_i3c_traceevent(FAR struct stm32_i2c_priv_s *priv,
|
||||
enum stm32_trace_e event, uint32_t parm);
|
||||
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
|
||||
#endif
|
||||
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
|
||||
uint32_t frequency);
|
||||
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
|
||||
|
@ -356,7 +404,7 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void inline stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
|
||||
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
|
||||
{
|
||||
while (sem_wait(&((struct stm32_i2c_inst_s *)dev)->priv->sem_excl) != 0)
|
||||
{
|
||||
|
@ -365,7 +413,7 @@ static void inline stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
|
|||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_i2c_sem_waitisr
|
||||
* Name: stm32_i2c_sem_waitdone
|
||||
*
|
||||
* Description:
|
||||
* Wait for a transfer to complete
|
||||
|
@ -373,9 +421,8 @@ static void inline stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
|
|||
************************************************************************************/
|
||||
|
||||
#ifndef CONFIG_I2C_POLLED
|
||||
static int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
||||
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
|
||||
{
|
||||
FAR struct stm32_i2c_priv_s *priv = ((struct stm32_i2c_inst_s *)dev)->priv;
|
||||
struct timespec abstime;
|
||||
irqstate_t flags;
|
||||
uint32_t regval;
|
||||
|
@ -446,9 +493,8 @@ static int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
|||
return ret;
|
||||
}
|
||||
#else
|
||||
int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
||||
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
|
||||
{
|
||||
FAR struct stm32_i2c_priv_s *priv = ((struct stm32_i2c_inst_s *)dev)->priv;
|
||||
uint32_t start;
|
||||
uint32_t elapsed;
|
||||
int ret;
|
||||
|
@ -458,9 +504,9 @@ int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
|||
* sem_timedwait() sleeps.
|
||||
*/
|
||||
|
||||
priv->intstate = INTSTATE_WAITING;
|
||||
start = clock_systimer();
|
||||
do
|
||||
priv->intstate = INTSTATE_WAITING;
|
||||
start = clock_systimer();
|
||||
do
|
||||
{
|
||||
/* Poll by simply calling the timer interrupt handler until it
|
||||
* reports that it is done.
|
||||
|
@ -473,10 +519,13 @@ int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
|||
elapsed = clock_systimer() - start;
|
||||
}
|
||||
|
||||
/* Loop until the interrupt level transfer is complete. */
|
||||
/* Loop until the transfer is complete. */
|
||||
|
||||
while (priv->intstate != INTSTATE_DONE && elapsed < CONFIG_STM32_I2CTIMEOTICKS);
|
||||
|
||||
i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n",
|
||||
priv->intstate, elapsed, CONFIG_STM32_I2CTIMEOTICKS, priv->status);
|
||||
|
||||
/* Set the interrupt state back to IDLE */
|
||||
|
||||
ret = priv->intstate == INTSTATE_DONE ? OK : -ETIMEDOUT;
|
||||
|
@ -485,6 +534,62 @@ int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
|||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_i2c_sem_waitstop
|
||||
*
|
||||
* Description:
|
||||
* Wait for a STOP to complete
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
|
||||
{
|
||||
uint32_t start;
|
||||
uint32_t elapsed;
|
||||
uint32_t cr1;
|
||||
uint32_t sr1;
|
||||
|
||||
/* 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
|
||||
* cleared by software, cleared by hardware when a Stop condition is
|
||||
* detected, set by hardware when a timeout error is detected."
|
||||
*/
|
||||
|
||||
start = clock_systimer();
|
||||
do
|
||||
{
|
||||
/* Check for STOP condition */
|
||||
|
||||
cr1 = stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET);
|
||||
if ((cr1 & I2C_CR1_STOP) == 0)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
/* Check for timeout error */
|
||||
|
||||
sr1 = stm32_i2c_getreg(priv, STM32_I2C_SR1_OFFSET);
|
||||
if ((sr1 & I2C_SR1_TIMEOUT) != 0)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
/* Calculate the elapsed time */
|
||||
|
||||
elapsed = clock_systimer() - start;
|
||||
}
|
||||
|
||||
/* Loop until the stop is complete or a timeout occurs. */
|
||||
|
||||
while (elapsed < CONFIG_STM32_I2CTIMEOTICKS);
|
||||
|
||||
/* If we get here then a timeout occurred with the STOP condition
|
||||
* still pending.
|
||||
*/
|
||||
|
||||
i2cvdbg("Timeout with CR1: %04x SR1: %04x\n", cr1, sr1);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_i2c_sem_post
|
||||
*
|
||||
|
@ -493,7 +598,7 @@ int inline stm32_i2c_sem_waitisr(FAR struct i2c_dev_s *dev)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void inline stm32_i2c_sem_post(FAR struct i2c_dev_s *dev)
|
||||
static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev)
|
||||
{
|
||||
sem_post( &((struct stm32_i2c_inst_s *)dev)->priv->sem_excl );
|
||||
}
|
||||
|
@ -506,7 +611,7 @@ static void inline stm32_i2c_sem_post(FAR struct i2c_dev_s *dev)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void inline stm32_i2c_sem_init(FAR struct i2c_dev_s *dev)
|
||||
static inline void stm32_i2c_sem_init(FAR struct i2c_dev_s *dev)
|
||||
{
|
||||
sem_init(&((struct stm32_i2c_inst_s *)dev)->priv->sem_excl, 0, 1);
|
||||
#ifndef CONFIG_I2C_POLLED
|
||||
|
@ -522,7 +627,7 @@ static void inline stm32_i2c_sem_init(FAR struct i2c_dev_s *dev)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void inline stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev)
|
||||
static inline void stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev)
|
||||
{
|
||||
sem_destroy(&((struct stm32_i2c_inst_s *)dev)->priv->sem_excl);
|
||||
#ifndef CONFIG_I2C_POLLED
|
||||
|
@ -530,6 +635,77 @@ static void inline stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev)
|
|||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_i2c_trace*
|
||||
*
|
||||
* Description:
|
||||
* I2C trace instrumentation
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_I2C_TRACE
|
||||
static void stm32_i2c_tracereset(FAR struct stm32_i2c_priv_s *priv)
|
||||
{
|
||||
/* Reset the trace info for a new data collection */
|
||||
|
||||
priv->isr_count = 0;
|
||||
priv->old_status = 0xffffffff;
|
||||
priv->tndx = -1;
|
||||
}
|
||||
|
||||
static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t status)
|
||||
{
|
||||
/* Increment the cout of interrupts received */
|
||||
|
||||
priv->isr_count++;
|
||||
|
||||
/* Has the status changed from the last interrupt */
|
||||
|
||||
if (status != priv->old_status)
|
||||
{
|
||||
/* Yes.. bump up the trace index (unless we are out of trace entries) */
|
||||
|
||||
if (priv->tndx < CONFIG_I2C_NTRACE)
|
||||
{
|
||||
priv->tndx++;
|
||||
}
|
||||
|
||||
/* Initialize the new trace entry */
|
||||
|
||||
priv->trace[priv->tndx].status = status;
|
||||
priv->trace[priv->tndx].count = priv->isr_count;
|
||||
priv->trace[priv->tndx].event = I2CEVENT_NONE;
|
||||
priv->trace[priv->tndx].parm = 0;
|
||||
priv->old_status = status;
|
||||
}
|
||||
}
|
||||
|
||||
static void stm32_i3c_traceevent(FAR struct stm32_i2c_priv_s *priv,
|
||||
enum stm32_trace_e event, uint32_t parm)
|
||||
{
|
||||
/* Add the event to the trace entry (possibly overwriting a previous trace
|
||||
* event.
|
||||
*/
|
||||
|
||||
priv->trace[priv->tndx].event = event;
|
||||
priv->trace[priv->tndx].parm = parm;
|
||||
}
|
||||
|
||||
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* Dump all of the buffered trace entries */
|
||||
|
||||
for (i = 0; i < priv->tndx; i++)
|
||||
{
|
||||
lib_rawprintf("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x\n", i,
|
||||
priv->trace[i].status, priv->trace[i].count,
|
||||
priv->trace[i].event, priv->trace[i].parm);
|
||||
}
|
||||
}
|
||||
#endif /* CONFIG_I2C_TRACE */
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_i2c_setclock
|
||||
*
|
||||
|
@ -772,22 +948,16 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
{
|
||||
uint32_t status = stm32_i2c_getstatus(priv);
|
||||
|
||||
#ifdef CONFIG_DEBUG_I2CINTS
|
||||
static uint32_t isr_count = 0;
|
||||
static uint32_t old_status = 0xffff;
|
||||
isr_count++;
|
||||
/* Check for new trace setup */
|
||||
|
||||
if (old_status != status)
|
||||
{
|
||||
intdbg("status = %8x, count=%d\n", status, isr_count); fflush(stdout);
|
||||
old_status = status;
|
||||
}
|
||||
#endif
|
||||
stm32_i2c_tracenew(priv, status);
|
||||
|
||||
/* Was start bit sent */
|
||||
|
||||
if ((status & I2C_SR1_SB) != 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_SB, priv->msgc);
|
||||
|
||||
/* Get run-time data */
|
||||
|
||||
priv->ptr = priv->msgv->buffer;
|
||||
|
@ -824,11 +994,13 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
|
||||
else if ((priv->flags & I2C_M_READ) == 0 && (status & (I2C_SR1_ADDR | I2C_SR1_TXE)) != 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_READ, priv->dcnt);
|
||||
|
||||
if (--priv->dcnt >= 0)
|
||||
{
|
||||
/* Send a byte */
|
||||
|
||||
intdbg("Send byte: %2x\n", *priv->ptr);
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_SENDBYTE, *priv->ptr);
|
||||
stm32_i2c_putreg(priv, STM32_I2C_DR_OFFSET, *priv->ptr++);
|
||||
}
|
||||
}
|
||||
|
@ -838,6 +1010,7 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
/* Enable RxNE and TxE buffers in order to receive one or multiple bytes */
|
||||
|
||||
#ifndef CONFIG_I2C_POLLED
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_ITBUFEN, 0);
|
||||
stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, 0, I2C_CR2_ITBUFEN);
|
||||
#endif
|
||||
}
|
||||
|
@ -848,11 +1021,10 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
{
|
||||
/* Read a byte, if dcnt goes < 0, then read dummy bytes to ack ISRs */
|
||||
|
||||
intdbg("dcnt=%d\n", priv->dcnt);
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_RXNE, priv->dcnt);
|
||||
if (--priv->dcnt >= 0)
|
||||
{
|
||||
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
|
||||
intdbg("Received: %2x\n", *(priv->ptr-1) );
|
||||
|
||||
/* Disable acknowledge when last byte is to be received */
|
||||
|
||||
|
@ -870,10 +1042,12 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
#ifndef CONFIG_I2C_POLLED
|
||||
if (priv->dcnt > 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_REITBUFEN, 0);
|
||||
stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, 0, I2C_CR2_ITBUFEN);
|
||||
}
|
||||
else if (priv->dcnt == 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_DISITBUFEN, 0);
|
||||
stm32_i2c_modifyreg(priv, STM32_I2C_CR2_OFFSET, I2C_CR2_ITBUFEN, 0);
|
||||
}
|
||||
#endif
|
||||
|
@ -882,7 +1056,6 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
|
||||
if (priv->dcnt <= 0 && (status & I2C_SR1_BTF) != 0)
|
||||
{
|
||||
intdbg("BTF\n");
|
||||
stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET); /* ACK ISR */
|
||||
|
||||
/* Do we need to terminate or restart after this byte?
|
||||
|
@ -895,6 +1068,7 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
|
||||
if (priv->msgc > 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_BTFSTART, priv->msgc);
|
||||
if (priv->msgv->flags & I2C_M_NORESTART)
|
||||
{
|
||||
priv->ptr = priv->msgv->buffer;
|
||||
|
@ -916,7 +1090,7 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
}
|
||||
else if (priv->msgv)
|
||||
{
|
||||
intdbg("stop2: status = %8x\n", status);
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_BTFSTOP, 0);
|
||||
stm32_i2c_sendstop(priv);
|
||||
|
||||
/* Is there a thread waiting for this event (there should be) */
|
||||
|
@ -948,6 +1122,8 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
|
|||
|
||||
if ((status & I2C_SR1_ERRORMASK) != 0)
|
||||
{
|
||||
stm32_i3c_traceevent(priv, I2CEVENT_ERROR, 0);
|
||||
|
||||
/* Clear interrupt flags */
|
||||
|
||||
stm32_i2c_putreg(priv, STM32_I2C_SR1_OFFSET, 0);
|
||||
|
@ -1216,46 +1392,30 @@ static int stm32_i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits)
|
|||
|
||||
static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count)
|
||||
{
|
||||
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;
|
||||
uint32_t status = 0;
|
||||
uint32_t ahbenr;
|
||||
uint16_t regval;
|
||||
int status_errno = 0;
|
||||
int errval = 0;
|
||||
|
||||
ASSERT(count);
|
||||
|
||||
/* Disable FSMC that shares a pin with I2C1 (LBAR) */
|
||||
|
||||
ahbenr = stm32_i2c_disablefsmc(inst->priv);
|
||||
ahbenr = stm32_i2c_disablefsmc(priv);
|
||||
|
||||
/* 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
|
||||
* cleared by software, cleared by hardware when a Stop condition is
|
||||
* detected, set by hardware when a timeout error is detected."
|
||||
/* 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
|
||||
* will not complete normally if the FSMC is enabled.
|
||||
*/
|
||||
|
||||
for (;;)
|
||||
{
|
||||
/* Check for STOP condition */
|
||||
|
||||
regval = stm32_i2c_getreg(inst->priv, STM32_I2C_CR1_OFFSET);
|
||||
if ((regval & I2C_CR1_STOP) == 0)
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
/* Check for timeout error */
|
||||
|
||||
regval = stm32_i2c_getreg(inst->priv, STM32_I2C_SR1_OFFSET);
|
||||
if ((regval & I2C_SR1_TIMEOUT) != 0)
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
#ifndef CONFIG_STM32_I2C1
|
||||
stm32_i2c_sem_waitstop(priv);
|
||||
#endif
|
||||
|
||||
/* Clear any pending error interrupts */
|
||||
|
||||
stm32_i2c_putreg(inst->priv, STM32_I2C_SR1_OFFSET, 0);
|
||||
stm32_i2c_putreg(priv, STM32_I2C_SR1_OFFSET, 0);
|
||||
|
||||
/* "Note: When the STOP, START or PEC bit is set, the software must
|
||||
* not perform any write access to I2C_CR1 before this bit is
|
||||
|
@ -1264,31 +1424,39 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
* not cleared by hardware, then we will have to do that from hardware.
|
||||
*/
|
||||
|
||||
stm32_i2c_clrstart(inst->priv);
|
||||
stm32_i2c_clrstart(priv);
|
||||
|
||||
/* Old transfers are done */
|
||||
|
||||
inst->priv->msgv = msgs;
|
||||
inst->priv->msgc = count;
|
||||
priv->msgv = msgs;
|
||||
priv->msgc = count;
|
||||
|
||||
/* Reset I2C trace logic */
|
||||
|
||||
stm32_i2c_tracereset(priv);
|
||||
|
||||
/* Set I2C clock frequency (on change it toggles I2C_CR1_PE !) */
|
||||
|
||||
stm32_i2c_setclock(inst->priv, inst->frequency);
|
||||
stm32_i2c_setclock(priv, inst->frequency);
|
||||
|
||||
/* Trigger start condition, then the process moves into the ISR. I2C
|
||||
* interrupts will be enabled within stm32_i2c_waitisr().
|
||||
* interrupts will be enabled within stm32_i2c_waitdone().
|
||||
*/
|
||||
|
||||
stm32_i2c_sendstart(inst->priv);
|
||||
priv->status = 0;
|
||||
stm32_i2c_sendstart(priv);
|
||||
|
||||
/* Wait for an ISR, if there was a timeout, fetch latest status to get
|
||||
* the BUSY flag.
|
||||
*/
|
||||
|
||||
if (stm32_i2c_sem_waitisr(dev) == ERROR)
|
||||
if (stm32_i2c_sem_waitdone(priv) == ERROR)
|
||||
{
|
||||
status = stm32_i2c_getstatus(inst->priv);
|
||||
status_errno = ETIMEDOUT;
|
||||
status = stm32_i2c_getstatus(priv);
|
||||
errval = ETIMEDOUT;
|
||||
|
||||
i2cdbg("Timed out: CR1: %04x status: %08x\n",
|
||||
stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET), status);
|
||||
|
||||
/* "Note: When the STOP, START or PEC bit is set, the software must
|
||||
* not perform any write access to I2C_CR1 before this bit is
|
||||
|
@ -1296,13 +1464,13 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
* second STOP, START or PEC request."
|
||||
*/
|
||||
|
||||
stm32_i2c_clrstart(inst->priv);
|
||||
stm32_i2c_clrstart(priv);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* clear SR2 (BUSY flag) as we've done successfully */
|
||||
|
||||
status = inst->priv->status & 0xffff;
|
||||
status = priv->status & 0xffff;
|
||||
}
|
||||
|
||||
/* Check for error status conditions */
|
||||
|
@ -1315,37 +1483,37 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
{
|
||||
/* Bus Error */
|
||||
|
||||
status_errno = EIO;
|
||||
errval = EIO;
|
||||
}
|
||||
else if (status & I2C_SR1_ARLO)
|
||||
{
|
||||
/* Arbitration Lost (master mode) */
|
||||
|
||||
status_errno = EAGAIN;
|
||||
errval = EAGAIN;
|
||||
}
|
||||
else if (status & I2C_SR1_AF)
|
||||
{
|
||||
/* Acknowledge Failure */
|
||||
|
||||
status_errno = ENXIO;
|
||||
errval = ENXIO;
|
||||
}
|
||||
else if (status & I2C_SR1_OVR)
|
||||
{
|
||||
/* Overrun/Underrun */
|
||||
|
||||
status_errno = EIO;
|
||||
errval = EIO;
|
||||
}
|
||||
else if (status & I2C_SR1_PECERR)
|
||||
{
|
||||
/* PEC Error in reception */
|
||||
|
||||
status_errno = EPROTO;
|
||||
errval = EPROTO;
|
||||
}
|
||||
else if (status & I2C_SR1_TIMEOUT)
|
||||
{
|
||||
/* Timeout or Tlow Error */
|
||||
|
||||
status_errno = ETIME;
|
||||
errval = ETIME;
|
||||
}
|
||||
|
||||
/* This is not an error and should never happen since SMBus is not enabled */
|
||||
|
@ -1356,13 +1524,13 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
* that want to trade their ability to master for a pin.
|
||||
*/
|
||||
|
||||
status_errno = EINTR;
|
||||
errval = EINTR;
|
||||
}
|
||||
}
|
||||
|
||||
/* This is not an error, but should not happen. The BUSY signal can hang,
|
||||
* however, if there are unhealthy devices on the bus that need to be reset.
|
||||
* NOTE: We will only see this buy indication if stm32_i2c_sem_waitisr()
|
||||
* NOTE: We will only see this buy indication if stm32_i2c_sem_waitdone()
|
||||
* fails above; Otherwise it is cleared.
|
||||
*/
|
||||
|
||||
|
@ -1370,16 +1538,28 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
{
|
||||
/* I2C Bus is for some reason busy */
|
||||
|
||||
status_errno = EBUSY;
|
||||
errval = EBUSY;
|
||||
}
|
||||
|
||||
/* Dump the trace result */
|
||||
|
||||
stm32_i2c_tracedump(priv);
|
||||
|
||||
/* 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
|
||||
* will not complete normally if the FSMC is enabled.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_STM32_I2C1
|
||||
stm32_i2c_sem_waitstop(priv);
|
||||
#endif
|
||||
|
||||
/* Re-enable the FSMC */
|
||||
|
||||
stm32_i2c_enablefsmc(ahbenr);
|
||||
stm32_i2c_sem_post(dev);
|
||||
|
||||
errno = status_errno;
|
||||
return -status_errno;
|
||||
return -errval;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
|
|
Loading…
Reference in New Issue