PX4 Firmware
PX4 Autopilot Software http://px4.io
24xxxx_mtd.c
Go to the documentation of this file.
1 /************************************************************************************
2  * Driver for 24xxxx-style I2C EEPROMs.
3  *
4  * Adapted from:
5  *
6  * drivers/mtd/at24xx.c
7  * Driver for I2C-based at24cxx EEPROM(at24c32,at24c64,at24c128,at24c256)
8  *
9  * Copyright (C) 2011 Li Zhuoyi. All rights reserved.
10  * Author: Li Zhuoyi <lzyy.cn@gmail.com>
11  * History: 0.1 2011-08-20 initial version
12  *
13  * 2011-11-1 Added support for larger MTD block sizes: Hal Glenn <hglenn@2g-eng.com>
14  *
15  * Derived from drivers/mtd/m25px.c
16  *
17  * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
18  * Author: Gregory Nutt <gnutt@nuttx.org>
19  *
20  * Redistribution and use in source and binary forms, with or without
21  * modification, are permitted provided that the following conditions
22  * are met:
23  *
24  * 1. Redistributions of source code must retain the above copyright
25  * notice, this list of conditions and the following disclaimer.
26  * 2. Redistributions in binary form must reproduce the above copyright
27  * notice, this list of conditions and the following disclaimer in
28  * the documentation and/or other materials provided with the
29  * distribution.
30  * 3. Neither the name NuttX nor the names of its contributors may be
31  * used to endorse or promote products derived from this software
32  * without specific prior written permission.
33  *
34  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
35  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
36  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
37  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
38  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
40  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
41  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
42  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
43  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
44  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
45  * POSSIBILITY OF SUCH DAMAGE.
46  *
47  ************************************************************************************/
48 
49 /************************************************************************************
50  * Included Files
51  ************************************************************************************/
52 
53 #include <px4_platform_common/px4_config.h>
54 #include <px4_platform_common/time.h>
55 
56 #include <sys/types.h>
57 #include <stdint.h>
58 #include <stdbool.h>
59 #include <stdlib.h>
60 #include <unistd.h>
61 #include <string.h>
62 #include <errno.h>
63 #include <debug.h>
64 
65 #include <nuttx/kmalloc.h>
66 #include <nuttx/fs/ioctl.h>
67 #include <nuttx/i2c/i2c_master.h>
68 #include <nuttx/mtd/mtd.h>
69 
70 #include <perf/perf_counter.h>
71 
72 /************************************************************************************
73  * Pre-processor Definitions
74  ************************************************************************************/
75 
76 /*
77  * Configuration is as for the AT24 driver, but the CONFIG_MTD_AT24XX define should be
78  * omitted in order to avoid building the AT24XX driver as well.
79  */
80 
81 /* As a minimum, the size of the AT24 part and its 7-bit I2C address are required. */
82 
83 #ifndef CONFIG_AT24XX_SIZE
84 /* XXX this is a well vetted special case,
85  * do not issue a warning any more
86  * # warning "Assuming AT24 size 64"
87  */
88 # define CONFIG_AT24XX_SIZE 64
89 #endif
90 #ifndef CONFIG_AT24XX_ADDR
91 /* XXX this is a well vetted special case,
92  * do not issue a warning any more
93  * # warning "Assuming AT24 address of 0x50"
94  */
95 # define CONFIG_AT24XX_ADDR 0x50
96 #endif
97 
98 /* Get the part configuration based on the size configuration */
99 
100 #if CONFIG_AT24XX_SIZE == 2 /* AT24C02: 2Kbits = 256; 16 * 16 = 256 */
101 # define AT24XX_NPAGES 16
102 # define AT24XX_PAGESIZE 16
103 # define AT24XX_ADDRSIZE 1
104 #elif CONFIG_AT24XX_SIZE == 4 /* AT24C04: 4Kbits = 512B; 32 * 16 = 512 */
105 # define AT24XX_NPAGES 32
106 # define AT24XX_PAGESIZE 16
107 # define AT24XX_ADDRSIZE 1
108 #elif CONFIG_AT24XX_SIZE == 8 /* AT24C08: 8Kbits = 1KiB; 64 * 16 = 1024 */
109 # define AT24XX_NPAGES 64
110 # define AT24XX_PAGESIZE 16
111 # define AT24XX_ADDRSIZE 1
112 #elif CONFIG_AT24XX_SIZE == 16 /* AT24C16: 16Kbits = 2KiB; 128 * 16 = 2048 */
113 # define AT24XX_NPAGES 128
114 # define AT24XX_PAGESIZE 16
115 # define AT24XX_ADDRSIZE 1
116 #elif CONFIG_AT24XX_SIZE == 32
117 # define AT24XX_NPAGES 128
118 # define AT24XX_PAGESIZE 32
119 #elif CONFIG_AT24XX_SIZE == 48
120 # define AT24XX_NPAGES 192
121 # define AT24XX_PAGESIZE 32
122 #elif CONFIG_AT24XX_SIZE == 64
123 # define AT24XX_NPAGES 256
124 # define AT24XX_PAGESIZE 32
125 #elif CONFIG_AT24XX_SIZE == 128
126 # define AT24XX_NPAGES 256
127 # define AT24XX_PAGESIZE 64
128 #elif CONFIG_AT24XX_SIZE == 256
129 # define AT24XX_NPAGES 512
130 # define AT24XX_PAGESIZE 64
131 #endif
132 
133 /* For applications where a file system is used on the AT24, the tiny page sizes
134  * will result in very inefficient FLASH usage. In such cases, it is better if
135  * blocks are comprised of "clusters" of pages so that the file system block
136  * size is, say, 256 or 512 bytes. In any event, the block size *must* be an
137  * even multiple of the pages.
138  */
139 
140 #ifndef CONFIG_AT24XX_MTD_BLOCKSIZE
141 /* XXX this is a well vetted special case,
142  * do not issue a warning any more
143  * # warning "Assuming driver block size is the same as the FLASH page size"
144  */
145 # define CONFIG_AT24XX_MTD_BLOCKSIZE AT24XX_PAGESIZE
146 #endif
147 
148 /* The AT24 does not respond on the bus during write cycles, so we depend on a long
149  * timeout to detect problems. The max program time is typically ~5ms.
150  */
151 #ifndef CONFIG_AT24XX_WRITE_TIMEOUT_MS
152 # define CONFIG_AT24XX_WRITE_TIMEOUT_MS 20
153 #endif
154 
155 /************************************************************************************
156  * Private Types
157  ************************************************************************************/
158 
159 /* This type represents the state of the MTD device. The struct mtd_dev_s
160  * must appear at the beginning of the definition so that you can freely
161  * cast between pointers to struct mtd_dev_s and struct at24c_dev_s.
162  */
163 
164 struct at24c_dev_s {
165  struct mtd_dev_s mtd; /* MTD interface */
166  FAR struct i2c_master_s *dev; /* Saved I2C interface instance */
167  uint8_t addr; /* I2C address */
168  uint16_t pagesize; /* 32, 63 */
169  uint16_t npages; /* 128, 256, 512, 1024 */
170 
174 };
175 
176 /************************************************************************************
177  * Private Function Prototypes
178  ************************************************************************************/
179 
180 /* MTD driver methods */
181 
182 static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
183 static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
184  size_t nblocks, FAR uint8_t *buf);
185 static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
186  size_t nblocks, FAR const uint8_t *buf);
187 static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
188 
189 void at24c_test(void);
190 int at24c_nuke(void);
191 
192 /************************************************************************************
193  * Private Data
194  ************************************************************************************/
195 
196 /* At present, only a single AT24 part is supported. In this case, a statically
197  * allocated state structure may be used.
198  */
199 
200 static struct at24c_dev_s g_at24c;
201 
202 /************************************************************************************
203  * Private Functions
204  ************************************************************************************/
205 
206 static int at24c_eraseall(FAR struct at24c_dev_s *priv)
207 {
208  int startblock = 0;
209  uint8_t buf[AT24XX_PAGESIZE + 2];
210 
211  struct i2c_msg_s msgv[1] = {
212  {
213  .frequency = 400000,
214  .addr = priv->addr,
215  .flags = 0,
216  .buffer = &buf[0],
217  .length = sizeof(buf),
218  }
219  };
220 
221  memset(&buf[2], 0xff, priv->pagesize);
222 
223  BOARD_EEPROM_WP_CTRL(false);
224 
225  for (startblock = 0; startblock < priv->npages; startblock++) {
226  uint16_t offset = startblock * priv->pagesize;
227  buf[1] = offset & 0xff;
228  buf[0] = (offset >> 8) & 0xff;
229 
230  while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) {
231  fwarn("erase stall\n");
232  px4_usleep(10000);
233  }
234  }
235 
236  BOARD_EEPROM_WP_CTRL(true);
237 
238  return OK;
239 }
240 
241 /************************************************************************************
242  * Name: at24c_erase
243  ************************************************************************************/
244 
245 static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
246 {
247  /* EEprom need not erase */
248 
249  return (int)nblocks;
250 }
251 
252 /************************************************************************************
253  * Name: at24c_test
254  ************************************************************************************/
255 
256 void at24c_test(void)
257 {
258  uint8_t buf[CONFIG_AT24XX_MTD_BLOCKSIZE];
259  unsigned count = 0;
260  unsigned errors = 0;
261 
262  for (count = 0; count < 10000; count++) {
263  ssize_t result = at24c_bread(&g_at24c.mtd, 0, 1, buf);
264 
265  if (result == ERROR) {
266  if (errors++ > 2) {
267  syslog(LOG_INFO, "too many errors\n");
268  return;
269  }
270 
271  } else if (result != 1) {
272  syslog(LOG_INFO, "unexpected %u\n", result);
273  }
274 
275  if ((count % 100) == 0) {
276  syslog(LOG_INFO, "test %u errors %u\n", count, errors);
277  }
278  }
279 }
280 
281 /************************************************************************************
282  * Name: at24c_bread
283  ************************************************************************************/
284 
285 static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
286  size_t nblocks, FAR uint8_t *buffer)
287 {
288  FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
289  size_t blocksleft;
290  uint8_t addr[2];
291  int ret;
292 
293  struct i2c_msg_s msgv[2] = {
294  {
295  .frequency = 400000,
296  .addr = priv->addr,
297  .flags = 0,
298  .buffer = &addr[0],
299  .length = sizeof(addr),
300  },
301  {
302  .frequency = 400000,
303  .addr = priv->addr,
304  .flags = I2C_M_READ,
305  .buffer = 0,
306  .length = priv->pagesize,
307  }
308  };
309 
310 #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
313 #endif
314  blocksleft = nblocks;
315 
316  finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
317 
318  if (startblock >= priv->npages) {
319  return 0;
320  }
321 
322  if (startblock + nblocks > priv->npages) {
323  nblocks = priv->npages - startblock;
324  }
325 
326  while (blocksleft-- > 0) {
327  uint16_t offset = startblock * priv->pagesize;
328  unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS;
329 
330  addr[1] = offset & 0xff;
331  addr[0] = (offset >> 8) & 0xff;
332  msgv[1].buffer = buffer;
333 
334  for (;;) {
335 
336  perf_begin(priv->perf_transfers);
337  ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
338  perf_end(priv->perf_transfers);
339 
340  if (ret >= 0) {
341  break;
342  }
343 
344  finfo("read stall");
345  px4_usleep(1000);
346 
347  /* We should normally only be here on the first read after
348  * a write.
349  *
350  * XXX maybe do special first-read handling with optional
351  * bus reset as well?
352  */
354 
355  if (--tries == 0) {
356  perf_count(priv->perf_errors);
357  return ERROR;
358  }
359  }
360 
361  startblock++;
362  buffer += priv->pagesize;
363  }
364 
365 #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
366  return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
367 #else
368  return nblocks;
369 #endif
370 }
371 
372 /************************************************************************************
373  * Name: at24c_bwrite
374  *
375  * Operates on MTD block's and translates to FLASH pages
376  *
377  ************************************************************************************/
378 
379 static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
380  FAR const uint8_t *buffer)
381 {
382  FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
383  size_t blocksleft;
384  uint8_t buf[AT24XX_PAGESIZE + 2];
385  int ret;
386 
387  struct i2c_msg_s msgv[1] = {
388  {
389  .frequency = 400000,
390  .addr = priv->addr,
391  .flags = 0,
392  .buffer = &buf[0],
393  .length = sizeof(buf),
394  }
395  };
396 
397 #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
400 #endif
401  blocksleft = nblocks;
402 
403  if (startblock >= priv->npages) {
404  return 0;
405  }
406 
407  if (startblock + nblocks > priv->npages) {
408  nblocks = priv->npages - startblock;
409  }
410 
411  finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
412 
413  BOARD_EEPROM_WP_CTRL(false);
414 
415  while (blocksleft-- > 0) {
416  uint16_t offset = startblock * priv->pagesize;
417  unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS;
418 
419  buf[1] = offset & 0xff;
420  buf[0] = (offset >> 8) & 0xff;
421  memcpy(&buf[2], buffer, priv->pagesize);
422 
423  for (;;) {
424 
425  perf_begin(priv->perf_transfers);
426  ret = I2C_TRANSFER(priv->dev, &msgv[0], 1);
427  perf_end(priv->perf_transfers);
428 
429  if (ret >= 0) {
430  break;
431  }
432 
433  finfo("write stall");
434  px4_usleep(1000);
435 
436  /* We expect to see a number of retries per write cycle as we
437  * poll for write completion.
438  */
439  if (--tries == 0) {
440  perf_count(priv->perf_errors);
441  BOARD_EEPROM_WP_CTRL(true);
442  return ERROR;
443  }
444  }
445 
446  startblock++;
447  buffer += priv->pagesize;
448  }
449 
450  BOARD_EEPROM_WP_CTRL(true);
451 
452 #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
453  return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
454 #else
455  return nblocks;
456 #endif
457 }
458 
459 /************************************************************************************
460  * Name: at24c_ioctl
461  ************************************************************************************/
462 
463 static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
464 {
465  FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
466  int ret = -EINVAL; /* Assume good command with bad parameters */
467 
468  finfo("cmd: %d \n", cmd);
469 
470  switch (cmd) {
471  case MTDIOC_GEOMETRY: {
472  FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
473 
474  if (geo) {
475  /* Populate the geometry structure with information need to know
476  * the capacity and how to access the device.
477  *
478  * NOTE: that the device is treated as though it where just an array
479  * of fixed size blocks. That is most likely not true, but the client
480  * will expect the device logic to do whatever is necessary to make it
481  * appear so.
482  *
483  * blocksize:
484  * May be user defined. The block size for the at24XX devices may be
485  * larger than the page size in order to better support file systems.
486  * The read and write functions translate BLOCKS to pages for the
487  * small flash devices
488  * erasesize:
489  * It has to be at least as big as the blocksize, bigger serves no
490  * purpose.
491  * neraseblocks
492  * Note that the device size is in kilobits and must be scaled by
493  * 1024 / 8
494  */
495 
496 #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
497  geo->blocksize = CONFIG_AT24XX_MTD_BLOCKSIZE;
498  geo->erasesize = CONFIG_AT24XX_MTD_BLOCKSIZE;
499  geo->neraseblocks = (CONFIG_AT24XX_SIZE * 1024 / 8) / CONFIG_AT24XX_MTD_BLOCKSIZE;
500 #else
501  geo->blocksize = priv->pagesize;
502  geo->erasesize = priv->pagesize;
503  geo->neraseblocks = priv->npages;
504 #endif
505  ret = OK;
506 
507  finfo("blocksize: %d erasesize: %d neraseblocks: %d\n",
508  geo->blocksize, geo->erasesize, geo->neraseblocks);
509  }
510  }
511  break;
512 
513  case MTDIOC_BULKERASE:
514  ret = at24c_eraseall(priv);
515  break;
516 
517  case MTDIOC_XIPBASE:
518  default:
519  ret = -ENOTTY; /* Bad command */
520  break;
521  }
522 
523  return ret;
524 }
525 
526 /************************************************************************************
527  * Public Functions
528  ************************************************************************************/
529 
530 /************************************************************************************
531  * Name: at24c_initialize
532  *
533  * Description:
534  * Create an initialize MTD device instance. MTD devices are not registered
535  * in the file system, but are created as instances that can be bound to
536  * other functions (such as a block or character driver front end).
537  *
538  ************************************************************************************/
539 
540 FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_master_s *dev)
541 {
542  FAR struct at24c_dev_s *priv;
543 
544  finfo("dev: %p\n", dev);
545 
546  /* Allocate a state structure (we allocate the structure instead of using
547  * a fixed, static allocation so that we can handle multiple FLASH devices.
548  * The current implementation would handle only one FLASH part per I2C
549  * device (only because of the SPIDEV_FLASH definition) and so would have
550  * to be extended to handle multiple FLASH parts on the same I2C bus.
551  */
552 
553  priv = &g_at24c;
554 
555  if (priv) {
556  /* Initialize the allocated structure */
557 
558  priv->addr = CONFIG_AT24XX_ADDR;
559  priv->pagesize = AT24XX_PAGESIZE;
560  priv->npages = AT24XX_NPAGES;
561 
562  priv->mtd.erase = at24c_erase;
563  priv->mtd.bread = at24c_bread;
564  priv->mtd.bwrite = at24c_bwrite;
565  priv->mtd.ioctl = at24c_ioctl;
566  priv->dev = dev;
567 
568  priv->perf_transfers = perf_alloc(PC_ELAPSED, "eeprom_trans");
569  priv->perf_resets_retries = perf_alloc(PC_COUNT, "eeprom_rst");
570  priv->perf_errors = perf_alloc(PC_COUNT, "eeprom_errs");
571  }
572 
573  /* attempt to read to validate device is present */
574  unsigned char buf[5];
575  uint8_t addrbuf[2] = {0, 0};
576 
577  struct i2c_msg_s msgv[2] = {
578  {
579  .frequency = 400000,
580  .addr = priv->addr,
581  .flags = 0,
582  .buffer = &addrbuf[0],
583  .length = sizeof(addrbuf),
584  },
585  {
586  .frequency = 400000,
587  .addr = priv->addr,
588  .flags = I2C_M_READ,
589  .buffer = &buf[0],
590  .length = sizeof(buf),
591  }
592  };
593 
594  BOARD_EEPROM_WP_CTRL(true);
595 
596  perf_begin(priv->perf_transfers);
597  int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
598  perf_end(priv->perf_transfers);
599 
600  if (ret < 0) {
601  return NULL;
602  }
603 
604  /* Return the implementation-specific state structure as the MTD device */
605 
606  finfo("Return %p\n", priv);
607  return (FAR struct mtd_dev_s *)priv;
608 }
609 
610 /*
611  * XXX: debug hackery
612  */
613 int at24c_nuke(void)
614 {
615  return at24c_eraseall(&g_at24c);
616 }
#define CONFIG_AT24XX_ADDR
Definition: 24xxxx_mtd.c:95
uint16_t pagesize
Definition: 24xxxx_mtd.c:168
uint16_t npages
Definition: 24xxxx_mtd.c:169
perf_counter_t perf_resets_retries
Definition: 24xxxx_mtd.c:172
measure the time elapsed performing an event
Definition: perf_counter.h:56
static uint32_t nblocks
Definition: reflect.c:55
FAR struct i2c_master_s * dev
Definition: 24xxxx_mtd.c:166
static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, FAR uint8_t *buf)
Definition: 24xxxx_mtd.c:285
struct mtd_dev_s mtd
Definition: 24xxxx_mtd.c:165
uint8_t addr
Definition: 24xxxx_mtd.c:167
count the number of times an event occurs
Definition: perf_counter.h:55
#define CONFIG_AT24XX_MTD_BLOCKSIZE
Definition: 24xxxx_mtd.c:145
void perf_count(perf_counter_t handle)
Count a performance event.
perf_counter_t perf_errors
Definition: 24xxxx_mtd.c:173
#define AT24XX_PAGESIZE
Definition: 24xxxx_mtd.c:124
Header common to all counters.
void at24c_test(void)
Definition: 24xxxx_mtd.c:256
#define perf_alloc(a, b)
Definition: px4io.h:59
#define CONFIG_AT24XX_SIZE
Definition: 24xxxx_mtd.c:88
void perf_end(perf_counter_t handle)
End a performance event.
static struct at24c_dev_s g_at24c
Definition: 24xxxx_mtd.c:200
static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
Definition: 24xxxx_mtd.c:463
#define AT24XX_NPAGES
Definition: 24xxxx_mtd.c:123
perf_counter_t perf_transfers
Definition: 24xxxx_mtd.c:171
#define OK
Definition: uavcan_main.cpp:71
static int at24c_eraseall(FAR struct at24c_dev_s *priv)
Definition: 24xxxx_mtd.c:206
int at24c_nuke(void)
Definition: 24xxxx_mtd.c:613
FAR struct mtd_dev_s * at24c_initialize(FAR struct i2c_master_s *dev)
Definition: 24xxxx_mtd.c:540
void perf_begin(perf_counter_t handle)
Begin a performance event.
static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
Definition: 24xxxx_mtd.c:245
static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, FAR const uint8_t *buf)
Definition: 24xxxx_mtd.c:379
Performance measuring tools.
#define CONFIG_AT24XX_WRITE_TIMEOUT_MS
Definition: 24xxxx_mtd.c:152