PX4 Firmware
PX4 Autopilot Software http://px4.io
flashfs.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 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 flashparam.c
36  *
37  * Global flash based parameter store.
38  *
39  * This provides the mechanisms to interface to the PX4
40  * parameter system but replace the IO with non file based flash
41  * i/o routines. So that the code my be implemented on a SMALL memory
42  * foot print device.
43  */
44 
45 #include <px4_platform_common/defines.h>
46 #include <px4_platform_common/posix.h>
47 #include <crc32.h>
48 #include <stddef.h>
49 #include <string.h>
50 #include <stdbool.h>
51 #include <stdint.h>
52 #include <stdlib.h>
53 #include <errno.h>
54 #include "flashfs.h"
55 #include <nuttx/compiler.h>
56 #include <nuttx/progmem.h>
57 
58 #if defined(CONFIG_ARCH_HAVE_PROGMEM)
59 
60 /****************************************************************************
61  * Pre-processor Definitions
62  ****************************************************************************/
63 
64 /****************************************************************************
65  * Private Types
66  ****************************************************************************/
67 
68 typedef uint32_t h_magic_t;
69 typedef uint16_t h_size_t;
70 typedef uint16_t h_flag_t;
71 typedef uint16_t data_size_t;
72 
73 typedef enum flash_config_t {
74  LargestBlock = 2 * 1024, // This represents the size need for backing store
75  MagicSig = 0xaa553cc3,
76  BlankSig = 0xffffffff
77 } flash_config_t;
78 
79 typedef enum flash_flags_t {
80  SizeMask = 0x0003,
81  MaskEntry = ~SizeMask,
82  BlankEntry = (h_flag_t)BlankSig,
83  ValidEntry = (0xa5ac & ~SizeMask),
84  ErasedEntry = 0x0000,
85 } flash_flags_t;
86 
87 
88 /* File flash_entry_header_t will be sizeof(h_magic_t) aligned
89  * The Size will be the actual length of the header plus the data
90  * and any padding needed to have the size be an even multiple of
91  * sizeof(h_magic_t)
92  * The
93  */
94 #pragma GCC diagnostic push
95 #pragma GCC diagnostic ignored "-Wattributes"
96 typedef begin_packed_struct struct flash_entry_header_t {
97  h_magic_t magic; /* Used to ID files*/
98  h_flag_t flag; /* Used to erase this entry */
99  uint32_t crc; /* Calculated over the size - end of data */
100  h_size_t size; /* When added to a byte pointer to flash_entry_header_t
101  * Will result the offset of the next active file or
102  * free space. */
103  flash_file_token_t file_token; /* file token type - essentially the name/type */
104 } end_packed_struct flash_entry_header_t;
105 #pragma GCC diagnostic pop
106 
107 /****************************************************************************
108  * Private Function Prototypes
109  ****************************************************************************/
110 
111 /****************************************************************************
112  * Private Data
113  ****************************************************************************/
114 static uint8_t *working_buffer;
115 static uint16_t working_buffer_size;
116 static bool working_buffer_static;
117 static sector_descriptor_t *sector_map;
118 static int last_erased;
119 
120 /****************************************************************************
121  * Public Data
122  ****************************************************************************/
123 
125  .n = {'p', 'a', 'r', 'm'},
126 };
127 
128 /****************************************************************************
129  * Private Functions
130  ****************************************************************************/
131 
132 /****************************************************************************
133  * Name: parameter_flashfs_free
134  *
135  * Description:
136  * Frees dynamically allocated memory
137  *
138  *
139  ****************************************************************************/
140 
141 void parameter_flashfs_free(void)
142 {
143  if (!working_buffer_static && working_buffer != NULL) {
144  free(working_buffer);
145  working_buffer = NULL;
146  working_buffer_size = 0;
147  }
148 }
149 
150 /****************************************************************************
151  * Name: blank_flash
152  *
153  * Description:
154  * This helper function returns true if the pointer points to a blank_flash
155  * location
156  *
157  * Input Parameters:
158  * pf - A pointer to memory aligned on sizeof(uint32_t) boundaries
159  *
160  * Returned value:
161  * true if blank
162  *
163  *
164  ****************************************************************************/
165 
166 static inline int blank_flash(uint32_t *pf)
167 {
168  return *pf == BlankSig;
169 }
170 
171 /****************************************************************************
172  * Name: blank_check
173  *
174  * Description:
175  * Given a pointer to a flash entry header and a new size
176  *
177  * Input Parameters:
178  * pf - A pointer to the current flash entry header
179  * new_size - The total number of bytes to be written
180  *
181  * Returned value:
182  * true if space is blank, If it is not blank it returns false
183  *
184  ****************************************************************************/
185 
186 static bool blank_check(flash_entry_header_t *pf,
187  size_t new_size)
188 {
189  bool rv = true;
190  uint32_t *pm = (uint32_t *) pf;
191  new_size /= sizeof(uint32_t);
192 
193  while (new_size-- && rv) {
194  if (!blank_flash(pm++)) {
195  rv = false;
196  }
197  }
198 
199  return rv;
200 }
201 
202 /****************************************************************************
203  * Name: valid_magic
204  *
205  * Description:
206  * This helper function returns true if the pointer points to a valid
207  * magic signature
208  *
209  * Input Parameters:
210  * pm - A pointer to memory aligned on sizeof(h_magic_t) boundaries
211  *
212  * Returned value:
213  * true if magic is valid
214  *
215  *
216  ****************************************************************************/
217 
218 static inline int valid_magic(h_magic_t *pm)
219 {
220  return *pm == MagicSig;
221 }
222 
223 /****************************************************************************
224  * Name: blank_magic
225  *
226  * Description:
227  * This helper function returns true if the pointer points to a valid
228  * blank magic signature
229  *
230  * Input Parameters:
231  * pm - A pointer to memory aligned on sizeof(h_magic_t) boundaries
232  *
233  * Returned value:
234  * true if magic is valid
235  *
236  *
237  ****************************************************************************/
238 
239 static inline int blank_magic(h_magic_t *pm)
240 {
241  return *pm == BlankSig;
242 }
243 /****************************************************************************
244  * Name: erased_entry
245  *
246  * Description:
247  * This helper function returns true if the entry is Erased
248  *
249  * Input Parameters:
250  * fi - A pointer to the current flash entry header
251  *
252  * Returned value:
253  * true if erased
254  *
255  *
256  ****************************************************************************/
257 
258 static inline int erased_entry(flash_entry_header_t *fi)
259 {
260  return (fi->flag & MaskEntry) == ErasedEntry;
261 }
262 
263 /****************************************************************************
264  * Name: blank_entry
265  *
266  * Description:
267  * This helper function returns true if the entry is Blank
268  *
269  * Input Parameters:
270  * fi - A pointer to the current flash entry header
271  *
272  * Returned value:
273  * true if Blank
274  *
275  *
276  ****************************************************************************/
277 
278 static inline int blank_entry(flash_entry_header_t *fi)
279 {
280  return fi->magic == BlankSig && fi->flag == BlankEntry;
281 }
282 
283 /****************************************************************************
284  * Name: valid_entry
285  *
286  * Description:
287  * This helper function returns true if the entry is Blank
288  *
289  * Input Parameters:
290  * fi - A pointer to the current flash entry header
291  *
292  * Returned value:
293  * true if valid_entry
294  *
295  *
296  ****************************************************************************/
297 
298 static inline int valid_entry(flash_entry_header_t *fi)
299 {
300  return (fi->flag & MaskEntry) == ValidEntry;
301 }
302 
303 /****************************************************************************
304  * Name: entry_size_adjust
305  *
306  * Description:
307  * This helper function returns the size adjust
308  *
309  * Input Parameters:
310  * fi - A pointer to the current flash entry header
311  *
312  * Returned value:
313  * true if valid_entry
314  *
315  *
316  ****************************************************************************/
317 
318 static inline int entry_size_adjust(flash_entry_header_t *fi)
319 {
320  return fi->flag & SizeMask;
321 }
322 
323 /****************************************************************************
324  * Name: next_entry
325  *
326  * Description:
327  * This helper function advances the flash entry header pointer to the
328  * locations of the next entry.
329  *
330  * Input Parameters:
331  * fh - A pointer to the current file header
332  *
333  * Returned value:
334  * - A pointer to the next file header location
335  *
336  *
337  ****************************************************************************/
338 
339 static inline flash_entry_header_t *next_entry(flash_entry_header_t *fi)
340 {
341  uint8_t *pb = (uint8_t *)fi;
342  return (flash_entry_header_t *) &pb[fi->size];
343 }
344 
345 /****************************************************************************
346  * Name: entry_data
347  *
348  * Description:
349  * This helper function returns a pointer the the data in the entry
350  *
351  * Input Parameters:
352  * fh - A pointer to the current file header
353  *
354  * Returned value:
355  * - A pointer to the next file header location
356  *
357  *
358  ****************************************************************************/
359 
360 static inline uint8_t *entry_data(flash_entry_header_t *fi)
361 {
362  return ((uint8_t *)fi) + sizeof(flash_entry_header_t);
363 }
364 
365 /****************************************************************************
366  * Name: entry_data_length
367  *
368  * Description:
369  * This helper function returns the size of the user data
370  *
371  * Input Parameters:
372  * fh - A pointer to the current file header
373  *
374  * Returned value:
375  * - The length of the data in the entry
376  *
377  *
378  ****************************************************************************/
379 
380 static inline data_size_t entry_data_length(flash_entry_header_t *fi)
381 {
382  return fi->size - (sizeof(flash_entry_header_t) + entry_size_adjust(fi));
383 }
384 
385 /****************************************************************************
386  * Name: entry_crc_start
387  *
388  * Description:
389  * This helper function returns a const byte pointer to the location
390  * where the CRC is calculated over
391  *
392  * Input Parameters:
393  * fi - A pointer to the current file header
394  *
395  * Returned value:
396  * A pointer to the point at which the crc is calculated from.
397  *
398  *
399  ****************************************************************************/
400 
401 static inline const uint8_t *entry_crc_start(flash_entry_header_t *fi)
402 {
403  return (const uint8_t *)&fi->size;
404 }
405 
406 /****************************************************************************
407  * Name: entry_crc_length
408  *
409  * Description:
410  * This helper function returns the length of the regone where the CRC is
411  * calculated over
412  *
413  * Input Parameters:
414  * fi - A pointer to the current file header
415  *
416  * Returned value:
417  * Number of bytes to to crc
418  *
419  *
420  ****************************************************************************/
421 
422 static inline data_size_t entry_crc_length(flash_entry_header_t *fi)
423 {
424  return fi->size - offsetof(flash_entry_header_t, size);
425 }
426 
427 /****************************************************************************
428  * Name: find_entry
429  *
430  * Description:
431  * This helper function locates an "file" from the the file token
432  *
433  * Input Parameters:
434  * token - A flash file token, the pseudo file name
435  *
436  * Returned value:
437  * On Success a pointer to flash entry header or NULL on failure
438  *
439  *
440  ****************************************************************************/
441 
442 static flash_entry_header_t *find_entry(flash_file_token_t token)
443 {
444  for (int s = 0; sector_map[s].address; s++) {
445 
446  h_magic_t *pmagic = (h_magic_t *) sector_map[s].address;
447  h_magic_t *pe = pmagic + (sector_map[s].size / sizeof(h_magic_t)) - 1;
448 
449  /* Hunt for Magic Signature */
450 cont:
451 
452  while (pmagic != pe && !valid_magic(pmagic)) {
453  pmagic++;
454  }
455 
456  /* Did we reach the end
457  * if so try the next sector */
458 
459  if (pmagic == pe) { continue; }
460 
461  /* Found a magic So assume it is a file header */
462 
463  flash_entry_header_t *pf = (flash_entry_header_t *) pmagic;
464 
465  /* Test the CRC */
466 
467  if (pf->crc == crc32(entry_crc_start(pf), entry_crc_length(pf))) {
468 
469  /* Good CRC is it the one we are looking for ?*/
470 
471  if (valid_entry(pf) && pf->file_token.t == token.t) {
472 
473  return pf;
474 
475  } else {
476 
477  /* Not the one we wanted but we can trust the size */
478 
479  pf = next_entry(pf);
480  pmagic = (h_magic_t *) pf;
481 
482  /* If the next one is erased */
483 
484  if (blank_entry(pf)) {
485  continue;
486  }
487  }
488 
489  goto cont;
490 
491  } else {
492 
493  /* in valid CRC so keep looking */
494 
495  pmagic++;
496  }
497  }
498 
499  return NULL;
500 }
501 
502 /****************************************************************************
503  * Name: find_free
504  *
505  * Description:
506  * This helper function locates free space for the number of bytes required
507  *
508  * Input Parameters:
509  * required - Number of bytes required
510  *
511  * Returned value:
512  * On Success a pointer to flash entry header or NULL on failure
513  *
514  *
515  ****************************************************************************/
516 
517 static flash_entry_header_t *find_free(data_size_t required)
518 {
519  for (int s = 0; sector_map[s].address; s++) {
520 
521  h_magic_t *pmagic = (h_magic_t *) sector_map[s].address;
522  h_magic_t *pe = pmagic + (sector_map[s].size / sizeof(h_magic_t)) - 1;
523 
524  /* Hunt for Magic Signature */
525 
526  do {
527 
528  if (valid_magic(pmagic)) {
529 
530  flash_entry_header_t *pf = (flash_entry_header_t *) pmagic;
531 
532  /* Test the CRC */
533 
534  if (pf->crc == crc32(entry_crc_start(pf), entry_crc_length(pf))) {
535 
536  /* Valid Magic and CRC look for the next record*/
537 
538  pmagic = ((uint32_t *) next_entry(pf));
539 
540  } else {
541 
542  pmagic++;
543  }
544  }
545 
546  if (blank_magic(pmagic)) {
547 
548  flash_entry_header_t *pf = (flash_entry_header_t *) pmagic;
549 
550  if (blank_entry(pf) && blank_check(pf, required)) {
551  return pf;
552  }
553 
554  }
555  } while (++pmagic != pe);
556  }
557 
558  return NULL;
559 }
560 
561 /****************************************************************************
562  * Name: get_next_sector_descriptor
563  *
564  * Description:
565  * Given a pointer to sector_descriptor_t, this helper function
566  * returns a pointer to the next sector_descriptor_t
567  *
568  * Input Parameters:
569  * current - A pointer to the current sector_descriptor_t
570  *
571  * Returned value:
572  * On Success A pointer to the next sector_descriptor_t,
573  * otherwise NULL
574  *
575  *
576  ****************************************************************************/
577 
578 static sector_descriptor_t *get_next_sector_descriptor(sector_descriptor_t *
579  current)
580 {
581  for (int s = 0; sector_map[s].address; s++) {
582  if (current == &sector_map[s]) {
583  if (sector_map[s + 1].address) {
584  s++;
585 
586  } else {
587  s = 0;
588  }
589 
590  return &sector_map[s];
591  }
592  }
593 
594  return NULL;
595 }
596 
597 /****************************************************************************
598  * Name: get_next_sector
599  *
600  * Description:
601  * Given a pointer to a flash entry header returns the sector descriptor
602  * for the file is located in
603  *
604  * Input Parameters:
605  * current - A pointer to the current flash entry header
606  *
607  * Returned value:
608  * On Success A pointer to the next sector_descriptor_t,
609  * otherwise NULL
610  *
611  *
612  ****************************************************************************/
613 
614 static sector_descriptor_t *get_sector_info(flash_entry_header_t *current)
615 {
616  for (int s = 0; sector_map[s].address != 0; s++) {
617  uint8_t *pb = (uint8_t *) sector_map[s].address;
618  uint8_t *pe = pb + sector_map[s].size - 1;
619  uint8_t *pc = (uint8_t *) current;
620 
621  if (pc >= pb && pc <= pe) {
622  return &sector_map[s];
623  }
624  }
625 
626  return 0;
627 }
628 
629 /****************************************************************************
630  * Name: erase_sector
631  *
632  * Description:
633  * Given a pointer to sector_descriptor_t, this function
634  * erases the sector and updates the last_erased using
635  * the pointer to the flash_entry_header_t as a sanity check
636  *
637  * Input Parameters:
638  * sm - A pointer to the current sector_descriptor_t
639  * pf - A pointer to the current flash entry header
640  *
641  * Returned value:
642  * O On Success or a negative errno
643  *
644  *
645  ****************************************************************************/
646 
647 static int erase_sector(sector_descriptor_t *sm, flash_entry_header_t *pf)
648 {
649  int rv = 0;
650  ssize_t block = up_progmem_getpage((size_t)pf);
651 
652  if (block > 0 && block == sm->page) {
653  last_erased = sm->page;
654  ssize_t size = up_progmem_eraseblock(block);
655 
656  if (size < 0 || size != (ssize_t)sm->size) {
657  rv = size;
658  }
659  }
660 
661  return rv;
662 }
663 
664 /****************************************************************************
665  * Name: erase_entry
666  *
667  * Description:
668  * Given a pointer to a flash entry header erases the entry
669  *
670  * Input Parameters:
671  * pf - A pointer to the current flash entry header
672  *
673  *
674  * Returned value:
675  * >0 On Success or a negative errno
676  *
677  *
678  ****************************************************************************/
679 
680 static int erase_entry(flash_entry_header_t *pf)
681 {
682  h_flag_t data = ErasedEntry;
683  size_t size = sizeof(h_flag_t);
684  int rv = up_progmem_write((size_t) &pf->flag, &data, size);
685  return rv;
686 }
687 
688 /****************************************************************************
689  * Name: check_free_space_in_sector
690  *
691  * Description:
692  * Given a pointer to a flash entry header and a new size
693  *
694  * Input Parameters:
695 * pf - A pointer to the current flash entry header
696  * new_size - The total number of bytes to be written
697  *
698  * Returned value:
699  * 0 if there is enough space left to write new size
700  * If not it returns the flash_file_sector_t * that needs to be erased.
701  *
702  ****************************************************************************/
703 
704 static sector_descriptor_t *check_free_space_in_sector(flash_entry_header_t
705  *pf, size_t new_size)
706 {
707  sector_descriptor_t *sm = get_sector_info(pf);
708  uint8_t *psector_first = (uint8_t *) sm->address;
709  uint8_t *psector_last = psector_first + sm->size - 1;
710  uint8_t *pnext_end = (uint8_t *)(valid_magic((h_magic_t *)pf) ? next_entry(pf) : pf) + new_size;
711 
712  if (pnext_end >= psector_first && pnext_end <= psector_last) {
713  sm = 0;
714  }
715 
716  return sm;
717 }
718 
719 /****************************************************************************
720  * Public Functions
721  ****************************************************************************/
722 /****************************************************************************
723  * Name: parameter_flashfs_read
724  *
725  * Description:
726  * This function returns a pointer to the locations of the data associated
727  * with the file token. On successful return *buffer will be set to Flash
728  * location and *buf_size the length of the user data.
729  *
730  * Input Parameters:
731  * token - File Token File to read
732  * buffer - A pointer to a pointer that will receive the address
733  * in flash of the data of this "files" data
734  * buf_size - A pointer to receive the number of bytes in the "file"
735  *
736  * Returned value:
737  * On success number of bytes read or a negative errno value,
738  *
739  *
740  ****************************************************************************/
741 
742 int parameter_flashfs_read(flash_file_token_t token, uint8_t **buffer, size_t
743  *buf_size)
744 {
745  int rv = -ENXIO;
746 
747  if (sector_map) {
748 
749  rv = -ENOENT;
750  flash_entry_header_t *pf = find_entry(token);
751 
752  if (pf) {
753  (*buffer) = entry_data(pf);
754  rv = entry_data_length(pf);
755  *buf_size = rv;
756  }
757  }
758 
759  return rv;
760 }
761 
762 /****************************************************************************
763  * Name: parameter_flashfs_write
764  *
765  * Description:
766  * This function writes user data from the buffer allocated with a previous call
767  * to parameter_flashfs_alloc. flash starting at the given address
768  *
769  * Input Parameters:
770  * token - File Token File to read
771  * buffer - A pointer to a buffer with buf_size bytes to be written
772  * to the flash. This buffer must be allocated
773  * with a previous call to parameter_flashfs_alloc
774  * buf_size - Number of bytes to write
775  *
776  * Returned value:
777  * On success the number of bytes written On Error a negative value of errno
778  *
779  ****************************************************************************/
780 
781 int
782 parameter_flashfs_write(flash_file_token_t token, uint8_t *buffer, size_t buf_size)
783 {
784  int rv = -ENXIO;
785 
786  if (sector_map) {
787 
788  rv = 0;
789 
790  /* Calculate the total space needed */
791 
792  size_t total_size = buf_size + sizeof(flash_entry_header_t);
793  size_t alignment = sizeof(h_magic_t) - 1;
794  size_t size_adjust = ((total_size + alignment) & ~alignment) - total_size;
795  total_size += size_adjust;
796 
797  /* Is this and existing entry */
798 
799  flash_entry_header_t *pf = find_entry(token);
800 
801  if (!pf) {
802 
803  /* No Entry exists for this token so find a place for it */
804 
805  pf = find_free(total_size);
806 
807  /* No Space */
808 
809  if (pf == 0) {
810  return -ENOSPC;
811  }
812 
813  } else {
814 
815  /* Do we have space after the entry in the sector for the update */
816 
817  sector_descriptor_t *current_sector = check_free_space_in_sector(pf,
818  total_size);
819 
820 
821  if (current_sector == 0) {
822 
823  /* Mark the last entry erased */
824 
825  /* todo:consider a 2 stage erase or write before erase and do a fs check
826  * at start up
827  */
828 
829  rv = erase_entry(pf);
830 
831  if (rv < 0) {
832  return rv;
833  }
834 
835  /* We had space and marked the last entry erased so use the Next Free */
836 
837  pf = next_entry(pf);
838 
839  } else {
840 
841  /*
842  * We did not have space in the current sector so select the next sector
843  */
844 
845  current_sector = get_next_sector_descriptor(current_sector);
846 
847  /* Will the data fit */
848 
849  if (current_sector->size < total_size) {
850  return -ENOSPC;
851  }
852 
853  /* Mark the last entry erased */
854 
855  /* todo:consider a 2 stage erase or write before erase and do a fs check
856  * at start up
857  */
858 
859  rv = erase_entry(pf);
860 
861  if (rv < 0) {
862  return rv;
863  }
864 
865  pf = (flash_entry_header_t *) current_sector->address;
866  }
867 
868  if (!blank_check(pf, total_size)) {
869  rv = erase_sector(current_sector, pf);
870  }
871  }
872 
873  flash_entry_header_t *pn = (flash_entry_header_t *)(buffer - sizeof(flash_entry_header_t));
874  pn->magic = MagicSig;
875  pn->file_token.t = token.t;
876  pn->flag = ValidEntry + size_adjust;
877  pn->size = total_size;
878 
879  for (size_t a = 0; a < size_adjust; a++) {
880  buffer[buf_size + a] = (uint8_t)BlankSig;
881  }
882 
883  pn->crc = crc32(entry_crc_start(pn), entry_crc_length(pn));
884  rv = up_progmem_write((size_t) pf, pn, pn->size);
885  int system_bytes = (sizeof(flash_entry_header_t) + size_adjust);
886 
887  if (rv >= system_bytes) {
888  rv -= system_bytes;
889  }
890  }
891 
892  return rv;
893 }
894 
895 /****************************************************************************
896  * Name: parameter_flashfs_alloc
897  *
898  * Description:
899  * This function is called to get a buffer to use in a subsequent call
900  * to parameter_flashfs_write. The address returned is advanced into the
901  * buffer to reserve space for the flash entry header.
902  * The caller is responsible to call parameter_flashfs_free after usage.
903  *
904  * Input Parameters:
905  * token - File Token File to read (not used)
906  * buffer - A pointer to return a pointer to Memory of buf_size length
907  * suitable for calling parameter_flashfs_write
908  * buf_size - In: the size needed for the write operation.
909  * Out: The maximum number of bytes that can be written to
910  * the buffer
911  *
912  * Returned value:
913  * On success the number of bytes written On Error a negative value of errno
914  *
915  ****************************************************************************/
916 
917 int parameter_flashfs_alloc(flash_file_token_t token, uint8_t **buffer, size_t *buf_size)
918 {
919  int rv = -ENXIO;
920 
921  if (sector_map) {
922 
923  rv = -ENOMEM;
924 
925  if (!working_buffer_static) {
926 
927  working_buffer_size = *buf_size + sizeof(flash_entry_header_t);
928  working_buffer = malloc(working_buffer_size);
929 
930  }
931 
932  /* Allocation failed or not provided */
933 
934  if (working_buffer == NULL) {
935 
936  working_buffer_size = 0;
937 
938  } else {
939 
940  /* We have a buffer reserve space and init it */
941  *buffer = &working_buffer[sizeof(flash_entry_header_t)];
942  *buf_size = working_buffer_size - sizeof(flash_entry_header_t);
943  memset(working_buffer, 0xff, working_buffer_size);
944  rv = 0;
945 
946  }
947  }
948 
949  return rv;
950 }
951 
952 /****************************************************************************
953  * Name: parameter_flashfs_erase
954  *
955  * Description:
956  * This function erases the sectors that were passed to parameter_flashfs_init
957  *
958  * Input Parameters:
959  *
960  * Returned value:
961  * On success the number of bytes erased
962  * On Error a negative value of errno
963  *
964  ****************************************************************************/
965 
966 int parameter_flashfs_erase(void)
967 {
968  int rv = -ENXIO;
969 
970  if (sector_map) {
971  rv = 0;
972 
973  for (int s = 0; sector_map[s].address; s++) {
974  int sz = erase_sector(&sector_map[s], (flash_entry_header_t *)sector_map[s].address);
975 
976  if (sz != 0) {
977  return sz;
978  }
979 
980  rv += sector_map[s].size;
981  }
982  }
983 
984  return rv;
985 }
986 
987 /****************************************************************************
988  * Name: parameter_flashfs_init
989  *
990  * Description:
991  * This helper function advances the flash entry header pointer to the
992  * locations of the next entry.
993  *
994  * Input Parameters:
995  * fconfig - A pointer to an null entry terminated array of
996  * flash_file_sector_t
997  * buffer - A pointer to a memory to make available to callers
998  * for write operations. When allocated to the caller
999  * space is reserved in the front for the
1000  * flash_entry_header_t.
1001  * If this is passes as NULL. The buffer will be
1002  * allocated from the heap on calls to
1003  * parameter_flashfs_alloc and fread on calls
1004  * to parameter_flashfs_free
1005  *
1006  * size - The size of the buffer in bytes. Should be be 0 if buffer
1007  * is NULL
1008  *
1009  * Returned value:
1010  * - A pointer to the next file header location
1011  *
1012  *
1013  ****************************************************************************/
1014 
1015 int parameter_flashfs_init(sector_descriptor_t *fconfig, uint8_t *buffer, uint16_t size)
1016 {
1017  int rv = 0;
1018  sector_map = fconfig;
1019  working_buffer_static = buffer != NULL;
1020 
1021  if (!working_buffer_static) {
1022  size = 0;
1023  }
1024 
1025  working_buffer = buffer;
1026  working_buffer_size = size;
1027  last_erased = -1;
1028 
1029  /* Sanity check */
1030 
1031  flash_entry_header_t *pf = find_entry(parameters_token);
1032 
1033  /* No paramaters */
1034 
1035  if (pf == NULL) {
1036  size_t total_size = size + sizeof(flash_entry_header_t);
1037  size_t alignment = sizeof(h_magic_t) - 1;
1038  size_t size_adjust = ((total_size + alignment) & ~alignment) - total_size;
1039  total_size += size_adjust;
1040 
1041  /* Do we have free space ?*/
1042 
1043  if (find_free(total_size) == NULL) {
1044 
1045  /* No paramates and no free space => neeed erase */
1046 
1047  rv = parameter_flashfs_erase();
1048  }
1049  }
1050 
1051  return rv;
1052 }
1053 
1054 #if defined(FLASH_UNIT_TEST)
1055 
1056 static sector_descriptor_t test_sector_map[] = {
1057  {1, 16 * 1024, 0x08004000},
1058  {2, 16 * 1024, 0x08008000},
1059  {0, 0, 0},
1060 };
1061 
1062 __EXPORT void test(void);
1063 
1064 uint8_t test_buf[32 * 1024];
1065 
1066 __EXPORT void test(void)
1067 {
1068  uint16_t largest_block = (32 * 1024) + 32;
1069  uint8_t *buffer = malloc(largest_block);
1070 
1071  parameter_flashfs_init(test_sector_map, buffer, largest_block);
1072 
1073  for (int t = 0; t < sizeof(test_buf); t++) {
1074  test_buf[t] = (uint8_t) t;
1075  }
1076 
1077  int er = parameter_flashfs_erase();
1078  uint8_t *fbuffer;
1079  size_t buf_size;
1080  int written = 0;
1081  int read = 0;
1082  int rv = 0;
1083 
1084  for (int a = 0; a <= 4; a++) {
1085  rv = parameter_flashfs_alloc(parameters_token, &fbuffer, &buf_size);
1086  memcpy(fbuffer, test_buf, a);
1087  buf_size = a;
1088  written = parameter_flashfs_write(parameters_token, fbuffer, buf_size);
1089  read = parameter_flashfs_read(parameters_token, &fbuffer, &buf_size);
1091 
1092  if (read != written) {
1093  static volatile int j;
1094  j++;
1095  }
1096  }
1097 
1098  int block = 2048;
1099 
1100  for (int a = 0; a <= 8; a++) {
1101  rv = parameter_flashfs_alloc(parameters_token, &fbuffer, &buf_size);
1102  memcpy(fbuffer, test_buf, block);
1103  buf_size = block;
1104  written = parameter_flashfs_write(parameters_token, fbuffer, buf_size);
1105  read = parameter_flashfs_read(parameters_token, &fbuffer, &buf_size);
1107 
1108  if (read != written) {
1109  static volatile int j;
1110  j++;
1111  }
1112 
1113  block += 2048;
1114  }
1115 
1116  rv++;
1117  er++;
1118  free(buffer);
1119 }
1120 #endif /* FLASH_UNIT_TEST */
1121 #endif /* CONFIG_ARCH_HAVE_PROGMEM */
flash_file_tokens_t t
Definition: flashfs.h:77
Definition: I2C.hpp:51
__EXPORT const flash_file_token_t parameters_token
__EXPORT void parameter_flashfs_free(void)
static void read(bootloader_app_shared_t *pshared)
uint8_t * data
Definition: dataman.cpp:149
__EXPORT int parameter_flashfs_alloc(flash_file_token_t ft, uint8_t **buffer, size_t *buf_size)
__EXPORT int parameter_flashfs_init(sector_descriptor_t *fconfig, uint8_t *buffer, uint16_t size)
void test(enum LPS25H_BUS busid)
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in p...
Definition: lps25h.cpp:792
uint32_t address
Definition: flashfs.h:103
Definition: reflect.c:56
__EXPORT int parameter_flashfs_read(flash_file_token_t ft, uint8_t **buffer, size_t *buf_size)
__EXPORT int parameter_flashfs_write(flash_file_token_t ft, uint8_t *buffer, size_t buf_size)
uint8_t n[sizeof(flash_file_tokens_t)]
Definition: flashfs.h:78
__EXPORT int parameter_flashfs_erase(void)