StorageManager: use pragmas to set storage layout rather than call

We don't need the flexibility to reset this, it's a waste of bytes and
something that could go wrong.  AP_Periph led the way with using
pragmas here.
This commit is contained in:
Peter Barker 2020-01-16 15:13:15 +11:00 committed by Andrew Tridgell
parent 7bc1f4ff9b
commit 4647c6ef62
2 changed files with 11 additions and 13 deletions

View File

@ -20,7 +20,10 @@
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include "StorageManager.h"
#include <stdio.h>
@ -35,17 +38,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
@ -71,12 +75,14 @@ const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_ARE
#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
@ -103,9 +109,6 @@ const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREA
};
#endif // STORAGE_NUM_AREAS == 1
// setup default layout
const StorageManager::StorageArea *StorageManager::layout = layout_default;
/*
erase all storage
*/

View File

@ -59,9 +59,6 @@ public:
// 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 +67,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];
};
/*