Browse Source

setting parameters at runtime to get rid of the designated union initializer

sbg
Andreas Antener 10 years ago committed by Lorenz Meier
parent
commit
28e943ca28
  1. 2
      unittests/CMakeLists.txt
  2. 43
      unittests/param_test.cpp

2
unittests/CMakeLists.txt

@ -61,7 +61,7 @@ add_executable(mixer_test mixer_test.cpp hrt.cpp @@ -61,7 +61,7 @@ add_executable(mixer_test mixer_test.cpp hrt.cpp
${PX_SRC}/modules/systemlib/mixer/mixer_simple.cpp
${PX_SRC}/modules/systemlib/pwm_limit/pwm_limit.c
${PX_SRC}/systemcmds/tests/test_mixer.cpp)
#add_gtest(mixer_test)
add_gtest(mixer_test)
# conversion_test
add_executable(conversion_test conversion_test.cpp ${PX_SRC}/systemcmds/tests/test_conv.cpp)

43
unittests/param_test.cpp

@ -3,30 +3,45 @@ @@ -3,30 +3,45 @@
#include "gtest/gtest.h"
static const struct param_info_s test_1 = {
"TEST_1",
PARAM_TYPE_INT32,
.val.i = 2
};
struct param_info_s param_array[256];
struct param_info_s *param_info_base;
struct param_info_s *param_info_limit;
TEST(ParamTest, ResetAll) {
/*
* 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;
param_array[0] = test_1;
param_array[1] = test_2;
param_info_base = (struct param_info_s *) &param_array[0];
param_info_limit = (struct param_info_s *) &param_array[1];
param_info_limit = (struct param_info_s *) &param_array[2];
}
TEST(ParamTest, SimpleFind) {
_add_parameters();
printf("diff: %i\n", (unsigned)(param_info_limit - param_info_base));
param_t test_1 = param_find("TEST_1");
ASSERT_NE(PARAM_INVALID, test_1) << "param_find failed";
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(test_1, &value);
ASSERT_EQ(0, result) << "param_get failed";
ASSERT_EQ(2, value) << "wrong param value";
//ASSERT_TRUE(false) << "fail";
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";
}

Loading…
Cancel
Save