Browse Source

Merge branch 'master' of https://github.com/PX4/Firmware

Conflicts:
	apps/commander/state_machine_helper.c
	apps/multirotor_att_control/multirotor_att_control_main.c
	apps/multirotor_att_control/multirotor_rate_control.c
solved
sbg
tnaegeli 13 years ago
parent
commit
ec018e7b64
  1. 2
      ROMFS/scripts/rc.FMU_quad_x
  2. 2
      ROMFS/scripts/rc.PX4IOAR
  3. 10
      ROMFS/scripts/rc.standalone
  4. 4
      apps/drivers/bma180/bma180.cpp
  5. 4
      apps/drivers/l3gd20/l3gd20.cpp
  6. 2
      apps/gps/ubx.c
  7. 128
      apps/sensors/sensors.cpp
  8. 38
      apps/systemcmds/bl_update/bl_update.c
  9. 4
      apps/systemcmds/eeprom/eeprom.c
  10. 42
      apps/systemcmds/param/Makefile
  11. 185
      apps/systemcmds/param/param.c
  12. 4
      apps/systemlib/bson/tinybson.c
  13. 58
      apps/systemlib/param/param.c
  14. 17
      apps/systemlib/param/param.h
  15. 1
      nuttx/configs/px4fmu/nsh/appconfig
  16. 4
      nuttx/configs/px4fmu/nsh/defconfig

2
ROMFS/scripts/rc.FMU_quad_x

@ -9,7 +9,7 @@ echo "[init] eeprom" @@ -9,7 +9,7 @@ echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters ]
then
eeprom load_param /eeprom/parameters
param load
fi
echo "[init] sensors"

2
ROMFS/scripts/rc.PX4IOAR

@ -19,7 +19,7 @@ echo "[init] eeprom" @@ -19,7 +19,7 @@ echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters ]
then
eeprom load_param /eeprom/parameters
param load
fi
#

10
ROMFS/scripts/rc.standalone

@ -10,6 +10,16 @@ echo "[init] doing standalone PX4FMU startup..." @@ -10,6 +10,16 @@ echo "[init] doing standalone PX4FMU startup..."
#
uorb start
#
# Init the EEPROM
#
echo "[init] eeprom"
eeprom start
if [ -f /eeprom/parameters ]
then
param load
fi
#
# Start the sensors.
#

4
apps/drivers/bma180/bma180.cpp

@ -410,8 +410,8 @@ BMA180::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -410,8 +410,8 @@ BMA180::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
/* XXX 500Hz is just a wild guess */
return ioctl(filp, SENSORIOCSPOLLRATE, 500);
/* With internal low pass filters enabled, 250 Hz is sufficient */
return ioctl(filp, SENSORIOCSPOLLRATE, 250);
/* adjust to a legal polling interval in Hz */
default: {

4
apps/drivers/l3gd20/l3gd20.cpp

@ -420,8 +420,8 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg) @@ -420,8 +420,8 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
/* XXX 500Hz is just a wild guess */
return ioctl(filp, SENSORIOCSPOLLRATE, 500);
/* With internal low pass filters enabled, 250 Hz is sufficient */
return ioctl(filp, SENSORIOCSPOLLRATE, 250);
/* adjust to a legal polling interval in Hz */
default: {

2
apps/gps/ubx.c

@ -781,6 +781,8 @@ void *ubx_watchdog_loop(void *args) @@ -781,6 +781,8 @@ void *ubx_watchdog_loop(void *args)
} else {
/* gps healthy */
ubx_success_count++;
ubx_healthy = true;
ubx_fail_count = 0;
if (!ubx_healthy && ubx_success_count == UBX_HEALTH_SUCCESS_COUNTER_LIMIT) {
//printf("[gps] ublox UBX module status ok (baud=%d)\r\n", current_gps_speed);

128
apps/sensors/sensors.cpp

@ -101,8 +101,6 @@ extern "C" { @@ -101,8 +101,6 @@ extern "C" {
/* PPM Settings */
# define PPM_MIN 1000
# define PPM_MAX 2000
/* Internal resolution is 10000 */
# define PPM_SCALE 10000/((PPM_MAX-PPM_MIN)/2)
# define PPM_MID (PPM_MIN+PPM_MAX)/2
#endif
@ -136,10 +134,6 @@ public: @@ -136,10 +134,6 @@ public:
private:
static const unsigned _rc_max_chan_count = 8; /**< maximum number of r/c channels we handle */
/* legacy sensor descriptors */
int _fd_bma180; /**< old accel driver */
int _fd_gyro_l3gd20; /**< old gyro driver */
#if CONFIG_HRT_PPM
hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */
@ -334,8 +328,6 @@ Sensors *g_sensors; @@ -334,8 +328,6 @@ Sensors *g_sensors;
}
Sensors::Sensors() :
_fd_bma180(-1),
_fd_gyro_l3gd20(-1),
_ppm_last_valid(0),
_fd_adc(-1),
@ -562,19 +554,7 @@ Sensors::accel_init() @@ -562,19 +554,7 @@ Sensors::accel_init()
fd = open(ACCEL_DEVICE_PATH, 0);
if (fd < 0) {
warn("%s", ACCEL_DEVICE_PATH);
/* fall back to bma180 here (new driver would be better...) */
_fd_bma180 = open("/dev/bma180", O_RDONLY);
if (_fd_bma180 < 0) {
warn("/dev/bma180");
warn("FATAL: no accelerometer found");
}
/* discard first (junk) reading */
int16_t junk_buf[3];
read(_fd_bma180, junk_buf, sizeof(junk_buf));
warnx("using BMA180");
errx(1, "FATAL: no accelerometer found");
} else {
/* set the accel internal sampling rate up to at leat 500Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 500);
@ -595,19 +575,7 @@ Sensors::gyro_init() @@ -595,19 +575,7 @@ Sensors::gyro_init()
fd = open(GYRO_DEVICE_PATH, 0);
if (fd < 0) {
warn("%s", GYRO_DEVICE_PATH);
/* fall back to bma180 here (new driver would be better...) */
_fd_gyro_l3gd20 = open("/dev/l3gd20", O_RDONLY);
if (_fd_gyro_l3gd20 < 0) {
warn("/dev/l3gd20");
warn("FATAL: no gyro found");
}
/* discard first (junk) reading */
int16_t junk_buf[3];
read(_fd_gyro_l3gd20, junk_buf, sizeof(junk_buf));
warn("using L3GD20");
errx(1, "FATAL: no gyro found");
} else {
/* set the gyro internal sampling rate up to at leat 500Hz */
ioctl(fd, GYROIOCSSAMPLERATE, 500);
@ -648,7 +616,7 @@ Sensors::baro_init() @@ -648,7 +616,7 @@ Sensors::baro_init()
fd = open(BARO_DEVICE_PATH, 0);
if (fd < 0) {
warn("%s", BARO_DEVICE_PATH);
errx(1, "FATAL: no barometer found");
warnx("No barometer found, ignoring");
}
/* set the driver to poll at 150Hz */
@ -671,67 +639,36 @@ Sensors::adc_init() @@ -671,67 +639,36 @@ Sensors::adc_init()
void
Sensors::accel_poll(struct sensor_combined_s &raw)
{
struct accel_report accel_report;
bool accel_updated;
orb_check(_accel_sub, &accel_updated);
if (_fd_bma180 >= 0) {
/* do ORB emulation for BMA180 */
int16_t buf[3];
if (accel_updated) {
struct accel_report accel_report;
read(_fd_bma180, buf, sizeof(buf));
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
accel_report.timestamp = hrt_absolute_time();
raw.accelerometer_m_s2[0] = accel_report.x;
raw.accelerometer_m_s2[1] = accel_report.y;
raw.accelerometer_m_s2[2] = accel_report.z;
accel_report.x_raw = (buf[1] == -32768) ? 32767 : -buf[1];
accel_report.y_raw = buf[0];
accel_report.z_raw = buf[2];
raw.accelerometer_raw[0] = accel_report.x_raw;
raw.accelerometer_raw[1] = accel_report.y_raw;
raw.accelerometer_raw[2] = accel_report.z_raw;
const float range_g = 4.0f;
/* scale from 14 bit to m/s2 */
accel_report.x = (((accel_report.x_raw - _parameters.accel_offset[0]) * range_g) / 8192.0f) / 9.81f;
accel_report.y = (((accel_report.y_raw - _parameters.accel_offset[0]) * range_g) / 8192.0f) / 9.81f;
accel_report.z = (((accel_report.z_raw - _parameters.accel_offset[0]) * range_g) / 8192.0f) / 9.81f;
raw.accelerometer_counter++;
} else {
bool accel_updated;
orb_check(_accel_sub, &accel_updated);
if (accel_updated) {
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
raw.accelerometer_counter++;
}
}
raw.accelerometer_m_s2[0] = accel_report.x;
raw.accelerometer_m_s2[1] = accel_report.y;
raw.accelerometer_m_s2[2] = accel_report.z;
raw.accelerometer_raw[0] = accel_report.x_raw;
raw.accelerometer_raw[1] = accel_report.y_raw;
raw.accelerometer_raw[2] = accel_report.z_raw;
}
void
Sensors::gyro_poll(struct sensor_combined_s &raw)
{
struct gyro_report gyro_report;
bool gyro_updated;
orb_check(_gyro_sub, &gyro_updated);
if (_fd_gyro_l3gd20 >= 0) {
/* do ORB emulation for L3GD20 */
int16_t buf[3];
if (gyro_updated) {
struct gyro_report gyro_report;
read(_fd_gyro_l3gd20, buf, sizeof(buf));
gyro_report.timestamp = hrt_absolute_time();
gyro_report.x_raw = buf[1];
gyro_report.y_raw = ((buf[0] == -32768) ? 32767 : -buf[0]);
gyro_report.z_raw = buf[2];
/* scaling calculated as: raw * (1/(32768*(500/180*PI))) */
gyro_report.x = (gyro_report.x_raw - _parameters.gyro_offset[0]) * 0.000266316109f;
gyro_report.y = (gyro_report.y_raw - _parameters.gyro_offset[1]) * 0.000266316109f;
gyro_report.z = (gyro_report.z_raw - _parameters.gyro_offset[2]) * 0.000266316109f;
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
raw.gyro_rad_s[0] = gyro_report.x;
raw.gyro_rad_s[1] = gyro_report.y;
@ -742,25 +679,6 @@ Sensors::gyro_poll(struct sensor_combined_s &raw) @@ -742,25 +679,6 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro_raw[2] = gyro_report.z_raw;
raw.gyro_counter++;
} else {
bool gyro_updated;
orb_check(_gyro_sub, &gyro_updated);
if (gyro_updated) {
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
raw.gyro_rad_s[0] = gyro_report.x;
raw.gyro_rad_s[1] = gyro_report.y;
raw.gyro_rad_s[2] = gyro_report.z;
raw.gyro_raw[0] = gyro_report.x_raw;
raw.gyro_raw[1] = gyro_report.y_raw;
raw.gyro_raw[2] = gyro_report.z_raw;
raw.gyro_counter++;
}
}
}
@ -974,7 +892,13 @@ Sensors::ppm_poll() @@ -974,7 +892,13 @@ Sensors::ppm_poll()
}
/* reverse channel if required */
_rc.chan[i].scaled *= _parameters.rev[i];
if (i == _rc.function[THROTTLE]) {
if ((int)_parameters.rev[i] == -1) {
_rc.chan[i].scaled = 1.0f + -1.0f * _rc.chan[i].scaled;
}
} else {
_rc.chan[i].scaled *= _parameters.rev[i];
}
/* handle any parameter-induced blowups */
if (isnan(_rc.chan[i].scaled) || isinf(_rc.chan[i].scaled))

38
apps/systemcmds/bl_update/bl_update.c

@ -51,16 +51,20 @@ @@ -51,16 +51,20 @@
#include <arch/board/board.h>
#include "systemlib/systemlib.h"
#include "systemlib/param/param.h"
#include "systemlib/err.h"
__EXPORT int bl_update_main(int argc, char *argv[]);
static void setopt(void);
int
bl_update_main(int argc, char *argv[])
{
if (argc != 2)
errx(1, "missing firmware filename");
errx(1, "missing firmware filename or command");
if (!strcmp(argv[1], "setopt"))
setopt();
int fd = open(argv[1], O_RDONLY);
if (fd < 0)
@ -172,3 +176,33 @@ flash_end: @@ -172,3 +176,33 @@ flash_end:
free(buf);
exit(0);
}
static void
setopt(void)
{
volatile uint32_t *optcr = (volatile uint32_t *)0x40023c14;
const uint16_t opt_mask = (3 << 2); /* BOR_LEV bitmask */
const uint16_t opt_bits = (0 << 2); /* BOR = 0, setting for 2.7-3.6V operation */
if ((*optcr & opt_mask) == opt_bits)
errx(0, "option bits are already set as required");
/* unlock the control register */
volatile uint32_t *optkeyr = (volatile uint32_t *)0x40023c08;
*optkeyr = 0x08192a3bU;
*optkeyr = 0x4c5d6e7fU;
if (*optcr & 1)
errx(1, "option control register unlock failed");
/* program the new option value */
*optcr = (*optcr & ~opt_mask) | opt_bits | (1 << 1);
usleep(1000);
if ((*optcr & opt_mask) == opt_bits)
errx(0, "option bits set");
errx(1, "option bits setting failed; readback 0x%04x", *optcr);
}

4
apps/systemcmds/eeprom/eeprom.c

@ -193,6 +193,8 @@ eeprom_save(const char *name) @@ -193,6 +193,8 @@ eeprom_save(const char *name)
if (!name)
err(1, "missing argument for device name, try '/eeprom/parameters'");
warnx("WARNING: 'eeprom save_param' deprecated - use 'param save' instead");
/* delete the file in case it exists */
unlink(name);
@ -222,6 +224,8 @@ eeprom_load(const char *name) @@ -222,6 +224,8 @@ eeprom_load(const char *name)
if (!name)
err(1, "missing argument for device name, try '/eeprom/parameters'");
warnx("WARNING: 'eeprom load_param' deprecated - use 'param load' instead");
int fd = open(name, O_RDONLY);
if (fd < 0)

42
apps/systemcmds/param/Makefile

@ -0,0 +1,42 @@ @@ -0,0 +1,42 @@
############################################################################
#
# 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.
#
############################################################################
#
# Build the parameters tool.
#
APPNAME = param
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk

185
apps/systemcmds/param/param.c

@ -0,0 +1,185 @@ @@ -0,0 +1,185 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* 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
*
* Parameter tool.
*/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <stdbool.h>
#include <unistd.h>
#include <fcntl.h>
#include <sys/stat.h>
#include <arch/board/board.h>
#include "systemlib/systemlib.h"
#include "systemlib/param/param.h"
#include "systemlib/err.h"
__EXPORT int param_main(int argc, char *argv[]);
static void do_save(void);
static void do_load(void);
static void do_import(void);
static void do_show(void);
static void do_show_print(void *arg, param_t param);
static const char *param_file_name = "/eeprom/parameters";
int
param_main(int argc, char *argv[])
{
if (argc >= 2) {
if (!strcmp(argv[1], "save"))
do_save();
if (!strcmp(argv[1], "load"))
do_load();
if (!strcmp(argv[1], "import"))
do_import();
if (!strcmp(argv[1], "show"))
do_show();
}
errx(1, "expected a command, try 'load', 'import', 'show' or 'save'\n");
}
static void
do_save(void)
{
/* delete the parameter file in case it exists */
unlink(param_file_name);
/* create the file */
int fd = open(param_file_name, O_WRONLY | O_CREAT | O_EXCL);
if (fd < 0)
err(1, "opening '%s' failed", param_file_name);
int result = param_export(fd, false);
close(fd);
if (result < 0) {
unlink(param_file_name);
errx(1, "error exporting to '%s'", param_file_name);
}
exit(0);
}
static void
do_load(void)
{
int fd = open(param_file_name, O_RDONLY);
if (fd < 0)
err(1, "open '%s'", param_file_name);
int result = param_load(fd);
close(fd);
if (result < 0)
errx(1, "error importing from '%s'", param_file_name);
exit(0);
}
static void
do_import(void)
{
int fd = open(param_file_name, O_RDONLY);
if (fd < 0)
err(1, "open '%s'", param_file_name);
int result = param_import(fd);
close(fd);
if (result < 0)
errx(1, "error importing from '%s'", param_file_name);
exit(0);
}
static void
do_show(void)
{
printf(" + = saved, * = unsaved (warning, floating-point values are often printed with the decimal point wrong)\n");
param_foreach(do_show_print, NULL, false);
exit(0);
}
static void
do_show_print(void *arg, param_t param)
{
int32_t i;
float f;
printf("%c %s: ",
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
param_name(param));
/*
* This case can be expanded to handle printing common structure types.
*/
switch (param_type(param)) {
case PARAM_TYPE_INT32:
if (!param_get(param, &i)) {
printf("%d\n", i);
return;
}
break;
case PARAM_TYPE_FLOAT:
if (!param_get(param, &f)) {
printf("%4.4f\n", (double)f);
return;
}
break;
case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX:
printf("<struct type %d size %u>\n", 0 + param_type(param), param_size(param));
return;
default:
printf("<unknown type %d>\n", 0 + param_type(param));
return;
}
printf("<error fetching parameter %d>\n", param);
}

4
apps/systemlib/bson/tinybson.c

@ -106,7 +106,9 @@ bson_decoder_next(bson_decoder_t decoder) @@ -106,7 +106,9 @@ bson_decoder_next(bson_decoder_t decoder)
/* if the nesting level is now zero, the top-level document is done */
if (decoder->nesting == 0) {
CODER_KILL(decoder, "nesting is zero, document is done");
/* like kill but not an error */
debug("nesting is zero, document is done");
decoder->fd = -1;
/* return end-of-file to the caller */
return 0;

58
apps/systemlib/param/param.c

@ -242,6 +242,25 @@ param_name(param_t param) @@ -242,6 +242,25 @@ param_name(param_t param)
return NULL;
}
bool
param_value_is_default(param_t param)
{
return param_find_changed(param) ? false : true;
}
bool
param_value_unsaved(param_t param)
{
static struct param_wbuf_s *s;
s = param_find_changed(param);
if (s && s->unsaved)
return true;
return false;
}
enum param_type_e
param_type(param_t param)
{
@ -330,8 +349,8 @@ param_get(param_t param, void *val) @@ -330,8 +349,8 @@ param_get(param_t param, void *val)
return result;
}
int
param_set(param_t param, const void *val)
static int
param_set_internal(param_t param, const void *val, bool mark_saved)
{
int result = -1;
bool params_changed = false;
@ -394,7 +413,7 @@ param_set(param_t param, const void *val) @@ -394,7 +413,7 @@ param_set(param_t param, const void *val)
goto out;
}
s->unsaved = true;
s->unsaved = !mark_saved;
params_changed = true;
result = 0;
}
@ -412,6 +431,12 @@ out: @@ -412,6 +431,12 @@ out:
return result;
}
int
param_set(param_t param, const void *val)
{
return param_set_internal(param, val, false);
}
void
param_reset(param_t param)
{
@ -535,6 +560,11 @@ out: @@ -535,6 +560,11 @@ out:
return result;
}
struct param_import_state
{
bool mark_saved;
};
static int
param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
{
@ -542,13 +572,13 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node) @@ -542,13 +572,13 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
int32_t i;
void *v, *tmp = NULL;
int result = -1;
struct param_import_state *state = (struct param_import_state *)private;
/*
* EOO means the end of the parameter object. (Currently not supporting
* nested BSON objects).
*/
if (node->type == BSON_EOO) {
*(bool *)private = true;
debug("end of parameters");
return 0;
}
@ -621,7 +651,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node) @@ -621,7 +651,7 @@ param_import_callback(bson_decoder_t decoder, void *private, bson_node_t node)
goto out;
}
if (param_set(param, v)) {
if (param_set_internal(param, v, state->mark_saved)) {
debug("error setting value for '%s'", node->name);
goto out;
}
@ -642,19 +672,19 @@ out: @@ -642,19 +672,19 @@ out:
return result;
}
int
param_import(int fd)
static int
param_import_internal(int fd, bool mark_saved)
{
bool done;
struct bson_decoder_s decoder;
int result = -1;
struct param_import_state state;
if (bson_decoder_init(&decoder, fd, param_import_callback, &done)) {
if (bson_decoder_init(&decoder, fd, param_import_callback, &state)) {
debug("decoder init failed");
goto out;
}
done = false;
state.mark_saved = mark_saved;
do {
result = bson_decoder_next(&decoder);
@ -668,11 +698,17 @@ out: @@ -668,11 +698,17 @@ out:
return result;
}
int
param_import(int fd)
{
return param_import_internal(fd, false);
}
int
param_load(int fd)
{
param_reset_all();
return param_import(fd);
return param_import_internal(fd, true);
}
void

17
apps/systemlib/param/param.h

@ -121,6 +121,20 @@ __EXPORT int param_get_index(param_t param); @@ -121,6 +121,20 @@ __EXPORT int param_get_index(param_t param);
*/
__EXPORT const char *param_name(param_t param);
/**
* Test whether a parameter's value has changed from the default.
*
* @return If true, the parameter's value has not been changed from the default.
*/
__EXPORT bool param_value_is_default(param_t param);
/**
* Test whether a parameter's value has been changed but not saved.
*
* @return If true, the parameter's value has not been saved.
*/
__EXPORT bool param_value_unsaved(param_t param);
/**
* Obtain the type of a parameter.
*
@ -160,7 +174,8 @@ __EXPORT int param_set(param_t param, const void *val); @@ -160,7 +174,8 @@ __EXPORT int param_set(param_t param, const void *val);
/**
* Reset a parameter to its default value.
*
* This function frees any storage used by struct parameters, but scalar parameters
* This function frees any storage used by struct parameters, and returns the parameter
* to its default value.
*
* @param param A handle returned by param_find or passed by param_foreach.
*/

1
nuttx/configs/px4fmu/nsh/appconfig

@ -53,6 +53,7 @@ CONFIGURED_APPS += systemcmds/boardinfo @@ -53,6 +53,7 @@ CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += systemcmds/led
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/bl_update
#CONFIGURED_APPS += systemcmds/calibration

4
nuttx/configs/px4fmu/nsh/defconfig

@ -236,11 +236,11 @@ CONFIG_AT24XX_MTD_BLOCKSIZE=256 @@ -236,11 +236,11 @@ CONFIG_AT24XX_MTD_BLOCKSIZE=256
CONFIG_SERIAL_TERMIOS=y
CONFIG_SERIAL_CONSOLE_REINIT=y
CONFIG_USART1_SERIAL_CONSOLE=n
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
CONFIG_UART4_SERIAL_CONSOLE=n
CONFIG_UART5_SERIAL_CONSOLE=y
CONFIG_UART5_SERIAL_CONSOLE=n
CONFIG_USART6_SERIAL_CONSOLE=n
#Mavlink messages can be bigger than 128

Loading…
Cancel
Save