aboutsummaryrefslogtreecommitdiff
path: root/unittests/param_test.cpp
diff options
context:
space:
mode:
authorAndreas Antener <antener_a@gmx.ch>2015-02-03 10:35:20 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-02-10 08:39:46 +0100
commit5cccc01cd472f5a906ce21bbafd9d35d90bf7227 (patch)
tree1cc981f132b8e5967263f5caf2538904b8416a21 /unittests/param_test.cpp
parent13039f9e69d4f5e138f3ff2485534477e21eab98 (diff)
downloadpx4-firmware-5cccc01cd472f5a906ce21bbafd9d35d90bf7227.tar.gz
px4-firmware-5cccc01cd472f5a906ce21bbafd9d35d90bf7227.tar.bz2
px4-firmware-5cccc01cd472f5a906ce21bbafd9d35d90bf7227.zip
added unit test directive to switch out parameter storage
Diffstat (limited to 'unittests/param_test.cpp')
-rw-r--r--unittests/param_test.cpp29
1 files changed, 12 insertions, 17 deletions
diff --git a/unittests/param_test.cpp b/unittests/param_test.cpp
index 2d71d3b49..b3aff34e8 100644
--- a/unittests/param_test.cpp
+++ b/unittests/param_test.cpp
@@ -3,33 +3,28 @@
#include "gtest/gtest.h"
-//#PARAM_DEFINE_INT32(TEST_A, 5);
-
-
-static const struct param_info_s testparam = {
- "test",
+static const struct param_info_s test_1 = {
+ "TEST_1",
PARAM_TYPE_INT32,
.val.i = 2
};
-
-extern param_info_s *__param_start, *__param_end;
-extern struct param_info_s param_array[];
-const struct param_info_s *ib = __param_start;
-const struct param_info_s *il = __param_end;
+struct param_info_s param_array[256];
+struct param_info_s *param_info_base;
+struct param_info_s *param_info_limit;
TEST(ParamTest, ResetAll) {
- param_array[0] = testparam;
+ param_array[0] = test_1;
+ param_info_base = (struct param_info_s *) &param_array[0];
+ param_info_limit = (struct param_info_s *) &param_array[1];
- printf("diff: %i\n", (unsigned)(il - ib));
- printf("start: %i\n", __param_start);
- printf("end: %i\n", __param_end);
+ printf("diff: %i\n", (unsigned)(param_info_limit - param_info_base));
- param_t testparam = param_find("test");
- ASSERT_NE(PARAM_INVALID, testparam) << "param_find failed";
+ param_t test_1 = param_find("TEST_1");
+ ASSERT_NE(PARAM_INVALID, test_1) << "param_find failed";
int32_t value;
- int result = param_get(testparam, &value);
+ int result = param_get(test_1, &value);
ASSERT_EQ(0, result) << "param_get failed";
ASSERT_EQ(2, value) << "wrong param value";