From 34a3b260f34398994a315388b3ffed22a1fe22fb Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 31 Oct 2012 00:37:15 -0700 Subject: Move the last of the board-specific code for PX4FMU out of the NuttX tree. Now it's just configuration. --- apps/systemcmds/led/Makefile | 42 --------- apps/systemcmds/led/led.c | 209 ------------------------------------------- 2 files changed, 251 deletions(-) delete mode 100644 apps/systemcmds/led/Makefile delete mode 100644 apps/systemcmds/led/led.c (limited to 'apps/systemcmds') diff --git a/apps/systemcmds/led/Makefile b/apps/systemcmds/led/Makefile deleted file mode 100644 index eb9d8f909..000000000 --- a/apps/systemcmds/led/Makefile +++ /dev/null @@ -1,42 +0,0 @@ -############################################################################ -# -# 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. -# -############################################################################ - -# -# Makefile to build ardrone interface -# - -APPNAME = led -PRIORITY = SCHED_PRIORITY_MAX - 15 -STACKSIZE = 2048 - -include $(APPDIR)/mk/app.mk diff --git a/apps/systemcmds/led/led.c b/apps/systemcmds/led/led.c deleted file mode 100644 index 15d448118..000000000 --- a/apps/systemcmds/led/led.c +++ /dev/null @@ -1,209 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Lorenz Meier - * - * 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 led.c - * Plain, stupid led outputs - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -__EXPORT int led_main(int argc, char *argv[]); - - -static bool thread_should_exit = false; /**< Deamon exit flag */ -static bool thread_running = false; /**< Deamon status flag */ -static int led_task; /**< Handle of deamon task / thread */ -static int leds; - -static int led_init(void) -{ - leds = open("/dev/led", O_RDONLY | O_NONBLOCK); - - if (leds < 0) { - errx(1, "[led] LED: open fail\n"); - } - - if (ioctl(leds, LED_ON, LED_BLUE) || ioctl(leds, LED_ON, LED_AMBER)) { - errx(1, "[led] LED: ioctl fail\n"); - } - - return 0; -} - -static void led_deinit(void) -{ - close(leds); -} - -static int led_toggle(int led) -{ - static int last_blue = LED_ON; - static int last_amber = LED_ON; - - if (led == LED_BLUE) last_blue = (last_blue == LED_ON) ? LED_OFF : LED_ON; - - if (led == LED_AMBER) last_amber = (last_amber == LED_ON) ? LED_OFF : LED_ON; - - return ioctl(leds, ((led == LED_BLUE) ? last_blue : last_amber), led); -} - -static int led_on(int led) -{ - return ioctl(leds, LED_ON, led); -} - -static int led_off(int led) -{ - return ioctl(leds, LED_OFF, led); -} - -/** - * Mainloop of led. - */ -int led_thread_main(int argc, char *argv[]); - -/** - * Print the correct usage. - */ -static void usage(const char *reason); - -static void -usage(const char *reason) -{ - if (reason) - fprintf(stderr, "%s\n", reason); - - fprintf(stderr, "usage: led {start|stop|status} [-d ]\n\n"); - exit(1); -} - -/** - * The deamon app only briefly exists to start - * the background job. The stack size assigned in the - * Makefile does only apply to this management task. - * - * The actual stack size should be set in the call - * to task_create(). - */ -int led_main(int argc, char *argv[]) -{ - if (argc < 1) - usage("missing command"); - - if (!strcmp(argv[1], "start")) { - - if (thread_running) { - printf("led already running\n"); - /* this is not an error */ - exit(0); - } - - thread_should_exit = false; - led_task = task_spawn("led", - SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 15, - 4096, - led_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); - thread_running = true; - exit(0); - } - - if (!strcmp(argv[1], "stop")) { - thread_should_exit = true; - exit(0); - } - - if (!strcmp(argv[1], "status")) { - if (thread_running) { - printf("\tled is running\n"); - - } else { - printf("\tled not started\n"); - } - - exit(0); - } - - usage("unrecognized command"); - exit(1); -} - -int led_thread_main(int argc, char *argv[]) -{ - /* welcome user */ - printf("[led] Control started, taking over motors\n"); - - /* open leds */ - led_init(); - - unsigned int rate = 200; - - while (!thread_should_exit) { - /* swell blue led */ - - - /* 200 Hz base loop */ - usleep(1000000 / rate); - } - - /* close leds */ - led_deinit(); - - printf("[led] ending now...\n\n"); - fflush(stdout); - - thread_running = false; - - return OK; -} - -- cgit v1.2.3 From 0ddfd7c75c1f692fe83fcc88f832b42e2b04f0af Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 31 Oct 2012 16:31:21 +0100 Subject: New param interface for microSD and EEPROM --- apps/commander/commander.c | 39 +++----------------- apps/mavlink/mavlink_parameters.c | 62 +------------------------------ apps/systemcmds/param/param.c | 51 +++++++++++++++++-------- apps/systemlib/param/param.c | 78 +++++++++++++++++++++++++++++++++++++++ apps/systemlib/param/param.h | 19 ++++++++++ 5 files changed, 141 insertions(+), 108 deletions(-) (limited to 'apps/systemcmds') diff --git a/apps/commander/commander.c b/apps/commander/commander.c index e00dc13d2..f2d92dc11 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -268,33 +268,6 @@ void tune_confirm() { ioctl(buzzer, TONE_SET_ALARM, 3); } -static const char *parameter_file = "/eeprom/parameters"; - -static int pm_save_eeprom(bool only_unsaved) -{ - /* delete the file in case it exists */ - unlink(parameter_file); - - /* create the file */ - int fd = open(parameter_file, O_WRONLY | O_CREAT | O_EXCL); - - if (fd < 0) { - warn("opening '%s' for writing failed", parameter_file); - return -1; - } - - int result = param_export(fd, only_unsaved); - close(fd); - - if (result != 0) { - unlink(parameter_file); - warn("error exporting parameters to '%s'", parameter_file); - return -2; - } - - return 0; -} - void do_mag_calibration(int status_pub, struct vehicle_status_s *status) { /* set to mag calibration mode */ @@ -496,9 +469,9 @@ void do_mag_calibration(int status_pub, struct vehicle_status_s *status) } /* auto-save to EEPROM */ - int save_ret = pm_save_eeprom(false); + int save_ret = param_save_default(); if(save_ret != 0) { - warn("WARNING: auto-save of params to EEPROM failed"); + warn("WARNING: auto-save of params to storage failed"); } printf("[mag cal]\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n", @@ -616,9 +589,9 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) close(fd); /* auto-save to EEPROM */ - int save_ret = pm_save_eeprom(false); + int save_ret = param_save_default(); if(save_ret != 0) { - warn("WARNING: auto-save of params to EEPROM failed"); + warn("WARNING: auto-save of params to storage failed"); } // char buf[50]; @@ -736,9 +709,9 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status) close(fd); /* auto-save to EEPROM */ - int save_ret = pm_save_eeprom(false); + int save_ret = param_save_default(); if(save_ret != 0) { - warn("WARNING: auto-save of params to EEPROM failed"); + warn("WARNING: auto-save of params to storage failed"); } //char buf[50]; diff --git a/apps/mavlink/mavlink_parameters.c b/apps/mavlink/mavlink_parameters.c index f41889535..6d434ed3d 100644 --- a/apps/mavlink/mavlink_parameters.c +++ b/apps/mavlink/mavlink_parameters.c @@ -172,64 +172,6 @@ int mavlink_pm_send_param(param_t param) return ret; } -static const char *mavlink_parameter_file = "/eeprom/parameters"; - -/** - * @return 0 on success, -1 if device open failed, -2 if writing parameters failed - */ -static int mavlink_pm_save_eeprom() -{ - /* delete the file in case it exists */ - unlink(mavlink_parameter_file); - - /* create the file */ - int fd = open(mavlink_parameter_file, O_WRONLY | O_CREAT | O_EXCL); - - if (fd < 0) { - warn("opening '%s' for writing failed", mavlink_parameter_file); - return -1; - } - - int result = param_export(fd, false); - close(fd); - - if (result != 0) { - unlink(mavlink_parameter_file); - warn("error exporting parameters to '%s'", mavlink_parameter_file); - return -2; - } - - return 0; -} - -/** - * @return 0 on success, 1 if all params have not yet been stored, -1 if device open failed, -2 if writing parameters failed - */ -static int -mavlink_pm_load_eeprom() -{ - int fd = open(mavlink_parameter_file, O_RDONLY); - - if (fd < 0) { - /* no parameter file is OK, otherwise this is an error */ - if (errno != ENOENT) { - warn("open '%s' for reading failed", mavlink_parameter_file); - return -1; - } - return 1; - } - - int result = param_load(fd); - close(fd); - - if (result != 0) { - warn("error reading parameters from '%s'", mavlink_parameter_file); - return -2; - } - - return 0; -} - void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg) { switch (msg->msgid) { @@ -307,7 +249,7 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess if (((int)(cmd_mavlink.param1)) == 0) { /* read all parameters from EEPROM to RAM */ - int read_ret = mavlink_pm_load_eeprom(); + int read_ret = param_load_default(); if (read_ret == OK) { //printf("[mavlink pm] Loaded EEPROM params in RAM\n"); mavlink_missionlib_send_gcs_string("[mavlink pm] OK loaded EEPROM params"); @@ -327,7 +269,7 @@ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_mess } else if (((int)(cmd_mavlink.param1)) == 1) { /* write all parameters from RAM to EEPROM */ - int write_ret = mavlink_pm_save_eeprom(); + int write_ret = param_save_default(); if (write_ret == OK) { mavlink_missionlib_send_gcs_string("[mavlink pm] OK params written to EEPROM"); result = MAV_RESULT_ACCEPTED; diff --git a/apps/systemcmds/param/param.c b/apps/systemcmds/param/param.c index 68dbd822e..77f47b95d 100644 --- a/apps/systemcmds/param/param.c +++ b/apps/systemcmds/param/param.c @@ -56,36 +56,53 @@ __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_save(const char* param_file_name); +static void do_load(const char* param_file_name); +static void do_import(const char* param_file_name); static void do_show(void); static void do_show_print(void *arg, param_t param); -static const char *param_file_name = "/eeprom/parameters"; +static const char *param_file_name_default = "/fs/microsd/parameters"; int param_main(int argc, char *argv[]) { if (argc >= 2) { - if (!strcmp(argv[1], "save")) - do_save(); + if (!strcmp(argv[1], "save")) { + if (argc >= 3) { + do_save(argv[2]); + } else { + do_save(param_file_name_default); + } + } - if (!strcmp(argv[1], "load")) - do_load(); + if (!strcmp(argv[1], "load")) { + if (argc >= 3) { + do_load(argv[2]); + } else { + do_load(param_file_name_default); + } + } - if (!strcmp(argv[1], "import")) - do_import(); + if (!strcmp(argv[1], "import")) { + if (argc >= 3) { + do_import(argv[2]); + } else { + do_import(param_file_name_default); + } + } - if (!strcmp(argv[1], "show")) + if (!strcmp(argv[1], "show")) { do_show(); + } + } errx(1, "expected a command, try 'load', 'import', 'show' or 'save'\n"); } static void -do_save(void) +do_save(const char* param_file_name) { /* delete the parameter file in case it exists */ unlink(param_file_name); @@ -108,7 +125,7 @@ do_save(void) } static void -do_load(void) +do_load(const char* param_file_name) { int fd = open(param_file_name, O_RDONLY); @@ -118,14 +135,18 @@ do_load(void) int result = param_load(fd); close(fd); - if (result < 0) + if (result < 0) { errx(1, "error importing from '%s'", param_file_name); + } else { + /* set default file name for next storage operation */ + param_set_default_file(param_file_name); + } exit(0); } static void -do_import(void) +do_import(const char* param_file_name) { int fd = open(param_file_name, O_RDONLY); diff --git a/apps/systemlib/param/param.c b/apps/systemlib/param/param.c index 365bd3d19..c63e7ca8d 100644 --- a/apps/systemlib/param/param.c +++ b/apps/systemlib/param/param.c @@ -47,6 +47,7 @@ #include #include #include +#include #include @@ -480,6 +481,83 @@ param_reset_all(void) param_notify_changes(); } +static char param_default_file_name[50] = "/eeprom/parameters"; + +int +param_set_default_file(const char* filename) +{ + if (filename) { + if (strlen(filename) < sizeof(param_default_file_name)) + { + strcpy(param_default_file_name, filename); + } else { + warnx("param file name too long"); + return 1; + } + return 0; + } else { + warnx("no valid param file name"); + return 1; + } + return 0; +} + +int +param_save_default(void) +{ + /* delete the file in case it exists */ + unlink(param_default_file_name); + + /* create the file */ + int fd = open(param_default_file_name, O_WRONLY | O_CREAT | O_EXCL); + + if (fd < 0) { + warn("opening '%s' for writing failed", param_default_file_name); + return -1; + } + + int result = param_export(fd, false); + /* should not be necessary, over-careful here */ + fsync(fd); + close(fd); + + if (result != 0) { + unlink(param_default_file_name); + warn("error exporting parameters to '%s'", param_default_file_name); + return -2; + } + + return 0; +} + +/** + * @return 0 on success, 1 if all params have not yet been stored, -1 if device open failed, -2 if writing parameters failed + */ +int +param_load_default(void) +{ + int fd = open(param_default_file_name, O_RDONLY); + + if (fd < 0) { + /* no parameter file is OK, otherwise this is an error */ + if (errno != ENOENT) { + warn("open '%s' for reading failed", param_default_file_name); + return -1; + } + return 1; + } + + int result = param_load(fd); + close(fd); + + if (result != 0) { + warn("error reading parameters from '%s'", param_default_file_name); + return -2; + } + + return 0; +} + int param_export(int fd, bool only_unsaved) { diff --git a/apps/systemlib/param/param.h b/apps/systemlib/param/param.h index 41e268db0..64bb77834 100644 --- a/apps/systemlib/param/param.h +++ b/apps/systemlib/param/param.h @@ -234,6 +234,25 @@ __EXPORT int param_load(int fd); */ __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg, bool only_changed); +/** + * Export parameters to the default file name. + * + * + * @param + */ +__EXPORT int param_save_default(void); + +/** + * Set the default parameter file name. + */ +__EXPORT int param_set_default_file(const char* filename); + +/** + * Import parameters from the default file name. + */ +__EXPORT int param_load_default(void); + + /* * Macros creating static parameter definitions. * -- cgit v1.2.3 From 3c987d63680d153e4d954ad6249d24e5448e2204 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 31 Oct 2012 18:50:00 +0100 Subject: Casting and fix default param path --- apps/mavlink/mavlink_receiver.c | 9 ++++----- apps/systemcmds/param/param.c | 2 +- 2 files changed, 5 insertions(+), 6 deletions(-) (limited to 'apps/systemcmds') diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index cfff0f469..826eb5625 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -253,14 +253,13 @@ handle_message(mavlink_message_t *msg) break; } - offboard_control_sp.p1 = quad_motors_setpoint.roll[mavlink_system.sysid] / (float)INT16_MAX; - offboard_control_sp.p2 = quad_motors_setpoint.pitch[mavlink_system.sysid] / (float)INT16_MAX; - offboard_control_sp.p3= quad_motors_setpoint.yaw[mavlink_system.sysid] / (float)INT16_MAX; + offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid] / (float)INT16_MAX; + offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid] / (float)INT16_MAX; + offboard_control_sp.p3= (float)quad_motors_setpoint.yaw[mavlink_system.sysid] / (float)INT16_MAX; offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid]/(float)UINT16_MAX; - if (quad_motors_setpoint.thrust[mavlink_system.sysid] ==0){ + if (quad_motors_setpoint.thrust[mavlink_system.sysid] == 0) { ml_armed = false; - } offboard_control_sp.armed = ml_armed; diff --git a/apps/systemcmds/param/param.c b/apps/systemcmds/param/param.c index 77f47b95d..9cb280933 100644 --- a/apps/systemcmds/param/param.c +++ b/apps/systemcmds/param/param.c @@ -62,7 +62,7 @@ static void do_import(const char* param_file_name); static void do_show(void); static void do_show_print(void *arg, param_t param); -static const char *param_file_name_default = "/fs/microsd/parameters"; +static const char *param_file_name_default = "/eeprom/parameters"; int param_main(int argc, char *argv[]) -- cgit v1.2.3 From 8bfceef89cc1fd2422863a99d99039d18a1301bc Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 31 Oct 2012 12:59:24 -0700 Subject: Remove the arbitrary limit on the path to the default parameter file. Add a verb to the param command to set the default parameter file. --- apps/systemcmds/param/param.c | 21 ++++++++++++++------- apps/systemlib/param/param.c | 42 +++++++++++++++++++++--------------------- apps/systemlib/param/param.h | 29 ++++++++++++++++++++++------- 3 files changed, 57 insertions(+), 35 deletions(-) (limited to 'apps/systemcmds') diff --git a/apps/systemcmds/param/param.c b/apps/systemcmds/param/param.c index 9cb280933..92313e45a 100644 --- a/apps/systemcmds/param/param.c +++ b/apps/systemcmds/param/param.c @@ -62,8 +62,6 @@ static void do_import(const char* param_file_name); static void do_show(void); static void do_show_print(void *arg, param_t param); -static const char *param_file_name_default = "/eeprom/parameters"; - int param_main(int argc, char *argv[]) { @@ -72,7 +70,7 @@ param_main(int argc, char *argv[]) if (argc >= 3) { do_save(argv[2]); } else { - do_save(param_file_name_default); + do_save(param_get_default_file()); } } @@ -80,7 +78,7 @@ param_main(int argc, char *argv[]) if (argc >= 3) { do_load(argv[2]); } else { - do_load(param_file_name_default); + do_load(param_get_default_file()); } } @@ -88,17 +86,26 @@ param_main(int argc, char *argv[]) if (argc >= 3) { do_import(argv[2]); } else { - do_import(param_file_name_default); + do_import(param_get_default_file()); } } + if (!strcmp(argv[1], "select")) { + if (argc >= 3) { + param_set_default_file(argv[2]); + } else { + param_set_default_file(NULL); + } + warnx("selected parameter file %s", param_get_default_file()); + } + if (!strcmp(argv[1], "show")) { do_show(); } } - - errx(1, "expected a command, try 'load', 'import', 'show' or 'save'\n"); + + errx(1, "expected a command, try 'load', 'import', 'show', 'select' or 'save'"); } static void diff --git a/apps/systemlib/param/param.c b/apps/systemlib/param/param.c index c63e7ca8d..9a00c91a5 100644 --- a/apps/systemlib/param/param.c +++ b/apps/systemlib/param/param.c @@ -481,38 +481,38 @@ param_reset_all(void) param_notify_changes(); } -static char param_default_file_name[50] = "/eeprom/parameters"; +static const char *param_default_file = "/eeprom/parameters"; +static char *param_user_file; int param_set_default_file(const char* filename) { - if (filename) { - if (strlen(filename) < sizeof(param_default_file_name)) - { - strcpy(param_default_file_name, filename); - } else { - warnx("param file name too long"); - return 1; - } - return 0; - } else { - warnx("no valid param file name"); - return 1; + if (param_user_file != NULL) { + free(param_user_file); + param_user_file = NULL; } + if (filename) + param_user_file = strdup(filename); return 0; } +const char * +param_get_default_file(void) +{ + return (param_user_file != NULL) ? param_user_file : param_default_file; +} + int param_save_default(void) { /* delete the file in case it exists */ - unlink(param_default_file_name); + unlink(param_get_default_file()); /* create the file */ - int fd = open(param_default_file_name, O_WRONLY | O_CREAT | O_EXCL); + int fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL); if (fd < 0) { - warn("opening '%s' for writing failed", param_default_file_name); + warn("opening '%s' for writing failed", param_get_default_file()); return -1; } @@ -522,8 +522,8 @@ param_save_default(void) close(fd); if (result != 0) { - unlink(param_default_file_name); - warn("error exporting parameters to '%s'", param_default_file_name); + unlink(param_get_default_file()); + warn("error exporting parameters to '%s'", param_get_default_file()); return -2; } @@ -536,12 +536,12 @@ param_save_default(void) int param_load_default(void) { - int fd = open(param_default_file_name, O_RDONLY); + int fd = open(param_get_default_file(), O_RDONLY); if (fd < 0) { /* no parameter file is OK, otherwise this is an error */ if (errno != ENOENT) { - warn("open '%s' for reading failed", param_default_file_name); + warn("open '%s' for reading failed", param_get_default_file()); return -1; } return 1; @@ -551,7 +551,7 @@ param_load_default(void) close(fd); if (result != 0) { - warn("error reading parameters from '%s'", param_default_file_name); + warn("error reading parameters from '%s'", param_get_default_file()); return -2; } diff --git a/apps/systemlib/param/param.h b/apps/systemlib/param/param.h index 64bb77834..6fa73b5a4 100644 --- a/apps/systemlib/param/param.h +++ b/apps/systemlib/param/param.h @@ -235,24 +235,39 @@ __EXPORT int param_load(int fd); __EXPORT void param_foreach(void (*func)(void *arg, param_t param), void *arg, bool only_changed); /** - * Export parameters to the default file name. + * Set the default parameter file name. * + * @param filename Path to the default parameter file. The file is not require to + * exist. + * @return Zero on success. + */ +__EXPORT int param_set_default_file(const char* filename); + +/** + * Get the default parameter file name. * - * @param + * @return The path to the current default parameter file; either as + * a result of a call to param_set_default_file, or the + * built-in default. */ -__EXPORT int param_save_default(void); +__EXPORT const char *param_get_default_file(void); /** - * Set the default parameter file name. + * Save parameters to the default file. + * + * This function saves all parameters with non-default values. + * + * @return Zero on success. */ -__EXPORT int param_set_default_file(const char* filename); +__EXPORT int param_save_default(void); /** - * Import parameters from the default file name. + * Load parameters from the default parameter file. + * + * @return Zero on success. */ __EXPORT int param_load_default(void); - /* * Macros creating static parameter definitions. * -- cgit v1.2.3