42 #include <px4_platform_common/px4_config.h> 43 #include <px4_platform_common/log.h> 44 #include <px4_platform_common/module.h> 52 #include <sys/mount.h> 53 #include <sys/ioctl.h> 56 #include <nuttx/spi/spi.h> 57 #include <nuttx/mtd/mtd.h> 58 #include <nuttx/fs/nxffs.h> 59 #include <nuttx/fs/ioctl.h> 60 #include <nuttx/drivers/drivers.h> 62 #include <arch/board/board.h> 67 #include <board_config.h> 76 PX4_WARN(
"MTD not enabled, skipping.");
82 # if defined(BOARD_HAS_MTD_PARTITION_OVERRIDE) 83 # define MTD_PARTITION_TABLE BOARD_HAS_MTD_PARTITION_OVERRIDE 85 # define MTD_PARTITION_TABLE {"/fs/mtd_params", "/fs/mtd_waypoints"} 89 #ifdef CONFIG_MTD_RAMTRON 90 static int ramtron_attach(
void);
93 #ifndef PX4_I2C_BUS_MTD 94 # ifdef PX4_I2C_BUS_ONBOARD 95 # define PX4_I2C_BUS_MTD PX4_I2C_BUS_ONBOARD 97 # error PX4_I2C_BUS_MTD and PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM 102 static int at24xxx_attach(
void);
104 static int mtd_start(
char *partition_names[],
unsigned n_partitions);
105 static int mtd_erase(
char *partition_names[],
unsigned n_partitions);
106 static int mtd_readtest(
char *partition_names[],
unsigned n_partitions);
107 static int mtd_rwtest(
char *partition_names[],
unsigned n_partitions);
108 static int mtd_print_info(
void);
109 static int mtd_get_geometry(
unsigned long *blocksize,
unsigned long *erasesize,
unsigned long *neraseblocks,
110 unsigned *blkpererase,
unsigned *
nblocks,
unsigned *partsize,
unsigned n_partitions);
112 static bool attached =
false;
113 static bool started =
false;
114 static struct mtd_dev_s *mtd_dev;
115 static unsigned n_partitions_current = 0;
118 static char *partition_names_default[] = MTD_PARTITION_TABLE;
119 static const int n_partitions_default =
arraySize(partition_names_default);
125 PX4_ERR(
"MTD driver not started");
129 return mtd_print_info();
134 PRINT_MODULE_DESCRIPTION(
"Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board)");
136 PRINT_MODULE_USAGE_NAME(
"mtd",
"command");
137 PRINT_MODULE_USAGE_COMMAND_DESCR(
"status",
"Print status information");
139 PRINT_MODULE_USAGE_COMMAND_DESCR(
"start",
"Mount partitions");
140 PRINT_MODULE_USAGE_COMMAND_DESCR(
"readtest",
"Perform read test");
141 PRINT_MODULE_USAGE_COMMAND_DESCR(
"rwtest",
"Perform read-write test");
142 PRINT_MODULE_USAGE_COMMAND_DESCR(
"erase",
"Erase partition(s)");
144 PRINT_MODULE_USAGE_PARAM_COMMENT(
"The commands 'start', 'readtest', 'rwtest' and 'erase' have an optional parameter:");
145 PRINT_MODULE_USAGE_ARG(
"<partition_name1> [<partition_name2> ...]",
146 "Partition names (eg. /fs/mtd_params), use system default if not provided",
true);
149 int mtd_main(
int argc,
char *argv[])
152 if (!strcmp(argv[1],
"start")) {
156 return mtd_start(argv + 2, argc - 2);
159 return mtd_start(partition_names_default, n_partitions_default);
163 if (!strcmp(argv[1],
"readtest")) {
165 return mtd_readtest(argv + 2, argc - 2);
168 return mtd_readtest(partition_names_default, n_partitions_default);
172 if (!strcmp(argv[1],
"rwtest")) {
174 return mtd_rwtest(argv + 2, argc - 2);
177 return mtd_rwtest(partition_names_default, n_partitions_default);
181 if (!strcmp(argv[1],
"status")) {
185 if (!strcmp(argv[1],
"erase")) {
187 return mtd_erase(argv + 2, argc - 2);
190 return mtd_erase(partition_names_default, n_partitions_default);
199 struct mtd_dev_s *ramtron_initialize(FAR
struct spi_dev_s *dev);
200 struct mtd_dev_s *mtd_partition(FAR
struct mtd_dev_s *mtd,
201 off_t firstblock, off_t
nblocks);
203 #ifdef CONFIG_MTD_RAMTRON 208 struct spi_dev_s *spi = px4_spibus_initialize(PX4_SPI_BUS_RAMTRON);
211 PX4_ERR(
"failed to locate spi bus");
216 SPI_SETFREQUENCY(spi, 10 * 1000 * 1000);
219 SPI_SELECT(spi, SPIDEV_FLASH(0),
false);
223 for (
int i = 0; i < 5; i++) {
224 mtd_dev = ramtron_initialize(spi);
229 PX4_WARN(
"mtd needed %d attempts to attach", i + 1);
237 if (mtd_dev == NULL) {
238 PX4_ERR(
"failed to initialize mtd driver");
242 int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_SETSPEED, (
unsigned long)10 * 1000 * 1000);
248 PX4_WARN(
"failed to set bus speed");
260 struct i2c_master_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_MTD);
263 PX4_ERR(
"failed to locate I2C bus");
268 for (
int i = 0; i < 5; i++) {
274 PX4_WARN(
"EEPROM needed %d attempts to attach", i + 1);
282 if (mtd_dev == NULL) {
283 PX4_ERR(
"failed to initialize EEPROM driver");
293 mtd_start(
char *partition_names[],
unsigned n_partitions)
298 PX4_ERR(
"mtd already mounted");
303 #ifdef CONFIG_MTD_RAMTRON 304 ret = ramtron_attach();
306 ret = at24xxx_attach();
315 PX4_ERR(
"Failed to create RAMTRON FRAM MTD instance");
319 unsigned long blocksize, erasesize, neraseblocks;
320 unsigned blkpererase,
nblocks, partsize;
322 ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize, n_partitions);
330 FAR
struct mtd_dev_s *part[n_partitions];
336 for (offset = 0, i = 0; i < n_partitions; offset +=
nblocks, i++) {
340 part[i] = mtd_partition(mtd_dev, offset, nblocks);
343 PX4_ERR(
"mtd_partition failed. offset=%lu nblocks=%lu",
344 (
unsigned long)offset, (
unsigned long)nblocks);
350 snprintf(blockname,
sizeof(blockname),
"/dev/mtdblock%d", i);
352 ret = ftl_initialize(i, part[i]);
355 PX4_ERR(
"ftl_initialize %s failed: %d", blockname, ret);
361 ret = bchdev_register(blockname, partition_names[i],
false);
364 PX4_ERR(
"bchdev_register %s failed: %d", partition_names[i], ret);
369 n_partitions_current = n_partitions;
375 int mtd_get_geometry(
unsigned long *blocksize,
unsigned long *erasesize,
unsigned long *neraseblocks,
376 unsigned *blkpererase,
unsigned *
nblocks,
unsigned *partsize,
unsigned n_partitions)
380 FAR
struct mtd_geometry_s geo;
382 int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_GEOMETRY, (
unsigned long)((uintptr_t)&geo));
385 PX4_ERR(
"mtd->ioctl failed: %d", ret);
389 *blocksize = geo.blocksize;
390 *erasesize = geo.erasesize;
391 *neraseblocks = geo.neraseblocks;
398 *blkpererase = geo.erasesize / geo.blocksize;
399 *
nblocks = (geo.neraseblocks / n_partitions) * *blkpererase;
400 *partsize = *
nblocks * geo.blocksize;
408 static ssize_t mtd_get_partition_size(
void)
410 unsigned long blocksize, erasesize, neraseblocks;
411 unsigned blkpererase,
nblocks, partsize = 0;
413 int ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize,
414 n_partitions_current);
417 PX4_ERR(
"Failed to get geometry");
424 int mtd_print_info(
void)
430 unsigned long blocksize, erasesize, neraseblocks;
431 unsigned blkpererase,
nblocks, partsize;
433 int ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize,
434 n_partitions_current);
440 PX4_INFO(
"Flash Geometry:");
442 printf(
" blocksize: %lu\n", blocksize);
443 printf(
" erasesize: %lu\n", erasesize);
444 printf(
" neraseblocks: %lu\n", neraseblocks);
445 printf(
" No. partitions: %u\n", n_partitions_current);
446 printf(
" Partition size: %u Blocks (%u bytes)\n", nblocks, partsize);
447 printf(
" TOTAL SIZE: %u KiB\n", neraseblocks * erasesize / 1024);
453 mtd_erase(
char *partition_names[],
unsigned n_partitions)
456 memset(v, 0xFF,
sizeof(v));
458 for (uint8_t i = 0; i < n_partitions; i++) {
460 printf(
"Erasing %s\n", partition_names[i]);
461 int fd = open(partition_names[i], O_WRONLY);
464 PX4_ERR(
"Failed to open partition");
468 while (
write(fd, v,
sizeof(v)) ==
sizeof(v)) {
472 printf(
"Erased %lu bytes\n", (
unsigned long)count);
485 mtd_readtest(
char *partition_names[],
unsigned n_partitions)
487 ssize_t expected_size = mtd_get_partition_size();
489 if (expected_size == 0) {
495 for (uint8_t i = 0; i < n_partitions; i++) {
497 printf(
"reading %s expecting %u bytes\n", partition_names[i], expected_size);
498 int fd = open(partition_names[i], O_RDONLY);
501 PX4_ERR(
"Failed to open partition");
505 while (
read(fd, v,
sizeof(v)) ==
sizeof(v)) {
509 if (count != expected_size) {
510 PX4_ERR(
"Failed to read partition - got %u/%u bytes", count, expected_size);
517 printf(
"readtest OK\n");
528 mtd_rwtest(
char *partition_names[],
unsigned n_partitions)
530 ssize_t expected_size = mtd_get_partition_size();
532 if (expected_size == 0) {
536 uint8_t v[128], v2[128];
538 for (uint8_t i = 0; i < n_partitions; i++) {
541 printf(
"rwtest %s testing %u bytes\n", partition_names[i], expected_size);
542 int fd = open(partition_names[i], O_RDWR);
545 PX4_ERR(
"Failed to open partition");
549 while (
read(fd, v,
sizeof(v)) ==
sizeof(v)) {
552 if (lseek(fd, offset, SEEK_SET) != offset) {
553 PX4_ERR(
"seek failed");
557 if (
write(fd, v,
sizeof(v)) !=
sizeof(v)) {
558 PX4_ERR(
"write failed");
562 if (lseek(fd, offset, SEEK_SET) != offset) {
563 PX4_ERR(
"seek failed");
567 if (
read(fd, v2,
sizeof(v2)) !=
sizeof(v2)) {
568 PX4_ERR(
"read failed");
572 if (memcmp(v, v2,
sizeof(v2)) != 0) {
573 PX4_ERR(
"memcmp failed");
580 if (count != expected_size) {
581 PX4_ERR(
"Failed to read partition - got %u/%u bytes", count, expected_size);
588 printf(
"rwtest OK\n");
__EXPORT int mtd_main(int argc, char *argv[])
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
static void print_usage()
Global flash based parameter store.
static void read(bootloader_app_shared_t *pshared)
static void write(bootloader_app_shared_t *pshared)
FAR struct mtd_dev_s * at24c_initialize(FAR struct i2c_master_s *dev)