aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-20 21:17:50 -0700
committerpx4dev <px4@purgatory.org>2012-08-20 21:17:50 -0700
commit503cb0ea03ecf6922b5c98aeade2a247ed41ac5f (patch)
tree6efe11ba9da6edaf248dcfcdcf35433da84a8749
parenta043702af5e8b778917de2bc3a429880a2e88a38 (diff)
downloadpx4-firmware-503cb0ea03ecf6922b5c98aeade2a247ed41ac5f.tar.gz
px4-firmware-503cb0ea03ecf6922b5c98aeade2a247ed41ac5f.tar.bz2
px4-firmware-503cb0ea03ecf6922b5c98aeade2a247ed41ac5f.zip
Add an ORB topic that can be subscribed for notification of changes in the parameter set.
-rw-r--r--apps/systemlib/param/param.c47
-rw-r--r--apps/systemlib/param/param.h29
-rw-r--r--apps/uORB/topics/parameters.h59
3 files changed, 107 insertions, 28 deletions
diff --git a/apps/systemlib/param/param.c b/apps/systemlib/param/param.c
index 692489cd4..7d0c75670 100644
--- a/apps/systemlib/param/param.c
+++ b/apps/systemlib/param/param.c
@@ -35,6 +35,10 @@
* @file param.c
*
* Global parameter store.
+ *
+ * Note that it might make sense to convert this into a driver. That would
+ * offer some interesting options regarding state for e.g. ORB advertisements
+ * and background parameter saving.
*/
#include <debug.h>
@@ -46,10 +50,15 @@
#include <sys/stat.h>
+#include <arch/board/up_hrt.h>
+
#include "systemlib/param/param.h"
#include "systemlib/uthash/utarray.h"
#include "systemlib/bson/tinybson.h"
+#include "uORB/uORB.h"
+#include "uORB/topics/parameters.h"
+
#if 1
# define debug(fmt, args...) do { warnx(fmt, ##args); } while(0)
#else
@@ -79,6 +88,9 @@ UT_array *param_values;
/** array info for the modified parameters array */
UT_icd param_icd = {sizeof(struct param_wbuf_s), NULL, NULL, NULL};
+/** parameter update topic */
+ORB_DEFINE(parameter_update, struct parameter_update_s);
+
/** lock the parameter store */
static void
param_lock(void)
@@ -369,6 +381,24 @@ param_set(param_t param, const void *val)
out:
param_unlock();
+
+ /*
+ * If we set something, now that we have unlocked, go ahead and advertise that
+ * a thing has been set.
+ */
+ if (result != 0) {
+ struct parameter_update_s pup = { .timestamp = hrt_absolute_time() };
+
+ /*
+ * Because we're a library, we can't keep a persistent advertisement
+ * around, so if we succeed in updating the topic, we have to toss
+ * the descriptor straight away.
+ */
+ int param_topic = orb_advertise(ORB_ID(parameter_update), &pup);
+ if (param_topic != -1)
+ close(param_topic);
+ }
+
return result;
}
@@ -407,6 +437,7 @@ param_export(int fd, bool only_unsaved)
switch (param_type(s->param)) {
case PARAM_TYPE_INT32:
param_get(s->param, &i);
+
if (bson_encoder_append_int(&encoder, param_name(s->param), i)) {
debug("BSON append failed for '%s'", param_name(s->param));
goto out;
@@ -416,6 +447,7 @@ param_export(int fd, bool only_unsaved)
case PARAM_TYPE_FLOAT:
param_get(s->param, &f);
+
if (bson_encoder_append_double(&encoder, param_name(s->param), f)) {
debug("BSON append failed for '%s'", param_name(s->param));
goto out;
@@ -424,7 +456,7 @@ param_export(int fd, bool only_unsaved)
break;
case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
- if (bson_encoder_append_binary(&encoder,
+ if (bson_encoder_append_binary(&encoder,
param_name(s->param),
BSON_BIN_BINARY,
param_size(s->param),
@@ -474,6 +506,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
* ignore the node.
*/
param_t param = param_find(node->name);
+
if (param == PARAM_INVALID)
return 0;
@@ -487,6 +520,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
debug("unexpected type for '%s", node->name);
goto out;
}
+
i = node->i;
v = &i;
break;
@@ -496,6 +530,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
debug("unexpected type for '%s", node->name);
goto out;
}
+
f = node->d;
v = &f;
break;
@@ -505,22 +540,28 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
debug("unexpected subtype for '%s", node->name);
goto out;
}
+
if (bson_decoder_data_pending(decoder) != param_size(param)) {
debug("bad size for '%s'", node->name);
goto out;
}
+
/* XXX check actual file data size? */
tmp = malloc(param_size(param));
+
if (tmp == NULL) {
debug("failed allocating for '%s'", node->name);
goto out;
}
+
if (bson_decoder_copy_data(decoder, tmp)) {
debug("failed copying data for '%s'", node->name);
goto out;
}
+
v = tmp;
break;
+
default:
debug("unrecognised node type");
goto out;
@@ -530,6 +571,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
debug("error setting value for '%s'", node->name);
goto out;
}
+
if (tmp != NULL) {
free(tmp);
tmp = NULL;
@@ -538,8 +580,10 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
result = 0;
out:
+
if (tmp != NULL)
free(tmp);
+
return result;
}
@@ -559,6 +603,7 @@ param_import(int fd)
while (!done) {
result = bson_decoder_next(&decoder);
+
if (result != 0) {
debug("error during BSON decode");
break;
diff --git a/apps/systemlib/param/param.h b/apps/systemlib/param/param.h
index 643d0ef7b..fdd9387e6 100644
--- a/apps/systemlib/param/param.h
+++ b/apps/systemlib/param/param.h
@@ -48,36 +48,11 @@
#include <stdint.h>
#include <stdbool.h>
+#include "drivers/drv_param.h"
+
/** Maximum size of the parameter backing file */
#define PARAM_FILE_MAXSIZE 4096
-/**
- * Parameter types.
- */
-typedef enum param_type_e {
- /* globally-known parameter types */
- PARAM_TYPE_INT32 = 0,
- PARAM_TYPE_FLOAT,
-
- /* structure parameters; size is encoded in the type value */
- PARAM_TYPE_STRUCT = 100,
- PARAM_TYPE_STRUCT_MAX = 16384 + PARAM_TYPE_STRUCT,
-
- PARAM_TYPE_UNKNOWN = 0xffff
-} param_type_t;
-
-/**
- * Parameter handle.
- *
- * Parameters are represented by parameter handles, which can
- * be obtained by looking up (or creating?) parameters.
- */
-typedef uintptr_t param_t;
-
-/**
- * Handle returned when a parameter cannot be found.
- */
-#define PARAM_INVALID ((uintptr_t)0xffffffff)
/**
* Look up a parameter by name.
diff --git a/apps/uORB/topics/parameters.h b/apps/uORB/topics/parameters.h
new file mode 100644
index 000000000..9dd76e8bc
--- /dev/null
+++ b/apps/uORB/topics/parameters.h
@@ -0,0 +1,59 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file parameters.h
+ *
+ * Actuator control topics - mixer inputs.
+ *
+ * Values published to these topics are the outputs of the vehicle control
+ * system, and are expected to be mixed and used to drive the actuators
+ * (servos, speed controls, etc.) that operate the vehicle.
+ *
+ * Each topic can be published by a single controller
+ */
+
+#ifndef TOPIC_PARAMETERS_H
+#define TOPIC_PARAMETERS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+struct parameter_update_s {
+ /** time at which the latest parameter was updated */
+ uint64_t timestamp;
+};
+
+ORB_DECLARE(parameter_update);
+
+#endif \ No newline at end of file