aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-19 22:15:29 -0700
committerpx4dev <px4@purgatory.org>2012-08-19 22:15:29 -0700
commitf8efb60b593be66534a4fdca554d03913a1b5651 (patch)
tree8fd8af38c7d645a7a7b9c1353f3aa7bc83dd94d5 /apps
parentc729bf98fee00b3decbc178cbd5a3f9b96a064a1 (diff)
downloadpx4-firmware-f8efb60b593be66534a4fdca554d03913a1b5651.tar.gz
px4-firmware-f8efb60b593be66534a4fdca554d03913a1b5651.tar.bz2
px4-firmware-f8efb60b593be66534a4fdca554d03913a1b5651.zip
Major cleanup of the param code; more layering, more comments. Parameter import.
Diffstat (limited to 'apps')
-rw-r--r--apps/systemlib/param/param.c369
-rw-r--r--apps/systemlib/param/param.h107
2 files changed, 387 insertions, 89 deletions
diff --git a/apps/systemlib/param/param.c b/apps/systemlib/param/param.c
index 315ba187b..78f3f7468 100644
--- a/apps/systemlib/param/param.c
+++ b/apps/systemlib/param/param.c
@@ -1,64 +1,122 @@
+/****************************************************************************
+ *
+ * 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 param.c
*
* Global parameter store.
*/
+#include <debug.h>
#include <string.h>
#include <stdbool.h>
#include <fcntl.h>
#include <unistd.h>
#include <err.h>
+#include <sys/stat.h>
+
#include "systemlib/param/param.h"
#include "systemlib/uthash/utarray.h"
#include "systemlib/bson/bson.h"
+#if 1
+# define debug(fmt, args...) do { warnx(fmt, ##args); } while(0)
+#else
+# define debug(fmt, args...) do { } while(0)
+#endif
+
/**
* Array of static parameter info.
*/
extern char __param_start, __param_end;
-static const struct param_info_s *param_info_base = (struct param_info_s *)&__param_start;
-static const struct param_info_s *param_info_limit = (struct param_info_s *)&__param_end;
+static const struct param_info_s *param_info_base = (struct param_info_s *) &__param_start;
+static const struct param_info_s *param_info_limit = (struct param_info_s *) &__param_end;
#define param_info_count ((unsigned)(param_info_limit - param_info_base))
/**
* Storage for modified parameters.
*/
-struct param_wbuf_s
-{
+struct param_wbuf_s {
param_t param;
union param_value_u val;
bool unsaved;
};
-UT_icd param_icd = {sizeof(struct param_wbuf_s), NULL, NULL, NULL};
+/** flexible array holding modified parameter values */
UT_array *param_values;
+/** array info for the modified parameters array */
+UT_icd param_icd = {sizeof(struct param_wbuf_s), NULL, NULL, NULL};
+
+/** lock the parameter store */
static void
param_lock(void)
{
/* XXX */
}
+/** unlock the parameter store */
static void
param_unlock(void)
{
/* XXX */
}
+/** assert that the parameter store is locked */
static void
param_assert_locked(void)
{
/* XXX */
}
+/**
+ * Test whether a param_t is value.
+ *
+ * @param param The parameter handle to test.
+ * @return True if the handle is valid.
+ */
static bool
-handle_in_range(param_t handle)
+handle_in_range(param_t param)
{
- return (handle < param_info_count);
+ return (param < param_info_count);
}
+/**
+ * Compare two modifid parameter structures to determine ordering.
+ *
+ * This function is suitable for passing to qsort or bsearch.
+ */
static int
param_compare_values(const void *a, const void *b)
{
@@ -67,14 +125,22 @@ param_compare_values(const void *a, const void *b)
if (pa->param < pb->param)
return -1;
+
if (pa->param > pb->param)
return 1;
+
return 0;
}
+/**
+ * Locate the modified parameter structure for a parameter, if it exists.
+ *
+ * @param param The parameter being searched.
+ * @return The structure holding the modified value, or
+ * NULL if the parameter has not been modified.
+ */
static struct param_wbuf_s *
-param_find_changed(param_t param)
-{
+param_find_changed(param_t param) {
struct param_wbuf_s *s = NULL;
param_assert_locked();
@@ -85,12 +151,15 @@ param_find_changed(param_t param)
key.param = param;
s = utarray_find(param_values, &key, param_compare_values);
#else
+
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != NULL) {
if (s->param == param)
break;
}
+
#endif
}
+
return s;
}
@@ -99,6 +168,7 @@ param_find(const char *name)
{
param_t param;
+ /* perform a linear search of the known parameters */
for (param = 0; handle_in_range(param); param++) {
if (!strcmp(param_info_base[param].name, name))
return param;
@@ -108,16 +178,31 @@ param_find(const char *name)
return PARAM_INVALID;
}
+unsigned
+param_count(void)
+{
+ return param_info_count;
+}
+
+param_t
+param_for_index(unsigned index)
+{
+ if (index < param_info_count)
+ return (param_t)index;
+
+ return PARAM_INVALID;
+}
+
const char *
param_name(param_t param)
{
if (handle_in_range(param))
return param_info_base[param].name;
- return NULL;
+ return NULL;
}
-enum param_type_e
+enum param_type_e
param_type(param_t param)
{
if (handle_in_range(param))
@@ -130,13 +215,14 @@ size_t
param_size(param_t param)
{
if (handle_in_range(param)) {
- switch (param_info_base[param].type) {
+ switch (param_type(param)) {
case PARAM_TYPE_INT32:
case PARAM_TYPE_FLOAT:
return 4;
case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
- return param_info_base[param].type - PARAM_TYPE_STRUCT;
+ /* decode structure size from type value */
+ return param_type(param) - PARAM_TYPE_STRUCT;
default:
return 0;
@@ -146,47 +232,57 @@ param_size(param_t param)
return 0;
}
-int
-param_get(param_t param, void *val)
+/**
+ * Obtain a pointer to the storage allocated for a parameter.
+ *
+ * @param param The parameter whose storage is sought.
+ * @return A pointer to the parameter value, or NULL
+ * if the parameter does not exist.
+ */
+static const void *
+param_get_value_ptr(param_t param)
{
- int result = -1;
+ const void *result = NULL;
- param_lock();
+ param_assert_locked();
if (handle_in_range(param)) {
- struct param_wbuf_s *s = param_find_changed(param);
const union param_value_u *v;
/* work out whether we're fetching the default or a written value */
+ struct param_wbuf_s *s = param_find_changed(param);
+
if (s != NULL) {
v = &s->val;
+
} else {
v = &param_info_base[param].val;
}
- /* XXX look for updated value stored elsewhere */
+ if (param_type(param) == PARAM_TYPE_STRUCT) {
+ result = v->p;
- switch (param_info_base[param].type) {
- case PARAM_TYPE_INT32:
- *(int32_t *)val = v->i;
- result = 0;
- break;
+ } else {
+ result = v;
+ }
+ }
- case PARAM_TYPE_FLOAT:
- *(float *)val = v->f;
- result = 0;
- break;
+ return result;
+}
- case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
- *(void **)val = v->p;
- result = 0;
- break;
+int
+param_get(param_t param, void *val)
+{
+ int result = -1;
- default:
- break;
- }
+ param_lock();
+ const void *v = param_get_value_ptr(param);
+
+ if (val != NULL) {
+ memcpy(val, v, param_size(param));
+ result = 0;
}
param_unlock();
@@ -195,7 +291,7 @@ param_get(param_t param, void *val)
}
int
-param_set(param_t param, void *val)
+param_set(param_t param, const void *val)
{
int result = -1;
@@ -203,8 +299,11 @@ param_set(param_t param, void *val)
if (param_values == NULL)
utarray_new(param_values, &param_icd);
- if (param_values == NULL)
+
+ if (param_values == NULL) {
+ debug("failed to allocate modified values array");
goto out;
+ }
if (handle_in_range(param)) {
@@ -213,7 +312,11 @@ param_set(param_t param, void *val)
if (s == NULL) {
/* construct a new parameter */
- struct param_wbuf_s buf = { .param = param };
+ struct param_wbuf_s buf = {
+ .param = param,
+ .val.p = NULL,
+ .unsaved = false
+ };
/* add it to the array and sort */
utarray_push_back(param_values, &buf);
@@ -224,7 +327,7 @@ param_set(param_t param, void *val)
}
/* update the changed value */
- switch (param_info_base[param].type) {
+ switch (param_type(param)) {
case PARAM_TYPE_INT32:
s->val.i = *(int32_t *)val;
break;
@@ -234,25 +337,36 @@ param_set(param_t param, void *val)
break;
case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
- s->val.p = *(void **)val;
+ if (s->val.p == NULL) {
+ s->val.p = malloc(param_size(param));
+
+ if (s->val.p == NULL) {
+ debug("failed to allocate parameter storage");
+ goto out;
+ }
+ }
+
+ memcpy(s->val.p, val, param_size(param));
break;
default:
goto out;
}
+
s->unsaved = true;
result = 0;
}
+
out:
param_unlock();
return result;
}
int
-param_export(const char *filename, bool only_unsaved)
+param_export(int fd, bool only_unsaved)
{
- struct param_wbuf_s *s;
+ struct param_wbuf_s *s = NULL;
bson b[1];
int result = -1;
@@ -260,69 +374,200 @@ param_export(const char *filename, bool only_unsaved)
bson_init(b);
+ /* no modified parameters -> we are done */
+ if (param_values == NULL) {
+ result = 0;
+ goto out;
+ }
+
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != NULL) {
- const struct param_info_s *is = &param_info_base[s->param];
- /*
- * if we are only saving values changed since last save, and this
+ int32_t i;
+ float f;
+
+ /*
+ * If we are only saving values changed since last save, and this
* one hasn't, then skip it
*/
if (only_unsaved & !s->unsaved)
continue;
+
s->unsaved = false;
- switch (is->type) {
+ /* append the appripriate BSON type object */
+ switch (param_type(s->param)) {
case PARAM_TYPE_INT32:
- if (bson_append_int(b, is->name, s->val.i) != BSON_OK)
+ param_get(s->param, &i);
+
+ if (bson_append_int(b, param_name(s->param), i) != BSON_OK) {
+ debug("BSON append failed for '%s'", param_name(s->param));
goto out;
+ }
+
break;
case PARAM_TYPE_FLOAT:
- if (bson_append_double(b, is->name, s->val.f) != BSON_OK)
+ param_get(s->param, &f);
+
+ if (bson_append_double(b, param_name(s->param), (double)f) != BSON_OK) {
+ debug("BSON append failed for '%s'", param_name(s->param));
goto out;
+ }
+
break;
case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
- if (bson_append_binary(b,
- is->name,
- is->type,
- is->val.p,
- is->type - PARAM_TYPE_STRUCT) != BSON_OK)
+ if (bson_append_binary(b,
+ param_name(s->param),
+ param_type(s->param),
+ param_get_value_ptr(s->param),
+ param_size(s->param)) != BSON_OK) {
+ debug("BSON append failed for '%s'", param_name(s->param));
goto out;
+ }
+
break;
+
default:
+ debug("unrecognised parameter type");
goto out;
}
}
+
result = 0;
out:
param_unlock();
if (result == 0) {
+ /* finalize the object ready for saving */
bson_finish(b);
+
+ /* print it for debugging purposes only */
bson_print(b);
- warnx("object is %d bytes", bson_buffer_size(b));
+ if (bson_buffer_size(b) > PARAM_FILE_MAXSIZE) {
+ debug("parameter export file too large");
+ result = -1;
- if (filename != NULL) {
- int fd = open(filename, O_CREAT | O_WRONLY | O_TRUNC, 0666);
- int siz = bson_buffer_size(b);
- int len = write(fd, bson_data(b), siz);
- close(fd);
- if (len != siz)
+ } else if (fd >= 0) {
+ int len = write(fd, bson_data(b), bson_buffer_size(b));
+
+ if (len != bson_buffer_size(b)) {
+ debug("wriet size mismatch");
result = -1;
+ }
}
}
+
bson_destroy(b);
return result;
}
int
-param_import(const char *filename)
+param_import(int fd)
{
- return -1;
+ bson b[1];
+ bson_iterator iter[1];
+ int result = -1;
+ char *raw = NULL;
+ bson_type type;
+ const char *name;
+ param_t param;
+ ssize_t size;
+
+ /* load the bson object from the parameter file */
+ raw = malloc(PARAM_FILE_MAXSIZE);
+ size = read(fd, raw, PARAM_FILE_MAXSIZE);
+ if (size < 0) {
+ debug("read failed for parameter data");
+ goto out;
+ }
+
+ if (bson_init_finished_data(b, raw) != BSON_OK) {
+ debug("BSON init error");
+ goto out;
+ }
+
+ bson_iterator_init(iter, b);
+
+ while ((type = bson_iterator_next(iter)) != BSON_EOO) {
+
+ int32_t i;
+ float f;
+ const void *v;
+
+ /* get the parameter name */
+ name = bson_iterator_key(iter);
+ param = param_find(name);
+
+ /* ignore unknown parameters */
+ if (param == PARAM_INVALID) {
+ debug("ignoring unknown parameter '%s'", name);
+ continue;
+ }
+
+ /* get a pointer to the data we are importing */
+ switch (type) {
+ case BSON_INT:
+ if (param_type(param) != PARAM_TYPE_INT32) {
+ debug("unexpected BSON_INT for '%s'", name);
+ goto out;
+ }
+
+ i = bson_iterator_int(iter);
+ v = &i;
+
+ break;
+
+ case BSON_DOUBLE:
+ if (param_type(param) != PARAM_TYPE_FLOAT) {
+ debug("unexpected BSON_FLOAT for '%s'", name);
+ goto out;
+ }
+
+ f = bson_iterator_double(iter);
+ v = &f;
+
+ break;
+
+ case BSON_BINDATA:
+ if (bson_iterator_bin_type(iter) != param_type(param)) {
+ debug("BSON_BINDATA type does not match '%s'", name);
+ goto out;
+ }
+
+ if (bson_iterator_bin_len(iter) != param_size(param)) {
+ debug("BSON_BINDATA size does not match '%s'", name);
+ goto out;
+ }
+
+ v = bson_iterator_bin_data(iter);
+
+ break;
+
+ default:
+ goto out;
+ }
+
+ /* set the parameter */
+ if (param_set(param, v) != 0) {
+ debug("param_set failed for '%s'", name);
+ goto out;
+ }
+ }
+ result = 0;
+out:
+
+ if (fd >= 0)
+ close(fd);
+
+ if (raw != NULL)
+ free(raw);
+
+ bson_destroy(b); /* XXX safe if bson_init was not called? */
+ return result;
}
void
diff --git a/apps/systemlib/param/param.h b/apps/systemlib/param/param.h
index 0d94ce6e3..29857b46b 100644
--- a/apps/systemlib/param/param.h
+++ b/apps/systemlib/param/param.h
@@ -1,7 +1,45 @@
+/****************************************************************************
+ *
+ * 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 param.h
*
* Global parameter store.
+ *
+ * Note that a number of API members are marked const or pure; these
+ * assume that the set of parameters cannot change, or that a parameter
+ * cannot change type or size over its lifetime. If any of these assumptions
+ * are invalidated, the attributes should be re-evaluated.
*/
#ifndef _SYSTEMLIB_PARAM_PARAM_H
@@ -10,16 +48,18 @@
#include <stdint.h>
#include <stdbool.h>
+/** Maximum size of the parameter backing file */
+#define PARAM_FILE_MAXSIZE 4096
+
/**
* Parameter types.
*/
-typedef enum param_type_e
-{
+typedef enum param_type_e {
/* globally-known parameter types */
PARAM_TYPE_INT32 = 0,
PARAM_TYPE_FLOAT,
- /* structure parameters; these are expected to be identified by name */
+ /* structure parameters; size is encoded in the type value */
PARAM_TYPE_STRUCT = 100,
PARAM_TYPE_STRUCT_MAX = 16384 + PARAM_TYPE_STRUCT,
@@ -45,7 +85,22 @@ typedef uintptr_t param_t;
* @param name The canonical name of the parameter being looked up.
* @return A handle to the parameter, or PARAM_INVALID if the parameter does not exist.
*/
-__EXPORT param_t param_find(const char *name);
+__EXPORT param_t param_find(const char *name) __attribute__((const));
+
+/**
+ * Return the total number of parameters.
+ *
+ * @return The number of parameters.
+ */
+__EXPORT unsigned param_count(void) __attribute__((const));
+
+/**
+ * Look up a parameter by index.
+ *
+ * @param index An index from 0 to n, where n is param_count()-1.
+ * @return A handle to the parameter, or PARAM_INVALID if the index is out of range.
+ */
+__EXPORT param_t param_for_index(unsigned index) __attribute__((const));
/**
* Obtain the name of a parameter.
@@ -53,7 +108,7 @@ __EXPORT param_t param_find(const char *name);
* @param param A handle returned by param_find or passed by param_foreach.
* @return The name assigned to the parameter, or NULL if the handle is invalid.
*/
-__EXPORT const char *param_name(param_t param);
+__EXPORT const char *param_name(param_t param) __attribute__((const));
/**
* Obtain the type of a parameter.
@@ -61,7 +116,7 @@ __EXPORT const char *param_name(param_t param);
* @param param A handle returned by param_find or passed by param_foreach.
* @return The type assigned to the parameter.
*/
-__EXPORT param_type_t param_type(param_t param);
+__EXPORT param_type_t param_type(param_t param) __attribute__((const));
/**
* Determine the size of a parameter.
@@ -69,15 +124,15 @@ __EXPORT param_type_t param_type(param_t param);
* @param param A handle returned by param_find or passed by param_foreach.
* @return The size of the parameter's value.
*/
-__EXPORT size_t param_size(param_t param);
+__EXPORT size_t param_size(param_t param) __attribute__((const));
/**
- * Obtain the scalar value of a parameter.
+ * Copy the value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val Where to return the value, assumed to point to suitable storage for the parameter type.
- * For structures, a pointer to the structure is returned.
- * @return Zero if the parameter's value could be returned as a scalar, nonzero otherwise.
+ * For structures, a bitwise copy of the structure is performed to this address.
+ * @return Zero if the parameter's value could be returned, nonzero otherwise.
*/
__EXPORT int param_get(param_t param, void *val);
@@ -89,25 +144,25 @@ __EXPORT int param_get(param_t param, void *val);
* For structures, the pointer is assumed to point to a copy of the structure.
* @return Zero if the parameter's value could be set from a scalar, nonzero otherwise.
*/
-__EXPORT int param_set(param_t param, void *val);
+__EXPORT int param_set(param_t param, const void *val);
/**
* Export changed parameters to a file.
*
- * @param filename The name of the file to export to. If it exists, it will be overwritten.
+ * @param fd File descriptor to export to.
* @param only_unsaved Only export changed parameters that have not yet been exported.
* @return Zero on success, nonzero on failure.
*/
-__EXPORT int param_export(const char *filename, bool only_unsaved);
+__EXPORT int param_export(int fd, bool only_unsaved);
/**
* Import parameters from a file, discarding any unrecognised parameters.
*
- * @param filename The name of the file to import from.
+ * @param fd File descriptor to import from. (Currently expected to be a file.)
* @return Zero on success, nonzero if an error occurred during import.
* Note that in the failure case, parameters may be inconsistent.
*/
-__EXPORT int param_import(const char *filename);
+__EXPORT int param_import(int fd);
/**
* Apply a function to each parameter.
@@ -124,7 +179,7 @@ __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg,
/*
* Macros creating static parameter definitions.
*
- * Note that these structures are not known by name; they are
+ * Note that these structures are not known by name; they are
* collected into a section that is iterated by the parameter
* code.
*/
@@ -135,8 +190,8 @@ __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg,
__attribute__((used, section("__param"))) \
struct param_info_s __param__##_name = { \
.name = #_name, \
- .type = PARAM_TYPE_INT32, \
- .val.i = _default \
+ .type = PARAM_TYPE_INT32, \
+ .val.i = _default \
}
/** define a float parameter */
@@ -145,8 +200,8 @@ __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg,
__attribute__((used, section("__param"))) \
struct param_info_s __param__##_name = { \
.name = #_name, \
- .type = PARAM_TYPE_FLOAT, \
- .val.f = _default \
+ .type = PARAM_TYPE_FLOAT, \
+ .val.f = _default \
}
/** define a parameter that points to a structure */
@@ -155,18 +210,17 @@ __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg,
__attribute__((used, section("__param"))) \
struct param_info_s __param__##_name = { \
.name = #_name, \
- .type = PARAM_TYPE_STRUCT + sizeof(_default), \
- .val.p = &_default; \
+ .type = PARAM_TYPE_STRUCT + sizeof(_default), \
+ .val.p = &_default; \
}
/**
* Parameter value union.
*/
-union param_value_u
-{
+union param_value_u {
void *p;
int32_t i;
- float f;
+ float f;
};
/**
@@ -175,8 +229,7 @@ union param_value_u
* This is normally not used by user code; see the PARAM_DEFINE macros
* instead.
*/
-struct param_info_s
-{
+struct param_info_s {
const char *name;
param_type_t type;
union param_value_u val;