APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include <AP_HAL/AP_HAL.h>
19 
20 #include "Storage.h"
21 #include "hwdef/common/flash.h"
22 
23 using namespace ChibiOS;
24 
25 #ifndef HAL_USE_EMPTY_STORAGE
26 
27 extern const AP_HAL::HAL& hal;
28 
30 {
31  if (_initialised) {
32  return;
33  }
34 
36 
37 #if HAL_WITH_RAMTRON
38  using_fram = fram.init();
39  if (using_fram) {
40  if (!fram.read(0, _buffer, CH_STORAGE_SIZE)) {
41  return;
42  }
43  _initialised = true;
44  return;
45  }
46  // allow for FMUv3 with no FRAM chip, fall through to flash storage
47 #endif
48 
49  // load from storage backend
50  _flash_load();
51 
52  _initialised = true;
53 }
54 
55 /*
56  mark some lines as dirty. Note that there is no attempt to avoid
57  the race condition between this code and the _timer_tick() code
58  below, which both update _dirty_mask. If we lose the race then the
59  result is that a line is written more than once, but it won't result
60  in a line not being written.
61 */
62 void Storage::_mark_dirty(uint16_t loc, uint16_t length)
63 {
64  uint16_t end = loc + length;
65  for (uint16_t line=loc>>CH_STORAGE_LINE_SHIFT;
66  line <= end>>CH_STORAGE_LINE_SHIFT;
67  line++) {
68  _dirty_mask.set(line);
69  }
70 }
71 
72 void Storage::read_block(void *dst, uint16_t loc, size_t n)
73 {
74  if (loc >= sizeof(_buffer)-(n-1)) {
75  return;
76  }
77  _storage_open();
78  memcpy(dst, &_buffer[loc], n);
79 }
80 
81 void Storage::write_block(uint16_t loc, const void *src, size_t n)
82 {
83  if (loc >= sizeof(_buffer)-(n-1)) {
84  return;
85  }
86  if (memcmp(src, &_buffer[loc], n) != 0) {
87  _storage_open();
88  memcpy(&_buffer[loc], src, n);
89  _mark_dirty(loc, n);
90  }
91 }
92 
94 {
95  if (!_initialised || _dirty_mask.empty()) {
96  return;
97  }
98 
99 
100  // write out the first dirty line. We don't write more
101  // than one to keep the latency of this call to a minimum
102  uint16_t i;
103  for (i=0; i<CH_STORAGE_NUM_LINES; i++) {
104  if (_dirty_mask.get(i)) {
105  break;
106  }
107  }
108  if (i == CH_STORAGE_NUM_LINES) {
109  // this shouldn't be possible
110  return;
111  }
112 
113 #if HAL_WITH_RAMTRON
114  if (using_fram) {
115  if (fram.write(CH_STORAGE_LINE_SIZE*i, &_buffer[CH_STORAGE_LINE_SIZE*i], CH_STORAGE_LINE_SIZE)) {
116  _dirty_mask.clear(i);
117  }
118  return;
119  }
120 #endif
121 
122  // save to storage backend
123  _flash_write(i);
124 }
125 
126 /*
127  load all data from flash
128  */
130 {
131  _flash_page = STORAGE_FLASH_PAGE;
132 
133  hal.console->printf("Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1);
134 
135  if (!_flash.init()) {
136  AP_HAL::panic("unable to init flash storage");
137  }
138 }
139 
140 /*
141  write one storage line. This also updates _dirty_mask.
142 */
143 void Storage::_flash_write(uint16_t line)
144 {
145  if (_flash.write(line*CH_STORAGE_LINE_SIZE, CH_STORAGE_LINE_SIZE)) {
146  // mark the line clean
147  _dirty_mask.clear(line);
148  }
149 }
150 
151 /*
152  callback to write data to flash
153  */
154 bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
155 {
156  size_t base_address = stm32_flash_getpageaddr(_flash_page+sector);
157  bool ret = stm32_flash_write(base_address+offset, data, length) == length;
158  if (!ret && _flash_erase_ok()) {
159  // we are getting flash write errors while disarmed. Try
160  // re-writing all of flash
161  uint32_t now = AP_HAL::millis();
162  if (now - _last_re_init_ms > 5000) {
163  _last_re_init_ms = now;
164  bool ok = _flash.re_initialise();
165  hal.console->printf("Storage: failed at %u:%u for %u - re-init %u\n",
166  (unsigned)sector, (unsigned)offset, (unsigned)length, (unsigned)ok);
167  }
168  }
169  return ret;
170 }
171 
172 /*
173  callback to read data from flash
174  */
175 bool Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
176 {
177  size_t base_address = stm32_flash_getpageaddr(_flash_page+sector);
178  const uint8_t *b = ((const uint8_t *)base_address)+offset;
179  memcpy(data, b, length);
180  return true;
181 }
182 
183 /*
184  callback to erase flash sector
185  */
186 bool Storage::_flash_erase_sector(uint8_t sector)
187 {
188  return stm32_flash_erasepage(_flash_page+sector);
189 }
190 
191 /*
192  callback to check if erase is allowed
193  */
195 {
196  // only allow erase while disarmed
197  return !hal.util->get_soft_armed();
198 }
199 
200 #endif // HAL_USE_EMPTY_STORAGE
bool get_soft_armed() const
Definition: Util.h:15
void _storage_open(void)
Definition: Storage.cpp:29
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:81
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: Storage.cpp:10
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define CH_STORAGE_SIZE
Definition: Storage.h:26
volatile bool _initialised
Definition: Storage.h:46
void clear(uint16_t bit)
Definition: Bitmask.h:56
void _mark_dirty(uint16_t loc, uint16_t length)
Definition: Storage.cpp:62
bool _flash_erase_ok(void)
Definition: Storage.cpp:194
uint8_t _flash_page
Definition: Storage.h:57
void _flash_load(void)
Definition: Storage.cpp:129
AP_HAL::Util * util
Definition: HAL.h:115
bool empty(void) const
Definition: Bitmask.h:75
Bitmask _dirty_mask
Definition: Storage.h:51
bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
Definition: Storage.cpp:175
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool get(uint16_t bit) const
Definition: Bitmask.h:68
AP_FlashStorage _flash
Definition: Storage.h:61
bool stm32_flash_erasepage(uint32_t page)
Definition: flash.c:215
uint32_t millis()
Definition: system.cpp:157
bool _flash_erase_sector(uint8_t sector)
Definition: Storage.cpp:186
void _timer_tick(void) override
Definition: Storage.cpp:93
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:72
bool write(uint16_t offset, uint16_t length)
#define CH_STORAGE_NUM_LINES
Definition: Storage.h:35
uint32_t _last_re_init_ms
Definition: Storage.h:59
bool re_initialise(void)
void set(uint16_t bit)
Definition: Bitmask.h:34
bool _flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
Definition: Storage.cpp:154
#define CH_STORAGE_LINE_SHIFT
Definition: Storage.h:32
#define CH_STORAGE_LINE_SIZE
Definition: Storage.h:34
uint32_t stm32_flash_getpageaddr(uint32_t page)
Definition: flash.c:157
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
int32_t stm32_flash_write(uint32_t addr, const void *buf, uint32_t count)
Definition: flash.c:259
void _flash_write(uint16_t line)
Definition: Storage.cpp:143
void clearall(void)
Definition: Bitmask.h:63