|
|
@ -65,7 +65,8 @@ const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_ARE |
|
|
|
{ StorageParam, 8192, 1280}, |
|
|
|
{ StorageParam, 8192, 1280}, |
|
|
|
{ StorageRally, 9472, 300}, |
|
|
|
{ StorageRally, 9472, 300}, |
|
|
|
{ StorageFence, 9772, 256}, |
|
|
|
{ StorageFence, 9772, 256}, |
|
|
|
{ StorageMission, 10028, 6228}, // leave 128 byte gap for expansion
|
|
|
|
{ StorageMission, 10028, 5204}, // leave 128 byte gap for expansion
|
|
|
|
|
|
|
|
{ StorageCANDNA, 15232, 1024}, |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
@ -95,7 +96,8 @@ const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREA |
|
|
|
{ StorageParam, 8192, 1280}, |
|
|
|
{ StorageParam, 8192, 1280}, |
|
|
|
{ StorageRally, 9472, 300}, |
|
|
|
{ StorageRally, 9472, 300}, |
|
|
|
{ StorageFence, 9772, 256}, |
|
|
|
{ StorageFence, 9772, 256}, |
|
|
|
{ StorageMission, 10028, 6228}, // leave 128 byte gap for expansion
|
|
|
|
{ StorageMission, 10028, 5204}, // leave 128 byte gap for expansion
|
|
|
|
|
|
|
|
{ StorageCANDNA, 15232, 1024}, |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
}; |
|
|
|
}; |
|
|
|
#endif // STORAGE_NUM_AREAS == 1
|
|
|
|
#endif // STORAGE_NUM_AREAS == 1
|
|
|
|