APM:Libraries
StorageManager.cpp
Go to the documentation of this file.
1 /*
2  Please contribute your ideas! See http://dev.ardupilot.org for details
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 /*
18  Management for hal.storage to allow for backwards compatible mapping
19  of storage offsets to available storage
20  */
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include "StorageManager.h"
24 
25 
26 extern const AP_HAL::HAL& hal;
27 
28 /*
29  the layouts below are carefully designed to ensure backwards
30  compatibility with older firmwares
31  */
32 
33 /*
34  layout for fixed wing and rovers
35  On PX4v1 this gives 309 waypoints, 30 rally points and 52 fence points
36  On Pixhawk this gives 724 waypoints, 50 rally points and 84 fence points
37  */
39  { StorageParam, 0, 1280}, // 0x500 parameter bytes
40  { StorageMission, 1280, 2506},
41  { StorageRally, 3786, 150}, // 10 rally points
42  { StorageFence, 3936, 160}, // 20 fence points
43 #if STORAGE_NUM_AREAS >= 8
44  { StorageParam, 4096, 1280},
45  { StorageRally, 5376, 300},
46  { StorageFence, 5676, 256},
47  { StorageMission, 5932, 2132},
48  { StorageKeys, 8064, 64},
49  { StorageBindInfo,8128, 56},
50 #endif
51 #if STORAGE_NUM_AREAS >= 12
52  { StorageParam, 8192, 1280},
53  { StorageRally, 9472, 300},
54  { StorageFence, 9772, 256},
55  { StorageMission, 10028, 6228}, // leave 128 byte gap for expansion
56 #endif
57 };
58 
59 
60 /*
61  layout for copter.
62  On PX4v1 this gives 303 waypoints, 26 rally points and 38 fence points
63  On Pixhawk this gives 718 waypoints, 46 rally points and 70 fence points
64  */
66  { StorageParam, 0, 1536}, // 0x600 param bytes
67  { StorageMission, 1536, 2422},
68  { StorageRally, 3958, 90}, // 6 rally points
69  { StorageFence, 4048, 48}, // 6 fence points
70 #if STORAGE_NUM_AREAS >= 8
71  { StorageParam, 4096, 1280},
72  { StorageRally, 5376, 300},
73  { StorageFence, 5676, 256},
74  { StorageMission, 5932, 2132},
75  { StorageKeys, 8064, 64},
76  { StorageBindInfo,8128, 56},
77 #endif
78 #if STORAGE_NUM_AREAS >= 12
79  { StorageParam, 8192, 1280},
80  { StorageRally, 9472, 300},
81  { StorageFence, 9772, 256},
82  { StorageMission, 10028, 6228}, // leave 128 byte gap for expansion
83 #endif
84 };
85 
86 // setup default layout
88 
89 /*
90  erase all storage
91  */
93 {
94  uint8_t blk[16];
95  memset(blk, 0, sizeof(blk));
96  for (uint8_t i=0; i<STORAGE_NUM_AREAS; i++) {
97  const StorageManager::StorageArea &area = StorageManager::layout[i];
98  uint16_t length = area.length;
99  uint16_t offset = area.offset;
100  for (uint16_t ofs=0; ofs<length; ofs += sizeof(blk)) {
101  uint8_t n = 16;
102  if (ofs + n > length) {
103  n = length - ofs;
104  }
105  hal.storage->write_block(offset + ofs, blk, n);
106  }
107  }
108 
109 }
110 
111 /*
112  constructor for StorageAccess
113  */
115  type(_type)
116 {
117  // calculate available bytes
118  total_size = 0;
119  for (uint8_t i=0; i<STORAGE_NUM_AREAS; i++) {
120  const StorageManager::StorageArea &area = StorageManager::layout[i];
121  if (area.type == type) {
122  total_size += area.length;
123  }
124  }
125 }
126 
127 /*
128  base read function. The src offset is within the bytes allocated
129  for the storage type of this StorageAccess object
130 */
131 bool StorageAccess::read_block(void *data, uint16_t addr, size_t n) const
132 {
133  uint8_t *b = (uint8_t *)data;
134  for (uint8_t i=0; i<STORAGE_NUM_AREAS; i++) {
135  const StorageManager::StorageArea &area = StorageManager::layout[i];
136  uint16_t length = area.length;
137  uint16_t offset = area.offset;
138  if (area.type != type) {
139  continue;
140  }
141  if (addr >= length) {
142  // the data isn't in this area
143  addr -= length;
144  continue;
145  }
146  uint8_t count = n;
147  if (count+addr > length) {
148  // the data crosses a boundary between two areas
149  count = length - addr;
150  }
151  hal.storage->read_block(b, addr+offset, count);
152  n -= count;
153 
154  if (n == 0) {
155  break;
156  }
157 
158  // move pointer after written bytes
159  b += count;
160  // continue writing at the beginning of next valid area
161  addr = 0;
162  }
163  return (n == 0);
164 }
165 
166 
167 /*
168  base read function. The addr offset is within the bytes allocated
169  for the storage type of this StorageAccess object
170 */
171 bool StorageAccess::write_block(uint16_t addr, const void *data, size_t n) const
172 {
173  const uint8_t *b = (const uint8_t *)data;
174  for (uint8_t i=0; i<STORAGE_NUM_AREAS; i++) {
175  const StorageManager::StorageArea &area = StorageManager::layout[i];
176  uint16_t length = area.length;
177  uint16_t offset = area.offset;
178  if (area.type != type) {
179  continue;
180  }
181  if (addr >= length) {
182  // the data isn't in this area
183  addr -= length;
184  continue;
185  }
186  uint8_t count = n;
187  if (count+addr > length) {
188  // the data crosses a boundary between two areas
189  count = length - addr;
190  }
191  hal.storage->write_block(addr+offset, b, count);
192  n -= count;
193 
194  if (n == 0) {
195  break;
196  }
197 
198  // move pointer after written bytes
199  b += count;
200  // continue writing at the beginning of next valid area
201  addr = 0;
202  }
203  return (n == 0);
204 }
205 
206 /*
207  read a byte
208  */
209 uint8_t StorageAccess::read_byte(uint16_t loc) const
210 {
211  uint8_t v;
212  read_block(&v, loc, sizeof(v));
213  return v;
214 }
215 
216 /*
217  read 16 bit value
218  */
219 uint16_t StorageAccess::read_uint16(uint16_t loc) const
220 {
221  uint16_t v;
222  read_block(&v, loc, sizeof(v));
223  return v;
224 }
225 
226 /*
227  read 32 bit value
228  */
229 uint32_t StorageAccess::read_uint32(uint16_t loc) const
230 {
231  uint32_t v;
232  read_block(&v, loc, sizeof(v));
233  return v;
234 }
235 
236 /*
237  write a byte
238  */
239 void StorageAccess::write_byte(uint16_t loc, uint8_t value) const
240 {
241  write_block(loc, &value, sizeof(value));
242 }
243 
244 /*
245  write a uint16
246  */
247 void StorageAccess::write_uint16(uint16_t loc, uint16_t value) const
248 {
249  write_block(loc, &value, sizeof(value));
250 }
251 
252 /*
253  write a uint32
254  */
255 void StorageAccess::write_uint32(uint16_t loc, uint32_t value) const
256 {
257  write_block(loc, &value, sizeof(value));
258 }
const StorageManager::StorageType type
uint8_t read_byte(uint16_t loc) const
StorageAccess(StorageManager::StorageType _type)
void write_uint16(uint16_t loc, uint16_t value) const
static const StorageArea * layout
uint16_t read_uint16(uint16_t loc) const
static const StorageArea layout_default[STORAGE_NUM_AREAS]
void write_byte(uint16_t loc, uint8_t value) const
virtual void read_block(void *dst, uint16_t src, size_t n)=0
AP_HAL::Storage * storage
Definition: HAL.h:109
float v
Definition: Printf.cpp:15
bool read_block(void *dst, uint16_t src, size_t n) const
uint32_t read_uint32(uint16_t loc) const
void write_uint32(uint16_t loc, uint32_t value) const
static const StorageArea layout_copter[STORAGE_NUM_AREAS]
bool write_block(uint16_t dst, const void *src, size_t n) const
float value
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint16_t total_size
virtual void write_block(uint16_t dst, const void *src, size_t n)=0
static void erase(void)