44 #include <px4_platform_common/px4_config.h> 45 #include <px4_platform_common/defines.h> 46 #include <px4_platform_common/module.h> 47 #include <px4_platform_common/posix.h> 48 #include <px4_platform_common/tasks.h> 49 #include <px4_platform_common/getopt.h> 56 #if defined(FLASH_BASED_DATAMAN) 57 #include <nuttx/clock.h> 58 #include <nuttx/progmem.h> 85 #if defined(FLASH_BASED_DATAMAN) 87 #define RAM_FLASH_FLUSH_TIMEOUT_USEC USEC_PER_SEC 91 static ssize_t _ram_flash_read(
dm_item_t item,
unsigned index,
void *buf,
size_t count);
92 static int _ram_flash_clear(
dm_item_t item);
94 static int _ram_flash_initialize(
unsigned max_offset);
95 static void _ram_flash_shutdown();
96 static int _ram_flash_wait(px4_sem_t *sem);
116 .wait = px4_sem_wait,
126 .wait = px4_sem_wait,
129 #if defined(FLASH_BASED_DATAMAN) 131 .
write = _ram_flash_write,
132 .read = _ram_flash_read,
133 .clear = _ram_flash_clear,
134 .restart = _ram_flash_restart,
135 .initialize = _ram_flash_initialize,
136 .shutdown = _ram_flash_shutdown,
137 .wait = _ram_flash_wait,
152 #if defined(FLASH_BASED_DATAMAN) 157 timespec flush_timeout;
219 #define DM_SECTOR_HDR_SIZE 4 224 sizeof(struct mission_fence_point_s) + DM_SECTOR_HDR_SIZE,
225 sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
226 sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
227 sizeof(struct mission_item_s) + DM_SECTOR_HDR_SIZE,
228 sizeof(struct mission_s) + DM_SECTOR_HDR_SIZE,
229 sizeof(struct dataman_compat_s) + DM_SECTOR_HDR_SIZE
247 #if defined(FLASH_BASED_DATAMAN) 248 static const dm_sector_descriptor_t *k_dataman_flash_sector =
nullptr;
255 #if defined(FLASH_BASED_DATAMAN) 281 px4_sem_init(&(q->
mutex), 1, 1);
288 px4_sem_destroy(&(q->
mutex));
294 px4_sem_wait(&(q->
mutex));
300 px4_sem_post(&(q->
mutex));
318 if (item ==
nullptr) {
326 (item + i)->first = 0;
327 sq_addfirst(&(item + i)->link, &(g_free_q.
q));
331 g_free_q.
size += k_work_item_allocation_chunk_size - 1;
343 px4_sem_init(&item->
wait_sem, 1, 0);
347 px4_sem_setprotocol(&item->
wait_sem, SEM_PRIO_NONE);
362 sq_addfirst(&item->
link, &(g_free_q.
q));
393 sq_addlast(&item->
link, &(g_work_q.
q));
403 px4_sem_post(&g_work_queued_sema);
408 int result = item->
result;
476 buffer[1] = persistence;
481 memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
503 if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
509 buffer[1] = persistence;
514 memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
534 #if defined(FLASH_BASED_DATAMAN) 536 _ram_flash_update_flush_timeout()
540 if (clock_gettime(CLOCK_REALTIME, &abstime) == 0) {
541 const unsigned billion = 1000 * 1000 * 1000;
542 uint64_t nsecs = abstime.tv_nsec + (uint64_t)RAM_FLASH_FLUSH_TIMEOUT_USEC * 1000;
543 abstime.tv_sec += nsecs / billion;
544 nsecs -= (nsecs / billion) * billion;
545 abstime.tv_nsec = nsecs;
559 _ram_flash_update_flush_timeout();
593 if (buffer[0] > count) {
598 memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
624 if (count > (g_per_item_size[item] - DM_SECTOR_HDR_SIZE)) {
648 if (buffer[0] > count) {
653 memcpy(buf, buffer + DM_SECTOR_HDR_SIZE, buffer[0]);
660 #if defined(FLASH_BASED_DATAMAN) 662 _ram_flash_read(
dm_item_t item,
unsigned index,
void *buf,
size_t count)
747 #if defined(FLASH_BASED_DATAMAN) 757 _ram_flash_update_flush_timeout();
775 bool clear_entry =
false;
822 if (len !=
sizeof(buffer)) {
830 bool clear_entry =
false;
874 #if defined(FLASH_BASED_DATAMAN) 890 struct dataman_compat_s compat_state;
893 bool incompat =
true;
895 if (ret ==
sizeof(compat_state)) {
904 unlink(k_data_manager_device_path);
909 dm_operations_data.file.fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY, PX4_O_MODE_666);
912 PX4_WARN(
"Could not open data manager file %s", k_data_manager_device_path);
913 px4_sem_post(&g_init_sema);
917 if ((
unsigned)lseek(
dm_operations_data.file.fd, max_offset, SEEK_SET) != max_offset) {
919 PX4_WARN(
"Could not seek data manager file %s", k_data_manager_device_path);
920 px4_sem_post(&g_init_sema);
925 struct dataman_compat_s compat_state;
929 if (ret !=
sizeof(compat_state)) {
930 PX4_ERR(
"Failed writing compat: %d", ret);
946 PX4_WARN(
"Could not allocate %d bytes of memory", max_offset);
947 px4_sem_post(&g_init_sema);
958 #if defined(FLASH_BASED_DATAMAN) 960 _ram_flash_initialize(
unsigned max_offset)
962 if (max_offset & 1) {
967 if (max_offset > k_dataman_flash_sector->size) {
968 PX4_WARN(
"Could not allocate %d bytes of flash memory", max_offset);
979 memcpy(
dm_operations_data.ram_flash.data, (
void *)k_dataman_flash_sector->address, max_offset);
981 struct dataman_compat_s compat_state;
992 return ret > 0 ? 0 : -1;
1010 #if defined(FLASH_BASED_DATAMAN) 1021 ssize_t ret = up_progmem_getpage(k_dataman_flash_sector->address);
1022 ret = up_progmem_eraseblock(ret);
1025 PX4_WARN(
"Error erasing flash sector %u", k_dataman_flash_sector->page);
1030 ret = up_progmem_write(k_dataman_flash_sector->address,
dm_operations_data.ram_flash.data, len);
1033 PX4_WARN(
"Error writing to flash sector %u, error: %i", k_dataman_flash_sector->page, ret);
1039 _ram_flash_shutdown()
1049 _ram_flash_wait(px4_sem_t *sem)
1058 while ((ret = px4_sem_timedwait(sem, &
dm_operations_data.ram_flash.flush_timeout)) == -1 && errno == EINTR);
1170 if (g_item_locks[item]) {
1171 return px4_sem_wait(g_item_locks[item]);
1192 if (g_item_locks[item]) {
1193 return px4_sem_trywait(g_item_locks[item]);
1213 if (g_item_locks[item]) {
1214 px4_sem_post(g_item_locks[item]);
1241 #if defined(FLASH_BASED_DATAMAN) 1243 dm_flash_sector_description_set(
const dm_sector_descriptor_t *description)
1245 k_dataman_flash_sector = description;
1263 #if defined(FLASH_BASED_DATAMAN) 1265 case BACKEND_RAM_FLASH:
1266 g_dm_ops = &dm_ram_flash_operations;
1271 PX4_WARN(
"No valid backend set.");
1278 g_key_offsets[0] = 0;
1292 px4_sem_init(&g_sys_state_mutex_mission, 1, 1);
1293 px4_sem_init(&g_sys_state_mutex_fence, 1, 1);
1296 g_item_locks[i] =
nullptr;
1302 g_task_should_exit =
false;
1307 px4_sem_init(&g_work_queued_sema, 1, 0);
1311 px4_sem_setprotocol(&g_work_queued_sema, SEM_PRIO_NONE);
1317 int sys_restart_val;
1319 const char *restart_type_str =
"Unknown restart";
1324 g_task_should_exit =
true;
1330 restart_type_str =
"Power on restart";
1334 restart_type_str =
"In flight restart";
1342 PX4_INFO(
"%s, data manager file '%s' size is %d bytes",
1343 restart_type_str, k_data_manager_device_path, max_offset);
1349 PX4_INFO(
"%s, data manager RAM size is %d bytes",
1350 restart_type_str, max_offset);
1353 #if defined(FLASH_BASED_DATAMAN) 1355 case BACKEND_RAM_FLASH:
1356 PX4_INFO(
"%s, data manager RAM/Flash size is %d bytes",
1357 restart_type_str, max_offset);
1366 px4_sem_post(&g_init_sema);
1372 if (!g_task_should_exit) {
1374 g_dm_ops->
wait(&g_work_queued_sema);
1381 switch (work->
func) {
1416 if (g_task_should_exit) {
1425 if ((work = (
work_q_item_t *)sq_remfirst(&(g_free_q.
q))) ==
nullptr) {
1438 px4_sem_destroy(&g_work_queued_sema);
1439 px4_sem_destroy(&g_sys_state_mutex_mission);
1440 px4_sem_destroy(&g_sys_state_mutex_fence);
1456 px4_sem_init(&g_init_sema, 1, 0);
1460 px4_sem_setprotocol(&g_init_sema, SEM_PRIO_NONE);
1465 px4_sem_destroy(&g_init_sema);
1466 PX4_ERR(
"task start failed");
1471 px4_sem_wait(&g_init_sema);
1472 px4_sem_destroy(&g_init_sema);
1485 PX4_INFO(
"Max Q lengths work %d, free %d", g_work_q.
max_size, g_free_q.
max_size);
1494 g_task_should_exit =
true;
1495 px4_sem_post(&g_work_queued_sema);
1501 PRINT_MODULE_DESCRIPTION(
1504 Module to provide persistent storage for the rest of the system in form of a simple database through a C API. 1505 Multiple backends are supported: 1506 - a file (eg. on the SD card) 1507 - FLASH (if the board supports it) 1509 - RAM (this is obviously not persistent) 1511 It is used to store structured data of different types: mission waypoints, mission state and geofence polygons. 1512 Each type has a specific type and a fixed maximum amount of storage items, so that fast random access is possible. 1515 Reading and writing a single item is always atomic. If multiple items need to be read/modified atomically, there is 1516 an additional lock per item type via `dm_lock`. 1518 **DM_KEY_FENCE_POINTS** and **DM_KEY_SAFE_POINTS** items: the first data element is a `mission_stats_entry_s` struct, 1519 which stores the number of items for these types. These items are always updated atomically in one transaction (from 1520 the mavlink mission manager). During that time, navigator will try to acquire the geofence item lock, fail, and will not 1521 check for geofence violations. 1525 PRINT_MODULE_USAGE_NAME("dataman",
"system");
1526 PRINT_MODULE_USAGE_COMMAND(
"start");
1527 PRINT_MODULE_USAGE_PARAM_STRING(
'f',
nullptr,
"<file>",
"Storage file",
true);
1528 PRINT_MODULE_USAGE_PARAM_FLAG(
'r',
"Use RAM backend (NOT persistent)",
true);
1529 PRINT_MODULE_USAGE_PARAM_FLAG(
'i',
"Use FLASH backend",
true);
1530 PRINT_MODULE_USAGE_PARAM_COMMENT(
"The options -f, -r and -i are mutually exclusive. If nothing is specified, a file 'dataman' is used");
1532 PRINT_MODULE_USAGE_COMMAND_DESCR(
"poweronrestart",
"Restart dataman (on power on)");
1533 PRINT_MODULE_USAGE_COMMAND_DESCR(
"inflightrestart",
"Restart dataman (in flight)");
1534 PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
1540 PX4_WARN(
"-f, -r and -i are mutually exclusive");
1556 if (!strcmp(argv[1],
"start")) {
1559 PX4_WARN(
"dataman already running");
1565 const char *dmoptarg =
nullptr;
1569 while ((ch = px4_getopt(argc, argv,
"f:ri", &dmoptind, &dmoptarg)) != EOF) {
1577 k_data_manager_device_path = strdup(dmoptarg);
1578 PX4_INFO(
"dataman file set to: %s", k_data_manager_device_path);
1590 #if defined(FLASH_BASED_DATAMAN) 1595 if (!k_dataman_flash_sector) {
1596 PX4_WARN(
"No flash sector set");
1600 backend = BACKEND_RAM_FLASH;
1603 PX4_WARN(
"RAM/Flash backend is not available");
1616 k_data_manager_device_path = strdup(default_device_path);
1622 PX4_ERR(
"dataman start failed");
1623 free(k_data_manager_device_path);
1624 k_data_manager_device_path =
nullptr;
1633 PX4_WARN(
"dataman worker thread not running");
1638 if (!strcmp(argv[1],
"stop")) {
1640 free(k_data_manager_device_path);
1641 k_data_manager_device_path =
nullptr;
1643 }
else if (!strcmp(argv[1],
"status")) {
1646 }
else if (!strcmp(argv[1],
"poweronrestart")) {
1649 }
else if (!strcmp(argv[1],
"inflightrestart")) {
const size_t k_work_item_allocation_chunk_size
int(* clear)(dm_item_t item)
measure the time elapsed performing an event
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
static ssize_t _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
__EXPORT int dm_lock(dm_item_t item)
Lock all items of a type.
dm_reset_reason
The reason for the last reset.
static perf_counter_t _dm_write_perf
static perf_counter_t _dm_read_perf
#define DM_SECTOR_HDR_SIZE
struct work_q_item_t::@89::@91 write_params
dm_item_t
Types of items that the data manager can store.
static unsigned g_func_counts[dm_number_of_funcs]
static bool g_task_should_exit
if true, dataman task should exit
static int task_main(int argc, char *argv[])
static int backend_check()
static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS]
static px4_sem_t g_work_queued_sema
static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
High-resolution timer with callouts and timekeeping.
dm_persitence_t persistence
int(* initialize)(unsigned max_offset)
Global flash based parameter store.
static constexpr dm_operations_t dm_ram_operations
int(* restart)(dm_reset_reason reason)
int(* wait)(px4_sem_t *sem)
static ssize_t _ram_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
static __END_DECLS constexpr int TASK_STACK_SIZE
static const dm_operations_t * g_dm_ops
static ssize_t _file_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
struct work_q_item_t::@89::@93 clear_params
__EXPORT ssize_t dm_read(dm_item_t item, unsigned index, void *buf, size_t count)
Retrieve from the data manager file.
dm_function_t
Types of function calls supported by the worker task.
static int enqueue_work_item_and_wait_for_result(work_q_item_t *item)
__EXPORT int dm_restart(dm_reset_reason reason)
Tell the data manager about the type of the last reset.
void perf_free(perf_counter_t handle)
Free a counter.
static void lock_queue(work_q_t *q)
static struct @83 dm_operations_data
static int _file_restart(dm_reset_reason reason)
static px4_sem_t g_sys_state_mutex_mission
struct work_q_item_t::@89::@94 restart_params
static int _file_initialize(unsigned max_offset)
static int _ram_restart(dm_reset_reason reason)
static px4_sem_t * g_item_locks[DM_KEY_NUM_KEYS]
static void destroy_q(work_q_t *q)
static void _ram_shutdown()
__EXPORT int dm_trylock(dm_item_t item)
Try to lock all items of a type (.
static void destroy_work_item(work_q_item_t *item)
__BEGIN_DECLS __EXPORT int dataman_main(int argc, char *argv[])
void perf_end(perf_counter_t handle)
End a performance event.
static constexpr size_t g_per_item_size[DM_KEY_NUM_KEYS]
static work_q_item_t * dequeue_work_item()
ssize_t(* write)(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Safe Point (Rally Point).
static const char * default_device_path
__EXPORT void dm_unlock(dm_item_t item)
Unlock a data Item.
static int _ram_initialize(unsigned max_offset)
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
static px4_sem_t g_init_sema
struct work_q_item_t::@89::@92 read_params
ssize_t(* read)(dm_item_t item, unsigned index, void *buf, size_t count)
sq_entry_t link
list linkage
static void unlock_queue(work_q_t *q)
static int calculate_offset(dm_item_t item, unsigned index)
static int _ram_clear(dm_item_t item)
dm_persitence_t
Data persistence levels.
struct @83::@85::@87 file
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
static void _file_shutdown()
__EXPORT ssize_t dm_write(dm_item_t item, unsigned index, dm_persitence_t persistence, const void *buf, size_t count)
Write to the data manager file.
static work_q_item_t * create_work_item()
static void init_q(work_q_t *q)
struct dm_operations_t dm_operations_t
static px4_sem_t g_sys_state_mutex_fence
static int _file_clear(dm_item_t item)
static char * k_data_manager_device_path
void perf_begin(perf_counter_t handle)
Begin a performance event.
static constexpr dm_operations_t dm_file_operations
static unsigned int g_key_offsets[DM_KEY_NUM_KEYS]
__EXPORT int dm_clear(dm_item_t item)
Clear a data Item.
Performance measuring tools.