forked from Archive/PX4-Autopilot
I2C changes for upstream NuttX per trasaction freq control
This commit is contained in:
parent
0177e250f4
commit
dcc2d1c3d1
|
@ -44,6 +44,10 @@
|
|||
|
||||
namespace device
|
||||
{
|
||||
/*
|
||||
* N.B. By defaulting the value of _bus_clocks to non Zero
|
||||
* All calls to init() will NOT set the buss frequency
|
||||
*/
|
||||
|
||||
unsigned int I2C::_bus_clocks[3] = { 100000, 100000, 100000 };
|
||||
|
||||
|
@ -128,12 +132,6 @@ I2C::init()
|
|||
goto out;
|
||||
}
|
||||
|
||||
// set the bus frequency on the first access if it has
|
||||
// not been set yet
|
||||
if (_bus_clocks[bus_index] == 0) {
|
||||
_bus_clocks[bus_index] = _frequency;
|
||||
}
|
||||
|
||||
// set frequency for this instance once to the bus speed
|
||||
// the bus speed is the maximum supported by all devices on the bus,
|
||||
// as we have to prioritize performance over compatibility.
|
||||
|
@ -143,7 +141,12 @@ I2C::init()
|
|||
// This is necessary as automatically lowering the bus speed
|
||||
// for maximum compatibility could induce timing issues on
|
||||
// critical sensors the adopter might be unaware of.
|
||||
I2C_SETFREQUENCY(_dev, _bus_clocks[bus_index]);
|
||||
|
||||
// set the bus frequency on the first access if it has
|
||||
// not been set yet
|
||||
if (_bus_clocks[bus_index] == 0) {
|
||||
_bus_clocks[bus_index] = _frequency;
|
||||
}
|
||||
|
||||
// call the probe function to check whether the device is present
|
||||
ret = probe();
|
||||
|
@ -196,6 +199,7 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
|
|||
msgs = 0;
|
||||
|
||||
if (send_len > 0) {
|
||||
msgv[msgs].frequency = _bus_clocks[_bus - 1];
|
||||
msgv[msgs].addr = _address;
|
||||
msgv[msgs].flags = 0;
|
||||
msgv[msgs].buffer = const_cast<uint8_t *>(send);
|
||||
|
@ -204,6 +208,7 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
|
|||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
msgv[msgs].frequency = _bus_clocks[_bus - 1];;
|
||||
msgv[msgs].addr = _address;
|
||||
msgv[msgs].flags = I2C_M_READ;
|
||||
msgv[msgs].buffer = recv;
|
||||
|
@ -224,7 +229,7 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
|
|||
|
||||
/* if we have already retried once, or we are going to give up, then reset the bus */
|
||||
if ((retry_count >= 1) || (retry_count >= _retries)) {
|
||||
up_i2creset(_dev);
|
||||
I2C_RESET(_dev);
|
||||
}
|
||||
|
||||
} while (retry_count++ < _retries);
|
||||
|
@ -239,8 +244,9 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
|
|||
int ret;
|
||||
unsigned retry_count = 0;
|
||||
|
||||
/* force the device address into the message vector */
|
||||
/* force the device address and Frequency into the message vector */
|
||||
for (unsigned i = 0; i < msgs; i++) {
|
||||
msgv[i].frequency = _bus_clocks[_bus - 1];
|
||||
msgv[i].addr = _address;
|
||||
}
|
||||
|
||||
|
@ -255,7 +261,7 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
|
|||
|
||||
/* if we have already retried once, or we are going to give up, then reset the bus */
|
||||
if ((retry_count >= 1) || (retry_count >= _retries)) {
|
||||
up_i2creset(_dev);
|
||||
I2C_RESET(_dev);
|
||||
}
|
||||
|
||||
} while (retry_count++ < _retries);
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
|
|
|
@ -46,14 +46,17 @@
|
|||
#error "Devices not supported in ROS"
|
||||
|
||||
#elif defined (__PX4_NUTTX)
|
||||
__BEGIN_DECLS
|
||||
|
||||
/*
|
||||
* Building for NuttX
|
||||
*/
|
||||
#include <px4_config.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <chip.h>
|
||||
|
@ -64,7 +67,8 @@
|
|||
|
||||
#define px4_i2c_msg_t i2c_msg_s
|
||||
|
||||
typedef struct i2c_dev_s px4_i2c_dev_t;
|
||||
typedef struct i2c_master_s px4_i2c_dev_t;
|
||||
__END_DECLS
|
||||
|
||||
#elif defined(__PX4_POSIX)
|
||||
#include <stdint.h>
|
||||
|
@ -74,11 +78,13 @@ typedef struct i2c_dev_s px4_i2c_dev_t;
|
|||
#define I2C_M_NORESTART 0x0080 /* message should not begin with (re-)start of transfer */
|
||||
|
||||
// NOTE - This is a copy of the NuttX i2c_msg_s structure
|
||||
|
||||
typedef struct {
|
||||
uint16_t addr; /* Slave address */
|
||||
uint16_t flags; /* See I2C_M_* definitions */
|
||||
uint8_t *buffer;
|
||||
int length;
|
||||
uint32_t frequency; /* I2C frequency */
|
||||
uint16_t addr; /* Slave address (7- or 10-bit) */
|
||||
uint16_t flags; /* See I2C_M_* definitions */
|
||||
uint8_t *buffer; /* Buffer to be transferred */
|
||||
ssize_t length; /* Length of the buffer in bytes */
|
||||
} px4_i2c_msg_t;
|
||||
|
||||
// NOTE - This is a copy of the NuttX i2c_ops_s structure
|
||||
|
@ -86,10 +92,6 @@ typedef struct {
|
|||
const struct px4_i2c_ops_t *ops; /* I2C vtable */
|
||||
} px4_i2c_dev_t;
|
||||
|
||||
// FIXME - Empty defines for I2C ops
|
||||
// Original version commented out
|
||||
//#define I2C_SETFREQUENCY(d,f) ((d)->ops->setfrequency(d,f))
|
||||
#define I2C_SETFREQUENCY(d,f)
|
||||
//#define SPI_SELECT(d,id,s) ((d)->ops->select(d,id,s))
|
||||
#define SPI_SELECT(d,id,s)
|
||||
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
|
@ -68,7 +68,7 @@ __EXPORT int i2c_main(int argc, char *argv[]);
|
|||
|
||||
static int transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len);
|
||||
|
||||
static struct i2c_dev_s *i2c;
|
||||
static struct i2c_master_s *i2c;
|
||||
|
||||
int i2c_main(int argc, char *argv[])
|
||||
{
|
||||
|
@ -110,6 +110,7 @@ transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsig
|
|||
msgs = 0;
|
||||
|
||||
if (send_len > 0) {
|
||||
msgv[msgs].frequency = 400000;
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = 0;
|
||||
msgv[msgs].buffer = send;
|
||||
|
@ -118,6 +119,7 @@ transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsig
|
|||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
msgv[msgs].frequency = 400000;
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = I2C_M_READ;
|
||||
msgv[msgs].buffer = recv;
|
||||
|
@ -129,12 +131,6 @@ transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsig
|
|||
return -1;
|
||||
}
|
||||
|
||||
/*
|
||||
* I2C architecture means there is an unavoidable race here
|
||||
* if there are any devices on the bus with a different frequency
|
||||
* preference. Really, this is pointless.
|
||||
*/
|
||||
I2C_SETFREQUENCY(i2c, 400000);
|
||||
ret = I2C_TRANSFER(i2c, &msgv[0], msgs);
|
||||
|
||||
// reset the I2C bus to unwedge on error
|
||||
|
|
|
@ -63,8 +63,8 @@
|
|||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/mtd.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
|
||||
#include "systemlib/perf_counter.h"
|
||||
|
||||
|
@ -146,7 +146,7 @@
|
|||
|
||||
struct at24c_dev_s {
|
||||
struct mtd_dev_s mtd; /* MTD interface */
|
||||
FAR struct i2c_dev_s *dev; /* Saved I2C interface instance */
|
||||
FAR struct i2c_master_s *dev; /* Saved I2C interface instance */
|
||||
uint8_t addr; /* I2C address */
|
||||
uint16_t pagesize; /* 32, 63 */
|
||||
uint16_t npages; /* 128, 256, 512, 1024 */
|
||||
|
@ -193,6 +193,7 @@ static int at24c_eraseall(FAR struct at24c_dev_s *priv)
|
|||
|
||||
struct i2c_msg_s msgv[1] = {
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &buf[0],
|
||||
|
@ -208,7 +209,7 @@ static int at24c_eraseall(FAR struct at24c_dev_s *priv)
|
|||
buf[0] = (offset >> 8) & 0xff;
|
||||
|
||||
while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) {
|
||||
fvdbg("erase stall\n");
|
||||
fwarn("erase stall\n");
|
||||
usleep(10000);
|
||||
}
|
||||
}
|
||||
|
@ -242,16 +243,16 @@ void at24c_test(void)
|
|||
|
||||
if (result == ERROR) {
|
||||
if (errors++ > 2) {
|
||||
vdbg("too many errors\n");
|
||||
syslog(LOG_INFO, "too many errors\n");
|
||||
return;
|
||||
}
|
||||
|
||||
} else if (result != 1) {
|
||||
vdbg("unexpected %u\n", result);
|
||||
syslog(LOG_INFO, "unexpected %u\n", result);
|
||||
}
|
||||
|
||||
if ((count % 100) == 0) {
|
||||
vdbg("test %u errors %u\n", count, errors);
|
||||
syslog(LOG_INFO, "test %u errors %u\n", count, errors);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -270,12 +271,14 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
|
|||
|
||||
struct i2c_msg_s msgv[2] = {
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &addr[0],
|
||||
.length = sizeof(addr),
|
||||
},
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = 0,
|
||||
|
@ -289,7 +292,7 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
|
|||
#endif
|
||||
blocksleft = nblocks;
|
||||
|
||||
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
if (startblock >= priv->npages) {
|
||||
return 0;
|
||||
|
@ -317,7 +320,7 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
|
|||
break;
|
||||
}
|
||||
|
||||
fvdbg("read stall");
|
||||
finfo("read stall");
|
||||
usleep(1000);
|
||||
|
||||
/* We should normally only be here on the first read after
|
||||
|
@ -362,6 +365,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
|
|||
|
||||
struct i2c_msg_s msgv[1] = {
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &buf[0],
|
||||
|
@ -383,7 +387,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
|
|||
nblocks = priv->npages - startblock;
|
||||
}
|
||||
|
||||
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
while (blocksleft-- > 0) {
|
||||
uint16_t offset = startblock * priv->pagesize;
|
||||
|
@ -403,7 +407,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
|
|||
break;
|
||||
}
|
||||
|
||||
fvdbg("write stall");
|
||||
finfo("write stall");
|
||||
usleep(1000);
|
||||
|
||||
/* We expect to see a number of retries per write cycle as we
|
||||
|
@ -435,7 +439,7 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
|
|||
FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
|
||||
int ret = -EINVAL; /* Assume good command with bad parameters */
|
||||
|
||||
fvdbg("cmd: %d \n", cmd);
|
||||
finfo("cmd: %d \n", cmd);
|
||||
|
||||
switch (cmd) {
|
||||
case MTDIOC_GEOMETRY: {
|
||||
|
@ -474,7 +478,7 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
|
|||
#endif
|
||||
ret = OK;
|
||||
|
||||
fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
|
||||
finfo("blocksize: %d erasesize: %d neraseblocks: %d\n",
|
||||
geo->blocksize, geo->erasesize, geo->neraseblocks);
|
||||
}
|
||||
}
|
||||
|
@ -507,11 +511,11 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
|
||||
FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_master_s *dev)
|
||||
{
|
||||
FAR struct at24c_dev_s *priv;
|
||||
|
||||
fvdbg("dev: %p\n", dev);
|
||||
finfo("dev: %p\n", dev);
|
||||
|
||||
/* Allocate a state structure (we allocate the structure instead of using
|
||||
* a fixed, static allocation so that we can handle multiple FLASH devices.
|
||||
|
@ -546,12 +550,14 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
|
|||
|
||||
struct i2c_msg_s msgv[2] = {
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &addrbuf[0],
|
||||
.length = sizeof(addrbuf),
|
||||
},
|
||||
{
|
||||
.frequency = 400000,
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = &buf[0],
|
||||
|
@ -569,7 +575,7 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev)
|
|||
|
||||
/* Return the implementation-specific state structure as the MTD device */
|
||||
|
||||
fvdbg("Return %p\n", priv);
|
||||
finfo("Return %p\n", priv);
|
||||
return (FAR struct mtd_dev_s *)priv;
|
||||
}
|
||||
|
||||
|
|
|
@ -51,10 +51,11 @@
|
|||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/spi.h>
|
||||
#include <nuttx/mtd.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
#include <nuttx/fs/nxffs.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
#include <nuttx/drivers/drivers.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
|
@ -230,9 +231,7 @@ static void
|
|||
at24xxx_attach(void)
|
||||
{
|
||||
/* find the right I2C */
|
||||
struct i2c_dev_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_MTD);
|
||||
/* this resets the I2C bus, set correct bus speed again */
|
||||
I2C_SETFREQUENCY(i2c, 400000);
|
||||
struct i2c_master_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_MTD);
|
||||
|
||||
if (i2c == NULL) {
|
||||
errx(1, "failed to locate I2C bus");
|
||||
|
|
|
@ -46,13 +46,9 @@
|
|||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <sys/mount.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/mtd.h>
|
||||
#include <nuttx/fs/nxffs.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
|
Loading…
Reference in New Issue