aboutsummaryrefslogtreecommitdiff
path: root/src/modules/dataman/dataman.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/dataman/dataman.c')
-rw-r--r--src/modules/dataman/dataman.c105
1 files changed, 78 insertions, 27 deletions
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 34d20e485..406293bda 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Jean Cyr
- * Lorenz Meier
- * Julian Oes
- * Thomas Gubler
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +33,11 @@
/**
* @file dataman.c
* DATAMANAGER driver.
+ *
+ * @author Jean Cyr
+ * @author Lorenz Meier
+ * @author Julian Oes
+ * @author Thomas Gubler
*/
#include <nuttx/config.h>
@@ -44,9 +45,12 @@
#include <stdlib.h>
#include <fcntl.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <queue.h>
+#include <string.h>
#include "dataman.h"
+#include <systemlib/param/param.h>
/**
* data manager app start / stop handling function
@@ -60,7 +64,7 @@ __EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t
__EXPORT int dm_clear(dm_item_t item);
__EXPORT int dm_restart(dm_reset_reason restart_type);
-/* Types of function calls supported by the worker task */
+/** Types of function calls supported by the worker task */
typedef enum {
dm_write_func = 0,
dm_read_func,
@@ -69,11 +73,12 @@ typedef enum {
dm_number_of_funcs
} dm_function_t;
-/* Work task work item */
+/** Work task work item */
typedef struct {
sq_entry_t link; /**< list linkage */
sem_t wait_sem;
- dm_function_t func;
+ unsigned char first;
+ unsigned char func;
ssize_t result;
union {
struct {
@@ -98,6 +103,8 @@ typedef struct {
};
} work_q_item_t;
+const size_t k_work_item_allocation_chunk_size = 8;
+
/* Usage statistics */
static unsigned g_func_counts[dm_number_of_funcs];
@@ -175,9 +182,23 @@ create_work_item(void)
unlock_queue(&g_free_q);
- /* If we there weren't any free items then obtain memory for a new one */
- if (item == NULL)
- item = (work_q_item_t *)malloc(sizeof(work_q_item_t));
+ /* If we there weren't any free items then obtain memory for a new ones */
+ if (item == NULL) {
+ item = (work_q_item_t *)malloc(k_work_item_allocation_chunk_size * sizeof(work_q_item_t));
+ if (item) {
+ item->first = 1;
+ lock_queue(&g_free_q);
+ for (size_t i = 1; i < k_work_item_allocation_chunk_size; i++) {
+ (item + i)->first = 0;
+ sq_addfirst(&(item + i)->link, &(g_free_q.q));
+ }
+ /* Update the queue size and potentially the maximum queue size */
+ g_free_q.size += k_work_item_allocation_chunk_size - 1;
+ if (g_free_q.size > g_free_q.max_size)
+ g_free_q.max_size = g_free_q.size;
+ unlock_queue(&g_free_q);
+ }
+ }
/* If we got one then lock the item*/
if (item)
@@ -409,31 +430,31 @@ _clear(dm_item_t item)
return result;
}
-/* Tell the data manager about the type of the last reset */
+/** Tell the data manager about the type of the last reset */
static int
_restart(dm_reset_reason reason)
{
unsigned char buffer[2];
- int offset, result = 0;
+ int offset = 0, result = 0;
/* We need to scan the entire file and invalidate and data that should not persist after the last reset */
/* Loop through all of the data segments and delete those that are not persistent */
- offset = 0;
-
while (1) {
size_t len;
/* Get data segment at current offset */
if (lseek(g_task_fd, offset, SEEK_SET) != offset) {
- result = -1;
+ /* must be at eof */
break;
}
len = read(g_task_fd, buffer, sizeof(buffer));
- if (len == 0)
+ if (len != sizeof(buffer)) {
+ /* must be at eof */
break;
+ }
/* check if segment contains data */
if (buffer[0]) {
@@ -441,12 +462,12 @@ _restart(dm_reset_reason reason)
/* Whether data gets deleted depends on reset type and data segment's persistence setting */
if (reason == DM_INIT_REASON_POWER_ON) {
- if (buffer[1] != DM_PERSIST_POWER_ON_RESET) {
+ if (buffer[1] > DM_PERSIST_POWER_ON_RESET) {
clear_entry = 1;
}
} else {
- if ((buffer[1] != DM_PERSIST_POWER_ON_RESET) && (buffer[1] != DM_PERSIST_IN_FLIGHT_RESET)) {
+ if (buffer[1] > DM_PERSIST_IN_FLIGHT_RESET) {
clear_entry = 1;
}
}
@@ -478,7 +499,7 @@ _restart(dm_reset_reason reason)
return result;
}
-/* write to the data manager file */
+/** Write to the data manager file */
__EXPORT ssize_t
dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
{
@@ -503,7 +524,7 @@ dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const
return (ssize_t)enqueue_work_item_and_wait_for_result(work);
}
-/* Retrieve from the data manager file */
+/** Retrieve from the data manager file */
__EXPORT ssize_t
dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
{
@@ -594,6 +615,20 @@ task_main(int argc, char *argv[])
sem_init(&g_work_queued_sema, 1, 0);
+ /* See if the data manage file exists and is a multiple of the sector size */
+ g_task_fd = open(k_data_manager_device_path, O_RDONLY | O_BINARY);
+ if (g_task_fd >= 0) {
+ /* File exists, check its size */
+ int file_size = lseek(g_task_fd, 0, SEEK_END);
+ if ((file_size % k_sector_size) != 0) {
+ warnx("Incompatible data manager file %s, resetting it", k_data_manager_device_path);
+ close(g_task_fd);
+ unlink(k_data_manager_device_path);
+ }
+ else
+ close(g_task_fd);
+ }
+
/* Open or create the data manager file */
g_task_fd = open(k_data_manager_device_path, O_RDWR | O_CREAT | O_BINARY);
@@ -603,7 +638,7 @@ task_main(int argc, char *argv[])
return -1;
}
- if (lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
+ if ((unsigned)lseek(g_task_fd, max_offset, SEEK_SET) != max_offset) {
close(g_task_fd);
warnx("Could not seek data manager file %s", k_data_manager_device_path);
sem_post(&g_init_sema); /* Don't want to hang startup */
@@ -612,6 +647,23 @@ task_main(int argc, char *argv[])
fsync(g_task_fd);
+ /* see if we need to erase any items based on restart type */
+ int sys_restart_val;
+ if (param_get(param_find("SYS_RESTART_TYPE"), &sys_restart_val) == OK) {
+ if (sys_restart_val == DM_INIT_REASON_POWER_ON) {
+ warnx("Power on restart");
+ _restart(DM_INIT_REASON_POWER_ON);
+ }
+ else if (sys_restart_val == DM_INIT_REASON_IN_FLIGHT) {
+ warnx("In flight restart");
+ _restart(DM_INIT_REASON_IN_FLIGHT);
+ }
+ else
+ warnx("Unknown restart");
+ }
+ else
+ warnx("Unknown restart");
+
/* We use two file descriptors, one for the caller context and one for the worker thread */
/* They are actually the same but we need to some way to reject caller request while the */
/* worker thread is shutting down but still processing requests */
@@ -684,8 +736,8 @@ task_main(int argc, char *argv[])
for (;;) {
if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
break;
-
- free(work);
+ if (work->first)
+ free(work);
}
destroy_q(&g_work_q);
@@ -703,12 +755,12 @@ start(void)
sem_init(&g_init_sema, 1, 0);
/* start the worker thread */
- if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) {
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2000, task_main, NULL)) <= 0) {
warn("task start failed");
return -1;
}
- /* wait for the thread to actuall initialize */
+ /* wait for the thread to actually initialize */
sem_wait(&g_init_sema);
sem_destroy(&g_init_sema);
@@ -776,4 +828,3 @@ dataman_main(int argc, char *argv[])
exit(1);
}
-