APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16 
17 (c) 2017 night_ghost@ykoctpa.ru
18 
19 
20  This uses 2*16k pages of FLASH ROM to emulate an EEPROM
21  This storage is retained after power down, and survives reloading of firmware via bootloader
22  All multi-byte accesses are reduced to single byte access so that can span EEPROM block boundaries
23 
24  http://www.st.com/content/ccc/resource/technical/document/application_note/ec/dd/8e/a8/39/49/4f/e5/DM00036065.pdf/files/DM00036065.pdf/jcr:content/translations/en.DM00036065.pdf
25 
26  problems of such design
27  http://ithare.com/journaled-flash-storage-emulating-eeprom-over-flash-acid-transactions-and-more-part-ii-existing-implementations-by-atmel-silabs-ti-stm-and-microchip/
28 
29 "partial write" problem fixed by requiring that highest bit of address should be 0
30 
31  */
32 #include <AP_HAL/AP_HAL.h>
33 
34 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
35 
36 #pragma GCC optimize ("O2")
37 
38 #include <string.h>
39 #include "Storage.h"
40 #include "EEPROM.h"
41 #include "Scheduler.h"
42 
43 using namespace F4Light;
44 
45 extern const AP_HAL::HAL& hal;
46 
47 // The EEPROM class uses 2x16k FLASH ROM pages to emulate up to 8k of EEPROM.
48 
49 #if defined(WRITE_IN_THREAD)
50 volatile uint16_t Storage::rd_ptr = 0;
51 volatile uint16_t Storage::wr_ptr = 0;
53 void *Storage::_task;
54 #endif
55 
56 
57 #if defined(EEPROM_CACHED)
58 uint8_t Storage::eeprom_buffer[BOARD_STORAGE_SIZE] IN_CCM;
59 #endif
60 
61 
62 // This is the size of each FLASH ROM page
63 const uint32_t pageSize = 0x4000; // real page size
64 
65 // This defines the base addresses of the 2 FLASH ROM pages that will be used to emulate EEPROM
66 // These are the 2 16k pages in the FLASH ROM address space on the STM32F4 used by HAL
67 // This will effectively provide a total of 8kb of emulated EEPROM storage
68 const uint32_t pageBase0 = 0x08008000; // Page2
69 const uint32_t pageBase1 = 0x0800c000; // Page3
70 
71 // it is possible to move EEPROM area to sectors 1&2 to free sector 3 for code (firmware from 0x0800c000)
72 // or use 3 sectors for EEPROM as wear leveling
73 
76 
77 
79 {}
80 
81 
82 void Storage::late_init(bool defer) {
83  write_deferred = defer;
85 }
86 
87 void Storage::error_parse(uint16_t status){
88  switch(status) {
89  case EEPROM_NO_VALID_PAGE: // despite repeated attempts, EEPROM does not work, but should
90  AP_HAL::panic("EEPROM Error: no valid page\r\n");
91  break;
92 
93  case EEPROM_OUT_SIZE:
94  AP_HAL::panic("EEPROM Error: full\r\n");
95  break;
96 
97  case EEPROM_BAD_FLASH: //
98  AP_HAL::panic("EEPROM Error: page not empty after erase\r\n");
99  break;
100 
101  case EEPROM_WRITE_FAILED:
102  AP_HAL::panic("EEPROM Error: write failed\r\n");
103  break;
104 
105  case EEPROM_BAD_ADDRESS: // just not found
106  case EEPROM_NOT_INIT: // can't be
107  default:
108  break; // all OK
109  }
110 }
111 
112 
114 {
116 
117 #if defined(EEPROM_CACHED)
118  uint16_t i;
119  for(i=0; i<BOARD_STORAGE_SIZE;i+=2){ // read out all data to RAM buffer
120 
121 #pragma GCC diagnostic push
122 #pragma GCC diagnostic ignored "-Wcast-align" // yes I know
123 
124  error_parse( eeprom.read(i >> 1, (uint16_t *)&eeprom_buffer[i]));
125 #pragma GCC diagnostic pop
126  }
127 #endif
128 
129 
130  _task = Scheduler::start_task(write_thread, 512); // small stack
131  if(_task){
132  Scheduler::set_task_priority(_task, MAIN_PRIORITY+2); // slightly less
133  }
134 }
135 
136 uint8_t Storage::read_byte(uint16_t loc){
137 
138 #if defined(EEPROM_CACHED)
139  return eeprom_buffer[loc];
140 #else
141  return _read_byte(loc);
142 #endif
143 }
144 
145 uint8_t Storage::_read_byte(uint16_t loc){
146 
147  // 'bytes' are packed 2 per word
148  // Read existing dataword and use upper or lower byte
149 
150  uint16_t data;
151  error_parse( eeprom.read(loc >> 1, &data) );
152 
153  if (loc & 1)
154  return data >> 8; // Odd, upper byte
155  else
156  return data & 0xff; // Even lower byte
157 }
158 
159 
160 
161 void Storage::read_block(void* dst, uint16_t loc, size_t n) {
162 #if defined(EEPROM_CACHED)
163  memmove(dst, &eeprom_buffer[loc], n);
164 #else
165  // Treat as a block of bytes
166  uint8_t *ptr_b=(uint8_t *)dst;
167 
168  if(loc & 1){
169  *ptr_b++ = read_byte(loc++);
170  n--;
171  }
172 
173 #pragma GCC diagnostic push
174 #pragma GCC diagnostic ignored "-Wcast-align"
175  uint16_t *ptr_w=(uint16_t *)ptr_b;
176 #pragma GCC diagnostic pop
177 
178  while(n>=2){
179  error_parse( eeprom.read(loc >> 1, ptr_w++) );
180  loc+=2;
181  n-=2;
182  }
183 
184  if(n){
185  ptr_b=(uint8_t *)ptr_w;
186  *ptr_b = read_byte(loc);
187  }
188 #endif
189 }
190 
191 void Storage::write_byte(uint16_t loc, uint8_t value){
192 #if defined(EEPROM_CACHED)
193  if(eeprom_buffer[loc]==value) return;
194  eeprom_buffer[loc]=value;
195 
196  if(write_deferred && hal.util->get_soft_armed()) return; // no changes in EEPROM, just in memory
197 
198 #endif
199  _write_byte(loc,value);
200 }
201 
202 void Storage::_write_byte(uint16_t loc, uint8_t value){
203  // 'bytes' are packed 2 per word
204  // Read existing data word and change upper or lower byte
205  uint16_t data;
206 
207 #if defined(EEPROM_CACHED)
208  memmove(&data,&eeprom_buffer[loc & ~1], 2); // read current value from cache
209 #else
210  error_parse(eeprom.read(loc >> 1, &data)); // read current value
211 #endif
212 
213  if (loc & 1)
214  data = (data & 0x00ff) | (value << 8); // Odd, upper byte
215  else
216  data = (data & 0xff00) | value; // Even, lower byte
217  write_word(loc >> 1, data);
218 }
219 
220 
221 void Storage::write_block(uint16_t loc, const void* src, size_t n)
222 {
223 #if defined(EEPROM_CACHED)
224  memmove(&eeprom_buffer[loc], src, n);
225 
226  if(write_deferred && hal.util->get_soft_armed()) return; // no changes in EEPROM, just in memory
227 
228 #endif
229 
230  uint8_t *ptr_b = (uint8_t *)src; // Treat as a block of bytes
231  if(loc & 1){
232  _write_byte(loc++, *ptr_b++); // odd byte
233  n--;
234  }
235 
236 #pragma GCC diagnostic push
237 #pragma GCC diagnostic ignored "-Wcast-align"
238  uint16_t *ptr_w = (uint16_t *)ptr_b; // Treat as a block of words
239 #pragma GCC diagnostic pop
240  while(n>=2){
241  write_word(loc >> 1, *ptr_w++);
242  loc+=2;
243  n-=2;
244  }
245 
246  if(n){ // the last one
247  ptr_b=(uint8_t *)ptr_w;
248  _write_byte(loc, *ptr_b); // odd byte
249  }
250 }
251 
252 void Storage::do_on_disarm(){ // save changes to EEPROM
253  uint16_t i;
254  for(i=0; i<BOARD_STORAGE_SIZE; i+=2){
255  uint16_t data;
256  error_parse(eeprom.read(i >> 1, &data));
257 #pragma GCC diagnostic push
258 #pragma GCC diagnostic ignored "-Wcast-align"
259  uint16_t b_data = *((uint16_t *)&eeprom_buffer[i]);
260 #pragma GCC diagnostic pop
261 
262  if(b_data!=data){
263  write_word(i >> 1, b_data);
264  }
265  }
266 }
267 
268 void Storage::write_word(uint16_t loc, uint16_t data){
269 #if defined(WRITE_IN_THREAD)
270 
271  Item &d = queue[wr_ptr];
272  d.loc=loc;
273  d.val=data;
274 
275  uint16_t new_wp = wr_ptr+1;
276 
277  if(new_wp >= EEPROM_QUEUE_LEN) { // move write pointer
278  new_wp=0; // ring
279  }
280 
281  while(new_wp == rd_ptr) { // buffer overflow
282  hal_yield(300); // wait for place
283  }
284 
285  wr_ptr=new_wp; // move forward
286 
287  Scheduler::set_task_active(_task); // activate write thread
288 #else
289  error_parse(eeprom.write(loc, data));
290 #endif
291 }
292 
293 #if defined(WRITE_IN_THREAD)
295  while(rd_ptr != wr_ptr) { // there are items
296  Item d = queue[rd_ptr++]; // get data and move to next item
297  if(rd_ptr >= EEPROM_QUEUE_LEN) { // move write pointer
298  rd_ptr=0; // ring
299  }
300  error_parse(eeprom.write(d.loc, d.val));
301  }
302 }
303 #endif
304 
305 #endif
306 
static void * _task
Definition: Storage.h:68
bool get_soft_armed() const
Definition: Util.h:15
static void do_on_disarm()
Definition: Storage.cpp:252
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
static uint8_t _read_byte(uint16_t loc)
Definition: Storage.cpp:145
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:161
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: Storage.cpp:10
#define BOARD_STORAGE_SIZE
Definition: board.h:134
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:221
static void set_task_priority(void *h, uint8_t prio)
Definition: Scheduler.h:282
static void _write_byte(uint16_t loc, uint8_t value)
Definition: Storage.cpp:202
AP_HAL::Util * util
Definition: HAL.h:115
static volatile uint16_t rd_ptr
Definition: Storage.h:65
static void register_on_disarm(Handler h)
Definition: Scheduler.h:460
static void error_parse(uint16_t status)
Definition: Storage.cpp:87
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void set_task_active(void *h)
Definition: Scheduler.h:306
uint8_t eeprom[0x1000]
Definition: eedump.c:8
#define EEPROM_QUEUE_LEN
Definition: Storage.h:50
static uint8_t read_byte(uint16_t loc)
Definition: Storage.cpp:136
const uint32_t pageBase0
Definition: Storage.cpp:68
Storage::Item Storage::queue [EEPROM_QUEUE_LEN] IN_CCM
Definition: Storage.cpp:52
#define MAIN_PRIORITY
Definition: Scheduler.h:24
static void write_thread()
Definition: Storage.cpp:294
static Item queue[EEPROM_QUEUE_LEN]
Definition: Storage.h:67
const uint32_t pageBase1
Definition: Storage.cpp:69
static void write_byte(uint16_t loc, uint8_t value)
Definition: Storage.cpp:191
float value
static volatile uint16_t wr_ptr
Definition: Storage.h:66
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
const uint32_t pageSize
Definition: Storage.cpp:63
static bool write_deferred
Definition: Storage.h:59
static void late_init(bool defer)
Definition: Storage.cpp:82
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
Definition: Scheduler.h:266
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
static void write_word(uint16_t loc, uint16_t value)
Definition: Storage.cpp:268