Browse Source

px4_mtd: update eeprom at24c driver to initialize multiple instances

main
Igor Mišić 3 years ago committed by Beat Küng
parent
commit
08a9e49f3e
  1. 2
      boards/px4/fmu-v5x/src/board_config.h
  2. 4
      platforms/common/include/px4_platform_common/board_common.h
  3. 5
      platforms/common/include/px4_platform_common/px4_mtd.h
  4. 32
      platforms/nuttx/src/px4/common/px4_24xxxx_mtd.c
  5. 8
      platforms/nuttx/src/px4/common/px4_mtd.cpp

2
boards/px4/fmu-v5x/src/board_config.h

@ -111,6 +111,8 @@ @@ -111,6 +111,8 @@
*
* Note that these are unshifted addresses.
*/
#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/
#define PX4_I2C_OBDEV_SE050 0x48
#define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5)

4
platforms/common/include/px4_platform_common/board_common.h

@ -82,6 +82,10 @@ @@ -82,6 +82,10 @@
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 1
#endif
#ifndef BOARD_MTD_NUM_EEPROM
#define BOARD_MTD_NUM_EEPROM 1
#endif
/* ADC defining tools
* We want to normalize the V5 Sensing to V = (adc_dn) * ADC_V5_V_FULL_SCALE/(2 ^ ADC_BITS) * ADC_V5_SCALE)
*/

5
platforms/common/include/px4_platform_common/px4_mtd.h

@ -75,7 +75,8 @@ __EXPORT int px4_mtd_get_geometry(const mtd_instance_s *instance, unsigned long @@ -75,7 +75,8 @@ __EXPORT int px4_mtd_get_geometry(const mtd_instance_s *instance, unsigned long
*/
__EXPORT ssize_t px4_mtd_get_partition_size(const mtd_instance_s *instance, const char *partname);
FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address);
int px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address, FAR struct mtd_dev_s **mtd_dev);
__END_DECLS

32
platforms/nuttx/src/px4/common/px4_24xxxx_mtd.c

@ -70,6 +70,7 @@ @@ -70,6 +70,7 @@
#include <nuttx/mtd/mtd.h>
#include <perf/perf_counter.h>
#include <board_config.h>
/************************************************************************************
* Pre-processor Definitions
@ -195,11 +196,8 @@ int at24c_nuke(void); @@ -195,11 +196,8 @@ int at24c_nuke(void);
* Private Data
************************************************************************************/
/* At present, only a single AT24 part is supported. In this case, a statically
* allocated state structure may be used.
*/
static struct at24c_dev_s g_at24c;
static uint8_t number_of_instances = 0u;
static struct at24c_dev_s g_at24c[BOARD_MTD_NUM_EEPROM];
/************************************************************************************
* Private Functions
@ -262,7 +260,7 @@ void at24c_test(void) @@ -262,7 +260,7 @@ void at24c_test(void)
unsigned errors = 0;
for (count = 0; count < 10000; count++) {
ssize_t result = at24c_bread(&g_at24c.mtd, 0, 1, buf);
ssize_t result = at24c_bread(&g_at24c[0].mtd, 0, 1, buf);
if (result == ERROR) {
if (errors++ > 2) {
@ -538,13 +536,17 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) @@ -538,13 +536,17 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
* other functions (such as a block or character driver front end).
*
************************************************************************************/
FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address)
int px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address, FAR struct mtd_dev_s **mtd_dev)
{
if (number_of_instances >= BOARD_MTD_NUM_EEPROM) {
return -ENOMEM;
}
FAR struct at24c_dev_s *priv;
finfo("dev: %p\n", dev);
finfo("dev: %p, mtd_dev %p\n", dev, mtd_dev);
/* Allocate a state structure (we allocate the structure instead of using
* a fixed, static allocation so that we can handle multiple FLASH devices.
@ -553,7 +555,7 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev, @@ -553,7 +555,7 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
* to be extended to handle multiple FLASH parts on the same I2C bus.
*/
priv = &g_at24c;
priv = &g_at24c[number_of_instances];
if (priv) {
/* Initialize the allocated structure */
@ -608,13 +610,13 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev, @@ -608,13 +610,13 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
priv->perf_resets_retries = NULL;
priv->perf_errors = NULL;
return NULL;
return ret;
}
/* Return the implementation-specific state structure as the MTD device */
*mtd_dev = (FAR struct mtd_dev_s *)priv;
++number_of_instances;
finfo("Return %p\n", priv);
return (FAR struct mtd_dev_s *)priv;
return 0;
}
/*
@ -622,5 +624,5 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev, @@ -622,5 +624,5 @@ FAR struct mtd_dev_s *px4_at24c_initialize(FAR struct i2c_master_s *dev,
*/
int at24c_nuke(void)
{
return at24c_eraseall(&g_at24c);
return at24c_eraseall(&g_at24c[0]);
}

8
platforms/nuttx/src/px4/common/px4_mtd.cpp

@ -147,15 +147,19 @@ static int at24xxx_attach(mtd_instance_s &instance) @@ -147,15 +147,19 @@ static int at24xxx_attach(mtd_instance_s &instance)
/* start the MTD driver, attempt 5 times */
for (int i = 0; i < 5; i++) {
instance.mtd_dev = px4_at24c_initialize(i2c, PX4_I2C_DEVID_ADDR(instance.devid));
int ret_val = px4_at24c_initialize(i2c, PX4_I2C_DEVID_ADDR(instance.devid), &(instance.mtd_dev));
if (instance.mtd_dev) {
if (ret_val == 0) {
/* abort on first valid result */
if (i > 0) {
PX4_WARN("EEPROM needed %d attempts to attach", i + 1);
}
break;
} else if (ret_val == -ENOMEM) {
PX4_ERR("Number of at24c EEPROM instances reached the board limit of %d", BOARD_MTD_NUM_EEPROM);
break;
}
}

Loading…
Cancel
Save