mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
dataman: remove flash backend
This commit is contained in:
parent
321df7ed84
commit
fd1fff89d4
@ -23,7 +23,6 @@ set +e
|
||||
set R /
|
||||
set AUTOCNF no
|
||||
set AUX_MODE pwm
|
||||
set DATAMAN_OPT ""
|
||||
set FCONFIG /fs/microsd/etc/config.txt
|
||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||
set FMU_MODE pwm
|
||||
@ -211,7 +210,7 @@ else
|
||||
# Waypoint storage.
|
||||
# REBOOTWORK this needs to start in parallel.
|
||||
#
|
||||
dataman start $DATAMAN_OPT
|
||||
dataman start
|
||||
|
||||
#
|
||||
# Start the socket communication send_event handler.
|
||||
@ -559,7 +558,6 @@ fi
|
||||
unset R
|
||||
unset AUTOCNF
|
||||
unset AUX_MODE
|
||||
unset DATAMAN_OPT
|
||||
unset FCONFIG
|
||||
unset FEXTRAS
|
||||
unset FMU_MODE
|
||||
|
||||
@ -53,11 +53,6 @@
|
||||
|
||||
#include "dataman.h"
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
#include <nuttx/clock.h>
|
||||
#include <nuttx/progmem.h>
|
||||
#endif
|
||||
|
||||
__BEGIN_DECLS
|
||||
__EXPORT int dataman_main(int argc, char *argv[]);
|
||||
__END_DECLS
|
||||
@ -82,20 +77,6 @@ static int _ram_restart(dm_reset_reason reason);
|
||||
static int _ram_initialize(unsigned max_offset);
|
||||
static void _ram_shutdown();
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
/* Private Ram_Flash based Operations */
|
||||
#define RAM_FLASH_FLUSH_TIMEOUT_USEC USEC_PER_SEC
|
||||
|
||||
static ssize_t _ram_flash_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf,
|
||||
size_t count);
|
||||
static ssize_t _ram_flash_read(dm_item_t item, unsigned index, void *buf, size_t count);
|
||||
static int _ram_flash_clear(dm_item_t item);
|
||||
static int _ram_flash_restart(dm_reset_reason reason);
|
||||
static int _ram_flash_initialize(unsigned max_offset);
|
||||
static void _ram_flash_shutdown();
|
||||
static int _ram_flash_wait(px4_sem_t *sem);
|
||||
#endif
|
||||
|
||||
typedef struct dm_operations_t {
|
||||
ssize_t (*write)(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count);
|
||||
ssize_t (*read)(dm_item_t item, unsigned index, void *buf, size_t count);
|
||||
@ -126,18 +107,6 @@ static constexpr dm_operations_t dm_ram_operations = {
|
||||
.wait = px4_sem_wait,
|
||||
};
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static constexpr dm_operations_t dm_ram_flash_operations = {
|
||||
.write = _ram_flash_write,
|
||||
.read = _ram_flash_read,
|
||||
.clear = _ram_flash_clear,
|
||||
.restart = _ram_flash_restart,
|
||||
.initialize = _ram_flash_initialize,
|
||||
.shutdown = _ram_flash_shutdown,
|
||||
.wait = _ram_flash_wait,
|
||||
};
|
||||
#endif
|
||||
|
||||
static const dm_operations_t *g_dm_ops;
|
||||
|
||||
static struct {
|
||||
@ -149,14 +118,6 @@ static struct {
|
||||
uint8_t *data;
|
||||
uint8_t *data_end;
|
||||
} ram;
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
struct {
|
||||
uint8_t *data;
|
||||
uint8_t *data_end;
|
||||
/* sync above with RAM backend */
|
||||
timespec flush_timeout;
|
||||
} ram_flash;
|
||||
#endif
|
||||
};
|
||||
bool running;
|
||||
} dm_operations_data;
|
||||
@ -244,17 +205,10 @@ static perf_counter_t _dm_write_perf{nullptr};
|
||||
static const char *default_device_path = PX4_STORAGEDIR "/dataman";
|
||||
static char *k_data_manager_device_path = nullptr;
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static const dm_sector_descriptor_t *k_dataman_flash_sector = nullptr;
|
||||
#endif
|
||||
|
||||
static enum {
|
||||
BACKEND_NONE = 0,
|
||||
BACKEND_FILE,
|
||||
BACKEND_RAM,
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
BACKEND_RAM_FLASH,
|
||||
#endif
|
||||
BACKEND_LAST
|
||||
} backend = BACKEND_NONE;
|
||||
|
||||
@ -531,38 +485,6 @@ _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const v
|
||||
return count - DM_SECTOR_HDR_SIZE;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static void
|
||||
_ram_flash_update_flush_timeout()
|
||||
{
|
||||
timespec &abstime = dm_operations_data.ram_flash.flush_timeout;
|
||||
|
||||
if (clock_gettime(CLOCK_REALTIME, &abstime) == 0) {
|
||||
const unsigned billion = 1000 * 1000 * 1000;
|
||||
uint64_t nsecs = abstime.tv_nsec + (uint64_t)RAM_FLASH_FLUSH_TIMEOUT_USEC * 1000;
|
||||
abstime.tv_sec += nsecs / billion;
|
||||
nsecs -= (nsecs / billion) * billion;
|
||||
abstime.tv_nsec = nsecs;
|
||||
}
|
||||
}
|
||||
|
||||
static ssize_t
|
||||
_ram_flash_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
|
||||
{
|
||||
ssize_t ret = dm_ram_operations.write(item, index, persistence, buf, count);
|
||||
|
||||
if (ret < 1) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
if (persistence == DM_PERSIST_POWER_ON_RESET) {
|
||||
_ram_flash_update_flush_timeout();
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Retrieve from the data manager RAM buffer*/
|
||||
static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
{
|
||||
@ -657,14 +579,6 @@ _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
return buffer[0];
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static ssize_t
|
||||
_ram_flash_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
{
|
||||
return dm_ram_operations.read(item, index, buf, count);
|
||||
}
|
||||
#endif
|
||||
|
||||
static int _ram_clear(dm_item_t item)
|
||||
{
|
||||
int i;
|
||||
@ -744,21 +658,6 @@ _file_clear(dm_item_t item)
|
||||
return result;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static int
|
||||
_ram_flash_clear(dm_item_t item)
|
||||
{
|
||||
ssize_t ret = dm_ram_operations.clear(item);
|
||||
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
_ram_flash_update_flush_timeout();
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Tell the data manager about the type of the last reset */
|
||||
static int _ram_restart(dm_reset_reason reason)
|
||||
{
|
||||
@ -871,14 +770,6 @@ _file_restart(dm_reset_reason reason)
|
||||
return result;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static int
|
||||
_ram_flash_restart(dm_reset_reason reason)
|
||||
{
|
||||
return dm_ram_operations.restart(reason);
|
||||
}
|
||||
#endif
|
||||
|
||||
static int
|
||||
_file_initialize(unsigned max_offset)
|
||||
{
|
||||
@ -955,44 +846,6 @@ _ram_initialize(unsigned max_offset)
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static int
|
||||
_ram_flash_initialize(unsigned max_offset)
|
||||
{
|
||||
if (max_offset & 1) {
|
||||
/* STM32 flash API requires half-word(2 bytes) access */
|
||||
max_offset++;
|
||||
}
|
||||
|
||||
if (max_offset > k_dataman_flash_sector->size) {
|
||||
PX4_WARN("Could not allocate %d bytes of flash memory", max_offset);
|
||||
return -1;
|
||||
}
|
||||
|
||||
ssize_t ret = dm_ram_operations.initialize(max_offset);
|
||||
|
||||
if (ret != 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Copy flash to RAM */
|
||||
memcpy(dm_operations_data.ram_flash.data, (void *)k_dataman_flash_sector->address, max_offset);
|
||||
|
||||
struct dataman_compat_s compat_state;
|
||||
ret = g_dm_ops->read(DM_KEY_COMPAT, 0, &compat_state, sizeof(compat_state));
|
||||
|
||||
if (ret != sizeof(compat_state) || compat_state.key != DM_COMPAT_KEY) {
|
||||
/* Not compatible: clear RAM and write DM_KEY_COMPAT(it will flush flash) */
|
||||
memset(dm_operations_data.ram_flash.data, 0, max_offset);
|
||||
|
||||
compat_state.key = DM_COMPAT_KEY;
|
||||
ret = g_dm_ops->write(DM_KEY_COMPAT, 0, DM_PERSIST_POWER_ON_RESET, &compat_state, sizeof(compat_state));
|
||||
}
|
||||
|
||||
return ret > 0 ? 0 : -1;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void
|
||||
_file_shutdown()
|
||||
{
|
||||
@ -1007,66 +860,6 @@ _ram_shutdown()
|
||||
dm_operations_data.running = false;
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
static void
|
||||
_ram_flash_flush()
|
||||
{
|
||||
/*
|
||||
* reseting flush_timeout even in errors cases to avoid looping
|
||||
* forever in case of flash failure.
|
||||
*/
|
||||
dm_operations_data.ram_flash.flush_timeout.tv_nsec = 0;
|
||||
dm_operations_data.ram_flash.flush_timeout.tv_sec = 0;
|
||||
|
||||
ssize_t ret = up_progmem_getpage(k_dataman_flash_sector->address);
|
||||
ret = up_progmem_eraseblock(ret);
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_WARN("Error erasing flash sector %u", k_dataman_flash_sector->page);
|
||||
return;
|
||||
}
|
||||
|
||||
const ssize_t len = (dm_operations_data.ram_flash.data_end - dm_operations_data.ram_flash.data) + 1;
|
||||
ret = up_progmem_write(k_dataman_flash_sector->address, dm_operations_data.ram_flash.data, len);
|
||||
|
||||
if (ret < len) {
|
||||
PX4_WARN("Error writing to flash sector %u, error: %i", k_dataman_flash_sector->page, ret);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
_ram_flash_shutdown()
|
||||
{
|
||||
if (dm_operations_data.ram_flash.flush_timeout.tv_sec) {
|
||||
_ram_flash_flush();
|
||||
}
|
||||
|
||||
dm_ram_operations.shutdown();
|
||||
}
|
||||
|
||||
static int
|
||||
_ram_flash_wait(px4_sem_t *sem)
|
||||
{
|
||||
if (!dm_operations_data.ram_flash.flush_timeout.tv_sec) {
|
||||
px4_sem_wait(sem);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int ret;
|
||||
|
||||
while ((ret = px4_sem_timedwait(sem, &dm_operations_data.ram_flash.flush_timeout)) == -1 && errno == EINTR);
|
||||
|
||||
if (ret == 0) {
|
||||
/* a work was queued before timeout */
|
||||
return 0;
|
||||
}
|
||||
|
||||
_ram_flash_flush();
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
/** Write to the data manager file */
|
||||
__EXPORT ssize_t
|
||||
dm_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
|
||||
@ -1238,15 +1031,6 @@ dm_restart(dm_reset_reason reason)
|
||||
return enqueue_work_item_and_wait_for_result(work);
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
__EXPORT int
|
||||
dm_flash_sector_description_set(const dm_sector_descriptor_t *description)
|
||||
{
|
||||
k_dataman_flash_sector = description;
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int
|
||||
task_main(int argc, char *argv[])
|
||||
{
|
||||
@ -1260,13 +1044,6 @@ task_main(int argc, char *argv[])
|
||||
g_dm_ops = &dm_ram_operations;
|
||||
break;
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
|
||||
case BACKEND_RAM_FLASH:
|
||||
g_dm_ops = &dm_ram_flash_operations;
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
PX4_WARN("No valid backend set.");
|
||||
return -1;
|
||||
@ -1350,14 +1127,6 @@ task_main(int argc, char *argv[])
|
||||
restart_type_str, max_offset);
|
||||
break;
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
|
||||
case BACKEND_RAM_FLASH:
|
||||
PX4_INFO("%s, data manager RAM/Flash size is %d bytes",
|
||||
restart_type_str, max_offset);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@ -1504,8 +1273,6 @@ usage()
|
||||
Module to provide persistent storage for the rest of the system in form of a simple database through a C API.
|
||||
Multiple backends are supported:
|
||||
- a file (eg. on the SD card)
|
||||
- FLASH (if the board supports it)
|
||||
- FRAM
|
||||
- RAM (this is obviously not persistent)
|
||||
|
||||
It is used to store structured data of different types: mission waypoints, mission state and geofence polygons.
|
||||
@ -1526,8 +1293,7 @@ check for geofence violations.
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('f', nullptr, "<file>", "Storage file", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('r', "Use RAM backend (NOT persistent)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('i', "Use FLASH backend", true);
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The options -f, -r and -i are mutually exclusive. If nothing is specified, a file 'dataman' is used");
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The options -f and -r are mutually exclusive. If nothing is specified, a file 'dataman' is used");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("poweronrestart", "Restart dataman (on power on)");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("inflightrestart", "Restart dataman (in flight)");
|
||||
@ -1537,7 +1303,7 @@ check for geofence violations.
|
||||
static int backend_check()
|
||||
{
|
||||
if (backend != BACKEND_NONE) {
|
||||
PX4_WARN("-f, -r and -i are mutually exclusive");
|
||||
PX4_WARN("-f and -r are mutually exclusive");
|
||||
usage();
|
||||
return -1;
|
||||
}
|
||||
@ -1566,7 +1332,7 @@ dataman_main(int argc, char *argv[])
|
||||
|
||||
/* jump over start and look at options first */
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "f:ri", &dmoptind, &dmoptarg)) != EOF) {
|
||||
while ((ch = px4_getopt(argc, argv, "f:r", &dmoptind, &dmoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'f':
|
||||
if (backend_check()) {
|
||||
@ -1586,24 +1352,6 @@ dataman_main(int argc, char *argv[])
|
||||
backend = BACKEND_RAM;
|
||||
break;
|
||||
|
||||
case 'i':
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
if (backend_check()) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (!k_dataman_flash_sector) {
|
||||
PX4_WARN("No flash sector set");
|
||||
return -1;
|
||||
}
|
||||
|
||||
backend = BACKEND_RAM_FLASH;
|
||||
break;
|
||||
#else
|
||||
PX4_WARN("RAM/Flash backend is not available");
|
||||
return -1;
|
||||
#endif
|
||||
|
||||
//no break
|
||||
default:
|
||||
usage();
|
||||
|
||||
@ -163,26 +163,6 @@ dm_restart(
|
||||
dm_reset_reason restart_type /* The last reset type */
|
||||
);
|
||||
|
||||
#if defined(FLASH_BASED_DATAMAN)
|
||||
typedef struct dm_sector_descriptor_t {
|
||||
uint8_t page;
|
||||
uint32_t size;
|
||||
uint32_t address;
|
||||
} dm_sector_descriptor_t;
|
||||
|
||||
/**
|
||||
* Set the flash sector description were data should persist data
|
||||
*
|
||||
* Important: do not use a Flash sector from the same bank that STM32 read
|
||||
* instructions or the CPU will held for sometime during Flash erase and write
|
||||
* and this could cause your drone to fall.
|
||||
*/
|
||||
__EXPORT int
|
||||
dm_flash_sector_description_set(
|
||||
const dm_sector_descriptor_t *description
|
||||
);
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user