From 6d07a512e92c0277a5b44cdb79cef3991b1833a7 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sat, 30 Oct 2021 15:38:40 +0530 Subject: [PATCH] StorageManager: fix storage manager counts and merge common areas --- libraries/StorageManager/StorageManager.cpp | 56 +++++---------------- libraries/StorageManager/StorageManager.h | 2 +- 2 files changed, 13 insertions(+), 45 deletions(-) diff --git a/libraries/StorageManager/StorageManager.cpp b/libraries/StorageManager/StorageManager.cpp index c6adc98e3b..96dcdbe95f 100644 --- a/libraries/StorageManager/StorageManager.cpp +++ b/libraries/StorageManager/StorageManager.cpp @@ -42,62 +42,30 @@ const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = { { StorageParam, 0, HAL_STORAGE_SIZE} }; -#elif !APM_BUILD_COPTER_OR_HELI - +#else /* 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[STORAGE_NUM_AREAS] = { - { StorageParam, 0, 1280}, // 0x500 parameter bytes - { StorageMission, 1280, 2506}, - { StorageRally, 3786, 150}, // 10 rally points - { StorageFence, 3936, 160}, // 20 fence points -#if STORAGE_NUM_AREAS >= 8 - { StorageParam, 4096, 1280}, - { StorageRally, 5376, 300}, - { StorageFence, 5676, 256}, - { StorageMission, 5932, 2132}, - { StorageKeys, 8064, 64}, - { StorageBindInfo,8128, 56}, -#endif -#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 >= 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[STORAGE_NUM_AREAS] = { +#if !APM_BUILD_COPTER_OR_HELI + { StorageParam, 0, 1280}, // 0x500 parameter bytes + { StorageMission, 1280, 2506}, + { StorageRally, 3786, 150}, // 10 rally points + { StorageFence, 3936, 160}, // 20 fence points +#else { StorageParam, 0, 1536}, // 0x600 param bytes { StorageMission, 1536, 2422}, { StorageRally, 3958, 90}, // 6 rally points { StorageFence, 4048, 48}, // 6 fence points -#if STORAGE_NUM_AREAS >= 8 +#endif +#if STORAGE_NUM_AREAS >= 10 { StorageParam, 4096, 1280}, { StorageRally, 5376, 300}, { StorageFence, 5676, 256}, @@ -113,7 +81,7 @@ const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = { { StorageParam, 8192, 6144}, { StorageCANDNA, 14336, 1024}, #endif -#if STORAGE_NUM_AREAS >= 13 +#if STORAGE_NUM_AREAS >= 15 { StorageParam, 8192, 1280}, { StorageRally, 9472, 300}, { StorageFence, 9772, 256}, @@ -121,10 +89,10 @@ const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = { { StorageCANDNA, 15232, 1024}, // 128 byte gap at end of first 16k #endif -#if STORAGE_NUM_AREAS >= 19 +#if STORAGE_NUM_AREAS >= 18 { StorageParam, 16384, 1280}, { StorageMission, 17664, 9842}, - { StorageParamBak, 27506, 5376}, + { StorageParamBak, 27506, 5262}, #endif }; #endif // STORAGE_NUM_AREAS == 1 diff --git a/libraries/StorageManager/StorageManager.h b/libraries/StorageManager/StorageManager.h index 782c4ba9db..f24d9d05a6 100644 --- a/libraries/StorageManager/StorageManager.h +++ b/libraries/StorageManager/StorageManager.h @@ -27,7 +27,7 @@ storage. Use larger areas for other boards */ #if HAL_STORAGE_SIZE >= 32768 -#define STORAGE_NUM_AREAS 19 +#define STORAGE_NUM_AREAS 18 #elif HAL_STORAGE_SIZE >= 16384 #define STORAGE_NUM_AREAS 15 #elif HAL_STORAGE_SIZE >= 15360 && defined(HAL_NUM_CAN_IFACES)