Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Param reset excludes #1739

Closed
wants to merge 10 commits into from
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,8 @@ then
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params
param reset_nostart
# Wipe out params except RC*
param reset_nostart RC*
set AUTOCNF yes
else
set AUTOCNF no
Expand Down
45 changes: 42 additions & 3 deletions src/modules/systemlib/param/param.c
Original file line number Diff line number Diff line change
Expand Up @@ -70,9 +70,16 @@
/**
* 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;
#ifdef _UNIT_TEST
extern struct param_info_s param_array[];
extern struct param_info_s *param_info_base;
extern struct param_info_s *param_info_limit;
#else
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;
#endif

#define param_info_count ((unsigned)(param_info_limit - param_info_base))

/**
Expand Down Expand Up @@ -483,6 +490,38 @@ param_reset_all(void)
param_notify_changes();
}

void
param_reset_excludes(const char* excludes[], int num_excludes)
{
param_lock();

param_t param;

for (param = 0; handle_in_range(param); param++) {
const char* name = param_name(param);
bool exclude = false;

for (int index = 0; index < num_excludes; index ++) {
int len = strlen(excludes[index]);

if((excludes[index][len - 1] == '*'
&& strncmp(name, excludes[index], len - 1) == 0)
|| strcmp(name, excludes[index]) == 0) {
exclude = true;
break;
}
}

if(!exclude) {
param_reset(param);
}
}

param_unlock();

param_notify_changes();
}

static const char *param_default_file = "/eeprom/parameters";
static char *param_user_file = NULL;

Expand Down
12 changes: 12 additions & 0 deletions src/modules/systemlib/param/param.h
Original file line number Diff line number Diff line change
Expand Up @@ -188,6 +188,18 @@ __EXPORT void param_reset(param_t param);
*/
__EXPORT void param_reset_all(void);


/**
* Reset all parameters to their default values except for excluded parameters.
*
* This function also releases the storage used by struct parameters.
*
* @param excludes Array of param names to exclude from resetting. Use a wildcard
* at the end to exclude parameters with a certain prefix.
* @param num_excludes The number of excludes provided.
*/
__EXPORT void param_reset_excludes(const char* excludes[], int num_excludes);

/**
* Export changed parameters to a file.
*
Expand Down
5 changes: 3 additions & 2 deletions src/modules/systemlib/system_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,9 @@ PARAM_DEFINE_INT32(SYS_AUTOSTART, 0);
/**
* Automatically configure default values.
*
* Set to 1 to set platform-specific parameters to their default
* values on next system startup.
* Set to 1 to reset parameters on next system startup (setting defaults).
* Platform-specific values are used if available.
* RC* parameters are preserved.
*
* @min 0
* @max 1
Expand Down
34 changes: 25 additions & 9 deletions src/systemcmds/param/param.c
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,8 @@ static void do_show(const char* search_string);
static void do_show_print(void *arg, param_t param);
static void do_set(const char* name, const char* val, bool fail_on_not_found);
static void do_compare(const char* name, char* vals[], unsigned comparisons);
static void do_reset(void);
static void do_reset_nostart(void);
static void do_reset(const char* excludes[], int num_excludes);
static void do_reset_nostart(const char* excludes[], int num_excludes);

int
param_main(int argc, char *argv[])
Expand Down Expand Up @@ -142,11 +142,19 @@ param_main(int argc, char *argv[])
}

if (!strcmp(argv[1], "reset")) {
do_reset();
if (argc >= 3) {
do_reset((const char**) &argv[2], argc - 2);
} else {
do_reset(NULL, 0);
}
}

if (!strcmp(argv[1], "reset_nostart")) {
do_reset_nostart();
if (argc >= 3) {
do_reset_nostart((const char**) &argv[2], argc - 2);
} else {
do_reset_nostart(NULL, 0);
}
}
}

Expand Down Expand Up @@ -421,10 +429,14 @@ do_compare(const char* name, char* vals[], unsigned comparisons)
}

static void
do_reset(void)
do_reset(const char* excludes[], int num_excludes)
{
param_reset_all();

if (num_excludes > 0) {
param_reset_excludes(excludes, num_excludes);
} else {
param_reset_all();
}

if (param_save_default()) {
warnx("Param export failed.");
exit(1);
Expand All @@ -434,7 +446,7 @@ do_reset(void)
}

static void
do_reset_nostart(void)
do_reset_nostart(const char* excludes[], int num_excludes)
{

int32_t autostart;
Expand All @@ -443,7 +455,11 @@ do_reset_nostart(void)
(void)param_get(param_find("SYS_AUTOSTART"), &autostart);
(void)param_get(param_find("SYS_AUTOCONFIG"), &autoconfig);

param_reset_all();
if (num_excludes > 0) {
param_reset_excludes(excludes, num_excludes);
} else {
param_reset_all();
}

(void)param_set(param_find("SYS_AUTOSTART"), &autostart);
(void)param_set(param_find("SYS_AUTOCONFIG"), &autoconfig);
Expand Down
10 changes: 10 additions & 0 deletions unittests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ add_definitions(-Dnoreturn_function=)
add_definitions(-Dmain_t=int)
add_definitions(-DERROR=-1)
add_definitions(-DOK=0)
add_definitions(-D_UNIT_TEST=)

# check
add_custom_target(unittests COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure)
Expand Down Expand Up @@ -77,3 +78,12 @@ add_gtest(st24_test)
# sf0x_test
add_executable(sf0x_test sf0x_test.cpp ${PX_SRC}/drivers/sf0x/sf0x_parser.cpp)
add_gtest(sf0x_test)

# param_test
add_executable(param_test param_test.cpp
hrt.cpp
uorb_stub.cpp
${PX_SRC}/modules/systemlib/param/param.c
${PX_SRC}/modules/systemlib/bson/tinybson.c
)
add_gtest(param_test)
143 changes: 143 additions & 0 deletions unittests/param_test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,143 @@
#include <systemlib/visibility.h>
#include <systemlib/param/param.h>

#include "gtest/gtest.h"

/*
* These will be used in param.c if compiling for unit tests
*/
struct param_info_s param_array[256];
struct param_info_s *param_info_base;
struct param_info_s *param_info_limit;

/*
* Adds test parameters
*/
void _add_parameters() {
struct param_info_s test_1 = {
"TEST_1",
PARAM_TYPE_INT32
};
test_1.val.i = 2;

struct param_info_s test_2 = {
"TEST_2",
PARAM_TYPE_INT32
};
test_2.val.i = 4;

struct param_info_s rc_x = {
"RC_X",
PARAM_TYPE_INT32
};
rc_x.val.i = 8;

struct param_info_s rc2_x = {
"RC2_X",
PARAM_TYPE_INT32
};
rc2_x.val.i = 16;

param_array[0] = test_1;
param_array[1] = test_2;
param_array[2] = rc_x;
param_array[3] = rc2_x;
param_info_base = (struct param_info_s *) &param_array[0];
param_info_limit = (struct param_info_s *) &param_array[4]; // needs to point at the end of the data,
// therefore number of params + 1
}

void _assert_parameter_int_value(param_t param, int32_t expected) {
int32_t value;
int result = param_get(param, &value);
ASSERT_EQ(0, result) << printf("param_get (%i) did not return parameter\n", param);
ASSERT_EQ(expected, value) << printf("value for param (%i) doesn't match default value\n", param);
}

void _set_all_int_parameters_to(int32_t value) {
param_set((param_t)0, &value);
param_set((param_t)1, &value);
param_set((param_t)2, &value);
param_set((param_t)3, &value);

_assert_parameter_int_value((param_t)0, value);
_assert_parameter_int_value((param_t)1, value);
_assert_parameter_int_value((param_t)2, value);
_assert_parameter_int_value((param_t)3, value);
}

TEST(ParamTest, SimpleFind) {
_add_parameters();

param_t param = param_find("TEST_2");
ASSERT_NE(PARAM_INVALID, param) << "param_find did not find parameter";

int32_t value;
int result = param_get(param, &value);
ASSERT_EQ(0, result) << "param_get did not return parameter";
ASSERT_EQ(4, value) << "value of returned parameter does not match";
}

TEST(ParamTest, ResetAll) {
_add_parameters();
_set_all_int_parameters_to(50);

param_reset_all();

_assert_parameter_int_value((param_t)0, 2);
_assert_parameter_int_value((param_t)1, 4);
_assert_parameter_int_value((param_t)2, 8);
_assert_parameter_int_value((param_t)3, 16);
}

TEST(ParamTest, ResetAllExcludesOne) {
_add_parameters();
_set_all_int_parameters_to(50);

const char* excludes[] = {"RC_X"};
param_reset_excludes(excludes, 1);

_assert_parameter_int_value((param_t)0, 2);
_assert_parameter_int_value((param_t)1, 4);
_assert_parameter_int_value((param_t)2, 50);
_assert_parameter_int_value((param_t)3, 16);
}

TEST(ParamTest, ResetAllExcludesTwo) {
_add_parameters();
_set_all_int_parameters_to(50);

const char* excludes[] = {"RC_X", "TEST_1"};
param_reset_excludes(excludes, 2);

_assert_parameter_int_value((param_t)0, 50);
_assert_parameter_int_value((param_t)1, 4);
_assert_parameter_int_value((param_t)2, 50);
_assert_parameter_int_value((param_t)3, 16);
}

TEST(ParamTest, ResetAllExcludesBoundaryCheck) {
_add_parameters();
_set_all_int_parameters_to(50);

const char* excludes[] = {"RC_X", "TEST_1"};
param_reset_excludes(excludes, 1);

_assert_parameter_int_value((param_t)0, 2);
_assert_parameter_int_value((param_t)1, 4);
_assert_parameter_int_value((param_t)2, 50);
_assert_parameter_int_value((param_t)3, 16);
}

TEST(ParamTest, ResetAllExcludesWildcard) {
_add_parameters();
_set_all_int_parameters_to(50);

const char* excludes[] = {"RC*"};
param_reset_excludes(excludes, 1);

_assert_parameter_int_value((param_t)0, 2);
_assert_parameter_int_value((param_t)1, 4);
_assert_parameter_int_value((param_t)2, 50);
_assert_parameter_int_value((param_t)3, 50);
}
6 changes: 3 additions & 3 deletions unittests/sf0x_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include "gtest/gtest.h"

TEST(SF0XTest, SF0X) {
const char LINE_MAX = 20;
char _linebuf[LINE_MAX];
const char _LINE_MAX = 20;
char _linebuf[_LINE_MAX];
_linebuf[0] = '\0';

const char *lines[] = {"0.01\r\n",
Expand All @@ -34,7 +34,7 @@ TEST(SF0XTest, SF0X) {

enum SF0X_PARSE_STATE state = SF0X_PARSE_STATE0_UNSYNC;
float dist_m;
char _parserbuf[LINE_MAX];
char _parserbuf[_LINE_MAX];
unsigned _parsebuf_index = 0;

for (unsigned l = 0; l < sizeof(lines) / sizeof(lines[0]); l++) {
Expand Down
21 changes: 21 additions & 0 deletions unittests/uorb_stub.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
#include <stdint.h>
#include <sys/types.h>
//#include "gmock/gmock.h"

#include "uORB/uORB.h"

/******************************************
* uORB stubs (incomplete)
*
* TODO: use googlemock
******************************************/

orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) {
return (orb_advert_t)0;
}

int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) {
return 0;
}