mirror of https://github.com/ArduPilot/ardupilot
StorageManager: added parameter backup region
This commit is contained in:
parent
eaf23f2eb4
commit
4b6ec99633
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
Please contribute your ideas! See http://dev.ardupilot.org for details
|
||||
Please contribute your ideas! See https://dev.ardupilot.org for details
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -20,7 +20,11 @@
|
|||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include "StorageManager.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
|
@ -35,17 +39,18 @@ extern const AP_HAL::HAL& hal;
|
|||
/*
|
||||
layout for peripherals
|
||||
*/
|
||||
const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_AREAS] = {
|
||||
const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = {
|
||||
{ StorageParam, 0, HAL_STORAGE_SIZE}
|
||||
};
|
||||
|
||||
#else
|
||||
#elif !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
|
||||
/*
|
||||
layout for fixed wing and rovers
|
||||
On PX4v1 this gives 309 waypoints, 30 rally points and 52 fence points
|
||||
On Pixhawk this gives 724 waypoints, 50 rally points and 84 fence points
|
||||
*/
|
||||
const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_AREAS] = {
|
||||
const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = {
|
||||
{ StorageParam, 0, 1280}, // 0x500 parameter bytes
|
||||
{ StorageMission, 1280, 2506},
|
||||
{ StorageRally, 3786, 150}, // 10 rally points
|
||||
|
@ -61,22 +66,34 @@ const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_ARE
|
|||
#if STORAGE_NUM_AREAS == 11
|
||||
// optimised for lots of parameters for 15k boards with OSD
|
||||
{ StorageParam, 8192, 7168},
|
||||
#elif STORAGE_NUM_AREAS == 12
|
||||
// optimised for lots of parameters for 15k boards with OSD, plus room for CAN DNA
|
||||
{ StorageParam, 8192, 6144},
|
||||
{ StorageCANDNA, 14336, 1024},
|
||||
#endif
|
||||
#if STORAGE_NUM_AREAS >= 12
|
||||
#if STORAGE_NUM_AREAS >= 13
|
||||
{ StorageParam, 8192, 1280},
|
||||
{ StorageRally, 9472, 300},
|
||||
{ StorageFence, 9772, 256},
|
||||
{ StorageMission, 10028, 5204}, // leave 128 byte gap for expansion
|
||||
{ StorageCANDNA, 15232, 1024},
|
||||
// 128 byte gap at end of first 16k
|
||||
#endif
|
||||
#if STORAGE_NUM_AREAS >= 19
|
||||
{ StorageParam, 16384, 1280},
|
||||
{ StorageMission, 17664, 9842},
|
||||
{ StorageParamBak, 27506, 5376},
|
||||
#endif
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
/*
|
||||
layout for copter.
|
||||
On PX4v1 this gives 303 waypoints, 26 rally points and 38 fence points
|
||||
On Pixhawk this gives 718 waypoints, 46 rally points and 70 fence points
|
||||
*/
|
||||
const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREAS] = {
|
||||
const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = {
|
||||
{ StorageParam, 0, 1536}, // 0x600 param bytes
|
||||
{ StorageMission, 1536, 2422},
|
||||
{ StorageRally, 3958, 90}, // 6 rally points
|
||||
|
@ -92,20 +109,27 @@ const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREA
|
|||
#if STORAGE_NUM_AREAS == 11
|
||||
// optimised for lots of parameters for 15k boards with OSD
|
||||
{ StorageParam, 8192, 7168},
|
||||
#elif STORAGE_NUM_AREAS == 12
|
||||
// optimised for lots of parameters for 15k boards with OSD, plus room for CAN DNA
|
||||
{ StorageParam, 8192, 6144},
|
||||
{ StorageCANDNA, 14336, 1024},
|
||||
#endif
|
||||
#if STORAGE_NUM_AREAS >= 12
|
||||
#if STORAGE_NUM_AREAS >= 13
|
||||
{ StorageParam, 8192, 1280},
|
||||
{ StorageRally, 9472, 300},
|
||||
{ StorageFence, 9772, 256},
|
||||
{ StorageMission, 10028, 5204}, // leave 128 byte gap for expansion
|
||||
{ StorageCANDNA, 15232, 1024},
|
||||
// 128 byte gap at end of first 16k
|
||||
#endif
|
||||
#if STORAGE_NUM_AREAS >= 19
|
||||
{ StorageParam, 16384, 1280},
|
||||
{ StorageMission, 17664, 9842},
|
||||
{ StorageParamBak, 27506, 5376},
|
||||
#endif
|
||||
};
|
||||
#endif // STORAGE_NUM_AREAS == 1
|
||||
|
||||
// setup default layout
|
||||
const StorageManager::StorageArea *StorageManager::layout = layout_default;
|
||||
|
||||
/*
|
||||
erase all storage
|
||||
*/
|
||||
|
@ -264,3 +288,25 @@ void StorageAccess::write_uint32(uint16_t loc, uint32_t value) const
|
|||
{
|
||||
write_block(loc, &value, sizeof(value));
|
||||
}
|
||||
|
||||
/*
|
||||
copy one area to another
|
||||
*/
|
||||
bool StorageAccess::copy_area(const StorageAccess &source)
|
||||
{
|
||||
// we deliberately allow for copies from smaller areas. This
|
||||
// allows for a partial backup region for parameters
|
||||
uint16_t total = MIN(source.size(), size());
|
||||
uint16_t ofs = 0;
|
||||
while (total > 0) {
|
||||
uint8_t block[32];
|
||||
uint16_t n = MIN(sizeof(block), total);
|
||||
if (!source.read_block(block, ofs, n) ||
|
||||
!write_block(ofs, block, n)) {
|
||||
return false;
|
||||
}
|
||||
total -= n;
|
||||
ofs += n;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
Please contribute your ideas! See http://dev.ardupilot.org for details
|
||||
Please contribute your ideas! See https://dev.ardupilot.org for details
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -26,8 +26,12 @@
|
|||
use just one area per storage type for boards with 4k of
|
||||
storage. Use larger areas for other boards
|
||||
*/
|
||||
#if HAL_STORAGE_SIZE >= 16384
|
||||
#if HAL_STORAGE_SIZE >= 32768
|
||||
#define STORAGE_NUM_AREAS 19
|
||||
#elif HAL_STORAGE_SIZE >= 16384
|
||||
#define STORAGE_NUM_AREAS 15
|
||||
#elif HAL_STORAGE_SIZE >= 15360 && defined(HAL_NUM_CAN_IFACES)
|
||||
#define STORAGE_NUM_AREAS 12
|
||||
#elif HAL_STORAGE_SIZE >= 15360
|
||||
#define STORAGE_NUM_AREAS 11
|
||||
#elif HAL_STORAGE_SIZE >= 8192
|
||||
|
@ -53,15 +57,13 @@ public:
|
|||
StorageMission = 3,
|
||||
StorageKeys = 4,
|
||||
StorageBindInfo= 5,
|
||||
StorageCANDNA = 6
|
||||
StorageCANDNA = 6,
|
||||
StorageParamBak = 7
|
||||
};
|
||||
|
||||
// erase whole of storage
|
||||
static void erase(void);
|
||||
|
||||
// setup for copter layout of storage
|
||||
static void set_layout_copter(void) { layout = layout_copter; }
|
||||
|
||||
private:
|
||||
struct StorageArea {
|
||||
StorageType type;
|
||||
|
@ -70,9 +72,7 @@ private:
|
|||
};
|
||||
|
||||
// available layouts
|
||||
static const StorageArea layout_copter[STORAGE_NUM_AREAS];
|
||||
static const StorageArea layout_default[STORAGE_NUM_AREAS];
|
||||
static const StorageArea *layout;
|
||||
static const StorageArea layout[STORAGE_NUM_AREAS];
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -101,6 +101,9 @@ public:
|
|||
void write_uint16(uint16_t loc, uint16_t value) const;
|
||||
void write_uint32(uint16_t loc, uint32_t value) const;
|
||||
|
||||
// copy from one storage area to another
|
||||
bool copy_area(const StorageAccess &source);
|
||||
|
||||
private:
|
||||
const StorageManager::StorageType type;
|
||||
uint16_t total_size;
|
||||
|
|
Loading…
Reference in New Issue