|
|
|
@ -42,62 +42,30 @@ const StorageManager::StorageArea StorageManager::layout[STORAGE_NUM_AREAS] = {
@@ -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] = {
@@ -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] = {
@@ -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
|
|
|
|
|