PX4 Firmware
PX4 Autopilot Software http://px4.io
mtd.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file mtd.c
36  *
37  * mtd service and utility app.
38  *
39  * @author Lorenz Meier <lm@inf.ethz.ch>
40  */
41 
42 #include <px4_platform_common/px4_config.h>
43 #include <px4_platform_common/log.h>
44 #include <px4_platform_common/module.h>
45 
46 #include <stdio.h>
47 #include <stdlib.h>
48 #include <string.h>
49 #include <stdbool.h>
50 #include <unistd.h>
51 #include <fcntl.h>
52 #include <sys/mount.h>
53 #include <sys/ioctl.h>
54 #include <sys/stat.h>
55 
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>
61 
62 #include <arch/board/board.h>
63 
64 #include "systemlib/px4_macros.h"
65 #include <parameters/param.h>
66 
67 #include <board_config.h>
68 
69 __EXPORT int mtd_main(int argc, char *argv[]);
70 
71 #ifndef CONFIG_MTD
72 
73 /* create a fake command with decent warning to not confuse users */
74 int mtd_main(int argc, char *argv[])
75 {
76  PX4_WARN("MTD not enabled, skipping.");
77  return 1;
78 }
79 
80 #else
81 
82 # if defined(BOARD_HAS_MTD_PARTITION_OVERRIDE)
83 # define MTD_PARTITION_TABLE BOARD_HAS_MTD_PARTITION_OVERRIDE
84 # else
85 # define MTD_PARTITION_TABLE {"/fs/mtd_params", "/fs/mtd_waypoints"}
86 # endif
87 
88 
89 #ifdef CONFIG_MTD_RAMTRON
90 static int ramtron_attach(void);
91 #else
92 
93 #ifndef PX4_I2C_BUS_MTD
94 # ifdef PX4_I2C_BUS_ONBOARD
95 # define PX4_I2C_BUS_MTD PX4_I2C_BUS_ONBOARD
96 # else
97 # error PX4_I2C_BUS_MTD and PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
98 # endif
99 #endif
100 
101 
102 static int at24xxx_attach(void);
103 #endif
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);
111 
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;
116 
117 /* note, these will be equally sized */
118 static char *partition_names_default[] = MTD_PARTITION_TABLE;
119 static const int n_partitions_default = arraySize(partition_names_default);
120 
121 static int
122 mtd_status(void)
123 {
124  if (!attached) {
125  PX4_ERR("MTD driver not started");
126  return 1;
127  }
128 
129  return mtd_print_info();
130 }
131 
132 static void print_usage(void)
133 {
134  PRINT_MODULE_DESCRIPTION("Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board)");
135 
136  PRINT_MODULE_USAGE_NAME("mtd", "command");
137  PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print status information");
138 
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)");
143 
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);
147 }
148 
149 int mtd_main(int argc, char *argv[])
150 {
151  if (argc >= 2) {
152  if (!strcmp(argv[1], "start")) {
153 
154  /* start mapping according to user request */
155  if (argc >= 3) {
156  return mtd_start(argv + 2, argc - 2);
157 
158  } else {
159  return mtd_start(partition_names_default, n_partitions_default);
160  }
161  }
162 
163  if (!strcmp(argv[1], "readtest")) {
164  if (argc >= 3) {
165  return mtd_readtest(argv + 2, argc - 2);
166 
167  } else {
168  return mtd_readtest(partition_names_default, n_partitions_default);
169  }
170  }
171 
172  if (!strcmp(argv[1], "rwtest")) {
173  if (argc >= 3) {
174  return mtd_rwtest(argv + 2, argc - 2);
175 
176  } else {
177  return mtd_rwtest(partition_names_default, n_partitions_default);
178  }
179  }
180 
181  if (!strcmp(argv[1], "status")) {
182  return mtd_status();
183  }
184 
185  if (!strcmp(argv[1], "erase")) {
186  if (argc >= 3) {
187  return mtd_erase(argv + 2, argc - 2);
188 
189  } else {
190  return mtd_erase(partition_names_default, n_partitions_default);
191  }
192  }
193  }
194 
195  print_usage();
196  return 1;
197 }
198 
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);
202 
203 #ifdef CONFIG_MTD_RAMTRON
204 static int
205 ramtron_attach(void)
206 {
207  /* initialize the right spi */
208  struct spi_dev_s *spi = px4_spibus_initialize(PX4_SPI_BUS_RAMTRON);
209 
210  if (spi == NULL) {
211  PX4_ERR("failed to locate spi bus");
212  return 1;
213  }
214 
215  /* this resets the spi bus, set correct bus speed again */
216  SPI_SETFREQUENCY(spi, 10 * 1000 * 1000);
217  SPI_SETBITS(spi, 8);
218  SPI_SETMODE(spi, SPIDEV_MODE3);
219  SPI_SELECT(spi, SPIDEV_FLASH(0), false);
220 
221  /* start the RAMTRON driver, attempt 5 times */
222 
223  for (int i = 0; i < 5; i++) {
224  mtd_dev = ramtron_initialize(spi);
225 
226  if (mtd_dev) {
227  /* abort on first valid result */
228  if (i > 0) {
229  PX4_WARN("mtd needed %d attempts to attach", i + 1);
230  }
231 
232  break;
233  }
234  }
235 
236  /* if last attempt is still unsuccessful, abort */
237  if (mtd_dev == NULL) {
238  PX4_ERR("failed to initialize mtd driver");
239  return 1;
240  }
241 
242  int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_SETSPEED, (unsigned long)10 * 1000 * 1000);
243 
244  if (ret != OK) {
245  // FIXME: From the previous warning call, it looked like this should have been fatal error instead. Tried
246  // that but setting the bus speed does fail all the time. Which was then exiting and the board would
247  // not run correctly. So changed to PX4_WARN.
248  PX4_WARN("failed to set bus speed");
249  }
250 
251  attached = true;
252  return 0;
253 }
254 #else
255 
256 static int
257 at24xxx_attach(void)
258 {
259  /* find the right I2C */
260  struct i2c_master_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_MTD);
261 
262  if (i2c == NULL) {
263  PX4_ERR("failed to locate I2C bus");
264  return 1;
265  }
266 
267  /* start the MTD driver, attempt 5 times */
268  for (int i = 0; i < 5; i++) {
269  mtd_dev = at24c_initialize(i2c);
270 
271  if (mtd_dev) {
272  /* abort on first valid result */
273  if (i > 0) {
274  PX4_WARN("EEPROM needed %d attempts to attach", i + 1);
275  }
276 
277  break;
278  }
279  }
280 
281  /* if last attempt is still unsuccessful, abort */
282  if (mtd_dev == NULL) {
283  PX4_ERR("failed to initialize EEPROM driver");
284  return 1;
285  }
286 
287  attached = true;
288  return 0;
289 }
290 #endif
291 
292 static int
293 mtd_start(char *partition_names[], unsigned n_partitions)
294 {
295  int ret;
296 
297  if (started) {
298  PX4_ERR("mtd already mounted");
299  return 1;
300  }
301 
302  if (!attached) {
303 #ifdef CONFIG_MTD_RAMTRON
304  ret = ramtron_attach();
305 #else
306  ret = at24xxx_attach();
307 #endif
308 
309  if (ret != 0) {
310  return ret;
311  }
312  }
313 
314  if (!mtd_dev) {
315  PX4_ERR("Failed to create RAMTRON FRAM MTD instance");
316  return 1;
317  }
318 
319  unsigned long blocksize, erasesize, neraseblocks;
320  unsigned blkpererase, nblocks, partsize;
321 
322  ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize, n_partitions);
323 
324  if (ret) {
325  return ret;
326  }
327 
328  /* Now create MTD FLASH partitions */
329 
330  FAR struct mtd_dev_s *part[n_partitions];
331  char blockname[32];
332 
333  unsigned offset;
334  unsigned i;
335 
336  for (offset = 0, i = 0; i < n_partitions; offset += nblocks, i++) {
337 
338  /* Create the partition */
339 
340  part[i] = mtd_partition(mtd_dev, offset, nblocks);
341 
342  if (!part[i]) {
343  PX4_ERR("mtd_partition failed. offset=%lu nblocks=%lu",
344  (unsigned long)offset, (unsigned long)nblocks);
345  return 1;
346  }
347 
348  /* Initialize to provide an FTL block driver on the MTD FLASH interface */
349 
350  snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", i);
351 
352  ret = ftl_initialize(i, part[i]);
353 
354  if (ret < 0) {
355  PX4_ERR("ftl_initialize %s failed: %d", blockname, ret);
356  return 1;
357  }
358 
359  /* Now create a character device on the block device */
360 
361  ret = bchdev_register(blockname, partition_names[i], false);
362 
363  if (ret < 0) {
364  PX4_ERR("bchdev_register %s failed: %d", partition_names[i], ret);
365  return 1;
366  }
367  }
368 
369  n_partitions_current = n_partitions;
370 
371  started = true;
372  return 0;
373 }
374 
375 int mtd_get_geometry(unsigned long *blocksize, unsigned long *erasesize, unsigned long *neraseblocks,
376  unsigned *blkpererase, unsigned *nblocks, unsigned *partsize, unsigned n_partitions)
377 {
378  /* Get the geometry of the FLASH device */
379 
380  FAR struct mtd_geometry_s geo;
381 
382  int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
383 
384  if (ret < 0) {
385  PX4_ERR("mtd->ioctl failed: %d", ret);
386  return ret;
387  }
388 
389  *blocksize = geo.blocksize;
390  *erasesize = geo.erasesize;
391  *neraseblocks = geo.neraseblocks;
392 
393  /* Determine the size of each partition. Make each partition an even
394  * multiple of the erase block size (perhaps not using some space at the
395  * end of the FLASH).
396  */
397 
398  *blkpererase = geo.erasesize / geo.blocksize;
399  *nblocks = (geo.neraseblocks / n_partitions) * *blkpererase;
400  *partsize = *nblocks * geo.blocksize;
401 
402  return ret;
403 }
404 
405 /*
406  get partition size in bytes
407  */
408 static ssize_t mtd_get_partition_size(void)
409 {
410  unsigned long blocksize, erasesize, neraseblocks;
411  unsigned blkpererase, nblocks, partsize = 0;
412 
413  int ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize,
414  n_partitions_current);
415 
416  if (ret != OK) {
417  PX4_ERR("Failed to get geometry");
418  return 0;
419  }
420 
421  return partsize;
422 }
423 
424 int mtd_print_info(void)
425 {
426  if (!attached) {
427  return 1;
428  }
429 
430  unsigned long blocksize, erasesize, neraseblocks;
431  unsigned blkpererase, nblocks, partsize;
432 
433  int ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize,
434  n_partitions_current);
435 
436  if (ret) {
437  return ret;
438  }
439 
440  PX4_INFO("Flash Geometry:");
441 
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);
448 
449  return 0;
450 }
451 
452 int
453 mtd_erase(char *partition_names[], unsigned n_partitions)
454 {
455  uint8_t v[64];
456  memset(v, 0xFF, sizeof(v));
457 
458  for (uint8_t i = 0; i < n_partitions; i++) {
459  uint32_t count = 0;
460  printf("Erasing %s\n", partition_names[i]);
461  int fd = open(partition_names[i], O_WRONLY);
462 
463  if (fd == -1) {
464  PX4_ERR("Failed to open partition");
465  return 1;
466  }
467 
468  while (write(fd, v, sizeof(v)) == sizeof(v)) {
469  count += sizeof(v);
470  }
471 
472  printf("Erased %lu bytes\n", (unsigned long)count);
473  close(fd);
474  }
475 
476  return 0;
477 }
478 
479 /*
480  readtest is useful during startup to validate the device is
481  responding on the bus. It relies on the driver returning an error on
482  bad reads (the ramtron driver does return an error)
483  */
484 int
485 mtd_readtest(char *partition_names[], unsigned n_partitions)
486 {
487  ssize_t expected_size = mtd_get_partition_size();
488 
489  if (expected_size == 0) {
490  return 1;
491  }
492 
493  uint8_t v[128];
494 
495  for (uint8_t i = 0; i < n_partitions; i++) {
496  ssize_t count = 0;
497  printf("reading %s expecting %u bytes\n", partition_names[i], expected_size);
498  int fd = open(partition_names[i], O_RDONLY);
499 
500  if (fd == -1) {
501  PX4_ERR("Failed to open partition");
502  return 1;
503  }
504 
505  while (read(fd, v, sizeof(v)) == sizeof(v)) {
506  count += sizeof(v);
507  }
508 
509  if (count != expected_size) {
510  PX4_ERR("Failed to read partition - got %u/%u bytes", count, expected_size);
511  return 1;
512  }
513 
514  close(fd);
515  }
516 
517  printf("readtest OK\n");
518  return 0;
519 }
520 
521 /*
522  rwtest is useful during startup to validate the device is
523  responding on the bus for both reads and writes. It reads data in
524  blocks and writes the data back, then reads it again, failing if the
525  data isn't the same
526  */
527 int
528 mtd_rwtest(char *partition_names[], unsigned n_partitions)
529 {
530  ssize_t expected_size = mtd_get_partition_size();
531 
532  if (expected_size == 0) {
533  return 1;
534  }
535 
536  uint8_t v[128], v2[128];
537 
538  for (uint8_t i = 0; i < n_partitions; i++) {
539  ssize_t count = 0;
540  off_t offset = 0;
541  printf("rwtest %s testing %u bytes\n", partition_names[i], expected_size);
542  int fd = open(partition_names[i], O_RDWR);
543 
544  if (fd == -1) {
545  PX4_ERR("Failed to open partition");
546  return 1;
547  }
548 
549  while (read(fd, v, sizeof(v)) == sizeof(v)) {
550  count += sizeof(v);
551 
552  if (lseek(fd, offset, SEEK_SET) != offset) {
553  PX4_ERR("seek failed");
554  return 1;
555  }
556 
557  if (write(fd, v, sizeof(v)) != sizeof(v)) {
558  PX4_ERR("write failed");
559  return 1;
560  }
561 
562  if (lseek(fd, offset, SEEK_SET) != offset) {
563  PX4_ERR("seek failed");
564  return 1;
565  }
566 
567  if (read(fd, v2, sizeof(v2)) != sizeof(v2)) {
568  PX4_ERR("read failed");
569  return 1;
570  }
571 
572  if (memcmp(v, v2, sizeof(v2)) != 0) {
573  PX4_ERR("memcmp failed");
574  return 1;
575  }
576 
577  offset += sizeof(v);
578  }
579 
580  if (count != expected_size) {
581  PX4_ERR("Failed to read partition - got %u/%u bytes", count, expected_size);
582  return 1;
583  }
584 
585  close(fd);
586  }
587 
588  printf("rwtest OK\n");
589  return 0;
590 }
591 
592 #endif
static uint32_t nblocks
Definition: reflect.c:55
Definition: I2C.hpp:51
__EXPORT int mtd_main(int argc, char *argv[])
Definition: mtd.c:74
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)
int fd
Definition: dataman.cpp:146
static void write(bootloader_app_shared_t *pshared)
#define arraySize(a)
#define OK
Definition: uavcan_main.cpp:71
FAR struct mtd_dev_s * at24c_initialize(FAR struct i2c_master_s *dev)
Definition: 24xxxx_mtd.c:540