Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
F
Firmware
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Package registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Alberto Ruiz Garcia
Firmware
Commits
59fd22be
Commit
59fd22be
authored
7 years ago
by
Daniel Agar
Browse files
Options
Downloads
Patches
Plain Diff
parameters import/export test
parent
8d4036df
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
src/include/unit_test.h
+1
-1
1 addition, 1 deletion
src/include/unit_test.h
src/systemcmds/tests/params.c
+5
-0
5 additions, 0 deletions
src/systemcmds/tests/params.c
src/systemcmds/tests/test_parameters.cpp
+338
-0
338 additions, 0 deletions
src/systemcmds/tests/test_parameters.cpp
with
344 additions
and
1 deletion
src/include/unit_test.h
+
1
−
1
View file @
59fd22be
...
...
@@ -161,7 +161,7 @@ protected:
/// since it will give you better error reporting of the actual values being compared.
#define ut_compare_float(message, v1, v2, precision) \
do { \
int _p = pow(10.0f, precision); \
int _p = pow
f
(10.0f, precision); \
int _v1 = (int)(v1 * _p + 0.5f); \
int _v2 = (int)(v2 * _p + 0.5f); \
if (_v1 != _v2) { \
...
...
This diff is collapsed.
Click to expand it.
src/systemcmds/tests/params.c
+
5
−
0
View file @
59fd22be
...
...
@@ -41,6 +41,11 @@ PARAM_DEFINE_INT32(TEST_1, 2);
*/
PARAM_DEFINE_INT32
(
TEST_2
,
4
);
/**
* @group Testing
*/
PARAM_DEFINE_FLOAT
(
TEST_3
,
5
.
0
f
);
/**
* @group Testing
*/
...
...
This diff is collapsed.
Click to expand it.
src/systemcmds/tests/test_parameters.cpp
+
338
−
0
View file @
59fd22be
#include
<unit_test.h>
#include
<px4_defines.h>
#include
<fcntl.h>
class
ParameterTest
:
public
UnitTest
{
public:
...
...
@@ -11,6 +14,7 @@ public:
p1
=
param_find
(
"TEST_RC2_X"
);
p2
=
param_find
(
"TEST_1"
);
p3
=
param_find
(
"TEST_2"
);
p4
=
param_find
(
"TEST_3"
);
}
private
:
...
...
@@ -19,16 +23,25 @@ private:
param_t
p1
{
PARAM_INVALID
};
param_t
p2
{
PARAM_INVALID
};
param_t
p3
{
PARAM_INVALID
};
param_t
p4
{
PARAM_INVALID
};
bool
_assert_parameter_int_value
(
param_t
param
,
int32_t
expected
);
bool
_assert_parameter_float_value
(
param_t
param
,
float
expected
);
bool
_set_all_int_parameters_to
(
int32_t
value
);
// tests on the test parameters (TEST_RC_X, TEST_RC2_X, TEST_1, TEST_2, TEST_3)
bool
SimpleFind
();
bool
ResetAll
();
bool
ResetAllExcludesOne
();
bool
ResetAllExcludesTwo
();
bool
ResetAllExcludesBoundaryCheck
();
bool
ResetAllExcludesWildcard
();
bool
exportImport
();
// tests on system parameters
// WARNING, can potentially trash your system
bool
exportImportAll
();
};
bool
ParameterTest
::
_assert_parameter_int_value
(
param_t
param
,
int32_t
expected
)
...
...
@@ -41,6 +54,16 @@ bool ParameterTest::_assert_parameter_int_value(param_t param, int32_t expected)
return
true
;
}
bool
ParameterTest
::
_assert_parameter_float_value
(
param_t
param
,
float
expected
)
{
float
value
;
int
result
=
param_get
(
param
,
&
value
);
ut_compare
(
"param_get did not return parameter"
,
0
,
result
);
ut_compare_float
(
"value for param doesn't match default value"
,
expected
,
value
,
0.001
);
return
true
;
}
bool
ParameterTest
::
_set_all_int_parameters_to
(
int32_t
value
)
{
param_set
(
p0
,
&
value
);
...
...
@@ -157,14 +180,329 @@ bool ParameterTest::ResetAllExcludesWildcard()
return
ret
;
}
bool
ParameterTest
::
exportImport
()
{
static
constexpr
float
MAGIC_FLOAT_VAL
=
0.314159
f
;
bool
ret
=
true
;
param_t
test_params
[]
=
{
p0
,
p1
,
p2
,
p3
,
p4
};
// set all params to corresponding param_t value
for
(
auto
p
:
test_params
)
{
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
const
int32_t
set_val
=
p
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
int32_t
get_val
=
0
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
const
float
set_val
=
(
float
)
p
+
MAGIC_FLOAT_VAL
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
float
get_val
=
0.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
(
float
)
p
+
MAGIC_FLOAT_VAL
);
}
}
// save
if
(
param_save_default
()
!=
PX4_OK
)
{
PX4_ERR
(
"param_save_default failed"
);
return
false
;
}
// zero all params and verify, but don't save
for
(
auto
p
:
test_params
)
{
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
const
int32_t
set_val
=
0
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
int32_t
get_val
=
-
1
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
set_val
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
const
float
set_val
=
0.0
f
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
float
get_val
=
-
1.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare_float
(
"value for param doesn't match default value"
,
set_val
,
get_val
,
0.001
f
);
}
}
// load saved params
if
(
param_load_default
()
!=
PX4_OK
)
{
PX4_ERR
(
"param_save_default failed"
);
ret
=
true
;
}
// check every param
for
(
auto
p
:
test_params
)
{
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
int32_t
get_val
=
0.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
float
get_val
=
0.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare_float
(
"value for param doesn't match default value"
,
p
,
(
float
)
p
+
MAGIC_FLOAT_VAL
,
0.001
f
);
}
}
return
ret
;
}
bool
ParameterTest
::
exportImportAll
()
{
static
constexpr
float
MAGIC_FLOAT_VAL
=
0.217828
f
;
// backup current parameters
const
char
*
param_file_name
=
PX4_ROOTFSDIR
"/fs/microsd/param_backup"
;
int
fd
=
open
(
param_file_name
,
O_WRONLY
|
O_CREAT
,
PX4_O_MODE_666
);
if
(
fd
<
0
)
{
PX4_ERR
(
"open '%s' failed (%i)"
,
param_file_name
,
errno
);
return
false
;
}
int
result
=
param_export
(
fd
,
false
);
if
(
result
!=
PX4_OK
)
{
PX4_ERR
(
"param_export failed"
);
close
(
fd
);
return
false
;
}
close
(
fd
);
bool
ret
=
true
;
int
N
=
param_count
();
// set all params to corresponding param_t value
for
(
unsigned
i
=
0
;
i
<
N
;
i
++
)
{
param_t
p
=
param_for_index
(
i
);
if
(
p
==
PARAM_INVALID
)
{
PX4_ERR
(
"param invalid: %d(%d)"
,
p
,
i
);
break
;
}
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
const
int32_t
set_val
=
p
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
int32_t
get_val
=
0
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
const
float
set_val
=
(
float
)
p
+
MAGIC_FLOAT_VAL
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_set_no_notification failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
float
get_val
=
0.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
(
float
)
p
+
MAGIC_FLOAT_VAL
);
}
}
// save
if
(
param_save_default
()
!=
PX4_OK
)
{
PX4_ERR
(
"param_save_default failed"
);
return
false
;
}
// zero all params and verify, but don't save
for
(
unsigned
i
=
0
;
i
<
N
;
i
++
)
{
param_t
p
=
param_for_index
(
i
);
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
const
int32_t
set_val
=
0
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param set failed: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
int32_t
get_val
=
-
1
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
set_val
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
float
set_val
=
0.0
f
;
if
(
param_set_no_notification
(
p
,
&
set_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param set failed: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
float
get_val
=
-
1.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
set_val
,
get_val
);
}
}
// load saved params
if
(
param_load_default
()
!=
PX4_OK
)
{
PX4_ERR
(
"param_save_default failed"
);
ret
=
true
;
}
// check every param
for
(
unsigned
i
=
0
;
i
<
N
;
i
++
)
{
param_t
p
=
param_for_index
(
i
);
if
(
param_type
(
p
)
==
PARAM_TYPE_INT32
)
{
int32_t
get_val
=
0
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
get_val
);
}
if
(
param_type
(
p
)
==
PARAM_TYPE_FLOAT
)
{
float
get_val
=
0.0
f
;
if
(
param_get
(
p
,
&
get_val
)
!=
PX4_OK
)
{
PX4_ERR
(
"param_get failed for: %d"
,
p
);
ut_assert
(
"param_set_no_notification failed"
,
false
);
}
ut_compare
(
"value for param doesn't match default value"
,
p
,
(
float
)
p
+
MAGIC_FLOAT_VAL
);
}
}
param_reset_all
();
// restore original params
fd
=
open
(
param_file_name
,
O_RDONLY
);
if
(
fd
<
0
)
{
PX4_ERR
(
"open '%s' failed (%i)"
,
param_file_name
,
errno
);
return
false
;
}
result
=
param_import
(
fd
);
close
(
fd
);
if
(
result
<
0
)
{
PX4_ERR
(
"importing from '%s' failed (%i)"
,
param_file_name
,
result
);
return
false
;
}
return
ret
;
}
bool
ParameterTest
::
run_tests
()
{
param_control_autosave
(
false
);
ut_run_test
(
ResetAll
);
ut_run_test
(
SimpleFind
);
ut_run_test
(
ResetAll
);
ut_run_test
(
ResetAllExcludesOne
);
ut_run_test
(
ResetAllExcludesTwo
);
ut_run_test
(
ResetAllExcludesBoundaryCheck
);
ut_run_test
(
ResetAllExcludesWildcard
);
ut_run_test
(
exportImport
);
// WARNING, can potentially trash your system
#ifdef __PX4_POSIX
ut_run_test
(
exportImportAll
);
#endif
/* __PX4_POSIX */
param_control_autosave
(
true
);
return
(
_tests_failed
==
0
);
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment