2014-08-13 01:41:44 -03:00
|
|
|
/*
|
2021-05-26 23:33:17 -03:00
|
|
|
Please contribute your ideas! See https://ardupilot.org/dev for details
|
2014-08-13 01:41:44 -03:00
|
|
|
|
|
|
|
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
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
Management for hal.storage to allow for backwards compatible mapping
|
|
|
|
of storage offsets to available storage
|
|
|
|
*/
|
2016-02-17 21:25:57 -04:00
|
|
|
#pragma once
|
2014-08-13 01:41:44 -03:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2023-02-14 05:39:15 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig_config.h>
|
2014-08-13 01:41:44 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
use just one area per storage type for boards with 4k of
|
|
|
|
storage. Use larger areas for other boards
|
|
|
|
*/
|
2021-01-12 19:09:53 -04:00
|
|
|
#if HAL_STORAGE_SIZE >= 32768
|
2021-10-30 07:08:40 -03:00
|
|
|
#define STORAGE_NUM_AREAS 18
|
2021-01-12 19:09:53 -04:00
|
|
|
#elif HAL_STORAGE_SIZE >= 16384
|
2019-09-19 00:02:18 -03:00
|
|
|
#define STORAGE_NUM_AREAS 15
|
2021-01-04 00:45:47 -04:00
|
|
|
#elif HAL_STORAGE_SIZE >= 15360 && defined(HAL_NUM_CAN_IFACES)
|
|
|
|
#define STORAGE_NUM_AREAS 12
|
2018-06-23 04:57:37 -03:00
|
|
|
#elif HAL_STORAGE_SIZE >= 15360
|
|
|
|
#define STORAGE_NUM_AREAS 11
|
2014-08-13 07:46:36 -03:00
|
|
|
#elif HAL_STORAGE_SIZE >= 8192
|
2017-03-09 19:46:48 -04:00
|
|
|
#define STORAGE_NUM_AREAS 10
|
2014-08-13 07:46:36 -03:00
|
|
|
#elif HAL_STORAGE_SIZE >= 4096
|
|
|
|
#define STORAGE_NUM_AREAS 4
|
2019-05-26 22:31:16 -03:00
|
|
|
#elif HAL_STORAGE_SIZE > 0
|
|
|
|
#define STORAGE_NUM_AREAS 1
|
2014-08-13 07:46:36 -03:00
|
|
|
#else
|
|
|
|
#error "Unsupported storage size"
|
2014-08-13 01:41:44 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
/*
|
2023-02-13 06:37:31 -04:00
|
|
|
The StorageManager holds the layout of non-volatile storage
|
2014-08-13 01:41:44 -03:00
|
|
|
*/
|
|
|
|
class StorageManager {
|
|
|
|
friend class StorageAccess;
|
|
|
|
public:
|
|
|
|
enum StorageType {
|
|
|
|
StorageParam = 0,
|
|
|
|
StorageFence = 1,
|
|
|
|
StorageRally = 2,
|
2016-01-20 22:48:41 -04:00
|
|
|
StorageMission = 3,
|
2017-03-09 19:46:48 -04:00
|
|
|
StorageKeys = 4,
|
2019-09-19 00:02:18 -03:00
|
|
|
StorageBindInfo= 5,
|
2021-01-12 19:09:53 -04:00
|
|
|
StorageCANDNA = 6,
|
|
|
|
StorageParamBak = 7
|
2014-08-13 01:41:44 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// erase whole of storage
|
|
|
|
static void erase(void);
|
|
|
|
|
2023-02-14 05:39:15 -04:00
|
|
|
static bool storage_failed(void) {
|
|
|
|
return last_io_failed;
|
|
|
|
}
|
|
|
|
|
2014-08-13 01:41:44 -03:00
|
|
|
private:
|
2023-02-14 05:39:15 -04:00
|
|
|
static bool last_io_failed;
|
|
|
|
|
2014-08-13 01:41:44 -03:00
|
|
|
struct StorageArea {
|
|
|
|
StorageType type;
|
|
|
|
uint16_t offset;
|
|
|
|
uint16_t length;
|
|
|
|
};
|
|
|
|
|
|
|
|
// available layouts
|
2020-01-16 00:13:15 -04:00
|
|
|
static const StorageArea layout[STORAGE_NUM_AREAS];
|
2014-08-13 01:41:44 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
A StorageAccess object allows access to one type of storage
|
2023-03-11 02:44:06 -04:00
|
|
|
|
|
|
|
NOTE: this object may be declared on the stack, so it will not be
|
|
|
|
zero initialised
|
2014-08-13 01:41:44 -03:00
|
|
|
*/
|
|
|
|
class StorageAccess {
|
|
|
|
public:
|
|
|
|
// constructor
|
|
|
|
StorageAccess(StorageManager::StorageType _type);
|
|
|
|
|
|
|
|
// return total size of this accessor
|
|
|
|
uint16_t size(void) const { return total_size; }
|
|
|
|
|
|
|
|
// base access via block functions
|
|
|
|
bool read_block(void *dst, uint16_t src, size_t n) const;
|
|
|
|
bool write_block(uint16_t dst, const void* src, size_t n) const;
|
|
|
|
|
|
|
|
// helper functions
|
|
|
|
uint8_t read_byte(uint16_t loc) const;
|
2019-08-05 01:39:03 -03:00
|
|
|
uint8_t read_uint8(uint16_t loc) const { return read_byte(loc); }
|
2014-08-13 01:41:44 -03:00
|
|
|
uint16_t read_uint16(uint16_t loc) const;
|
|
|
|
uint32_t read_uint32(uint16_t loc) const;
|
2021-06-01 00:17:22 -03:00
|
|
|
float read_float(uint16_t loc) const;
|
2014-08-13 01:41:44 -03:00
|
|
|
|
|
|
|
void write_byte(uint16_t loc, uint8_t value) const;
|
2019-08-05 01:39:03 -03:00
|
|
|
void write_uint8(uint16_t loc, uint8_t value) const { return write_byte(loc, value); }
|
2014-08-13 01:41:44 -03:00
|
|
|
void write_uint16(uint16_t loc, uint16_t value) const;
|
|
|
|
void write_uint32(uint16_t loc, uint32_t value) const;
|
2021-06-01 00:17:22 -03:00
|
|
|
void write_float(uint16_t loc, float value) const;
|
2014-08-13 01:41:44 -03:00
|
|
|
|
2021-01-12 19:09:53 -04:00
|
|
|
// copy from one storage area to another
|
2021-02-01 12:15:32 -04:00
|
|
|
bool copy_area(const StorageAccess &source) const;
|
2021-01-12 19:09:53 -04:00
|
|
|
|
2023-02-14 05:39:15 -04:00
|
|
|
// attach a storage file from microSD
|
|
|
|
bool attach_file(const char *fname, uint16_t size_kbyte);
|
|
|
|
|
2014-08-13 01:41:44 -03:00
|
|
|
private:
|
|
|
|
const StorageManager::StorageType type;
|
|
|
|
uint16_t total_size;
|
2023-02-14 05:39:15 -04:00
|
|
|
|
|
|
|
#if AP_SDCARD_STORAGE_ENABLED
|
|
|
|
/*
|
|
|
|
support for storage regions on microSD. Only the StorageMission
|
|
|
|
for now
|
|
|
|
*/
|
|
|
|
struct FileStorage {
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
int fd;
|
|
|
|
uint8_t *buffer;
|
|
|
|
uint32_t bufsize;
|
|
|
|
uint32_t last_clean_ms;
|
|
|
|
uint32_t last_io_fail_ms;
|
|
|
|
// each bit of the dirty mask covers 1k of data
|
|
|
|
uint64_t dirty_mask;
|
|
|
|
} *file;
|
|
|
|
|
|
|
|
void flush_file(void);
|
|
|
|
#endif
|
2014-08-13 01:41:44 -03:00
|
|
|
};
|