mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Merge pull request #1331 from AndersHoglund/testsystem
Added junittest XML test results.
This commit is contained in:
commit
c96bb34fda
3 changed files with 39 additions and 9 deletions
5
Makefile
5
Makefile
|
@ -826,8 +826,9 @@ targets:
|
||||||
$(V0) @echo "Base target: $(BASE_TARGET)"
|
$(V0) @echo "Base target: $(BASE_TARGET)"
|
||||||
|
|
||||||
## test : run the cleanflight test suite
|
## test : run the cleanflight test suite
|
||||||
test:
|
## junittest : run the cleanflight test suite, producing Junit XML result files.
|
||||||
$(V0) cd src/test && $(MAKE) test || true
|
test junittest:
|
||||||
|
$(V0) cd src/test && $(MAKE) $@ || true
|
||||||
|
|
||||||
# rebuild everything when makefile changes
|
# rebuild everything when makefile changes
|
||||||
$(TARGET_OBJS) : Makefile
|
$(TARGET_OBJS) : Makefile
|
||||||
|
|
|
@ -42,6 +42,12 @@ C_FLAGS = $(COMMON_FLAGS) \
|
||||||
CXX_FLAGS = $(COMMON_FLAGS) \
|
CXX_FLAGS = $(COMMON_FLAGS) \
|
||||||
-std=gnu++11
|
-std=gnu++11
|
||||||
|
|
||||||
|
# Compiler flags for coverage instrumentation
|
||||||
|
COVERAGE_FLAGS := --coverage
|
||||||
|
|
||||||
|
C_FLAGS += $(COVERAGE_FLAGS)
|
||||||
|
CXX_FLAGS += $(COVERAGE_FLAGS)
|
||||||
|
|
||||||
# Gather up all of the tests.
|
# Gather up all of the tests.
|
||||||
TEST_SRC = $(sort $(wildcard $(TEST_DIR)/*.cc))
|
TEST_SRC = $(sort $(wildcard $(TEST_DIR)/*.cc))
|
||||||
TESTS = $(TEST_SRC:$(TEST_DIR)/%.cc=%)
|
TESTS = $(TEST_SRC:$(TEST_DIR)/%.cc=%)
|
||||||
|
@ -545,9 +551,32 @@ $(OBJECT_DIR)/alignsensor_unittest : \
|
||||||
|
|
||||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||||
|
|
||||||
|
|
||||||
|
## test : Build and run the Unit Tests
|
||||||
test: $(TESTS:%=test-%)
|
test: $(TESTS:%=test-%)
|
||||||
|
|
||||||
|
## junittest : Build and run the Unit Tests, producing Junit XML result files."
|
||||||
|
junittest: EXEC_OPTS = "--gtest_output=xml:$<_results.xml"
|
||||||
|
junittest: $(TESTS:%=test-%)
|
||||||
|
|
||||||
test-%: $(OBJECT_DIR)/%
|
test-%: $(OBJECT_DIR)/%
|
||||||
$<
|
$< $(EXEC_OPTS)
|
||||||
|
|
||||||
|
## help : print this help message and exit
|
||||||
|
## what : print this help message and exit
|
||||||
|
## usage : print this help message and exit
|
||||||
|
help what usage: Makefile
|
||||||
|
@echo ""
|
||||||
|
@echo "Makefile for Unit Tests"
|
||||||
|
@echo ""
|
||||||
|
@echo "Usage:"
|
||||||
|
@echo " make [goal] "
|
||||||
|
@echo ""
|
||||||
|
@echo "Valid goals are:"
|
||||||
|
@echo ""
|
||||||
|
@sed -n 's/^## //p' $<
|
||||||
|
@echo ""
|
||||||
|
@echo "Any of the Unit Test programs can be used as goals:"
|
||||||
|
@$(foreach prg, $(TEST_BINARIES), echo " $(prg)";)
|
||||||
|
|
||||||
-include $(DEPS)
|
-include $(DEPS)
|
||||||
|
|
|
@ -41,7 +41,7 @@ extern "C" {
|
||||||
|
|
||||||
static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
|
static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
|
||||||
{
|
{
|
||||||
int16_t tmp[3];
|
int32_t tmp[3];
|
||||||
|
|
||||||
for(int i=0; i<3; i++) {
|
for(int i=0; i<3; i++) {
|
||||||
tmp[i] = 0;
|
tmp[i] = 0;
|
||||||
|
@ -56,7 +56,7 @@ static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//static void initXAxisRotation(int32_t mat[][3], int16_t angle)
|
//static void initXAxisRotation(int32_t mat[][3], int32_t angle)
|
||||||
//{
|
//{
|
||||||
// mat[0][0] = 1;
|
// mat[0][0] = 1;
|
||||||
// mat[0][1] = 0;
|
// mat[0][1] = 0;
|
||||||
|
@ -69,7 +69,7 @@ static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
|
||||||
// mat[2][2] = cos(angle*DEG2RAD);
|
// mat[2][2] = cos(angle*DEG2RAD);
|
||||||
//}
|
//}
|
||||||
|
|
||||||
static void initYAxisRotation(int32_t mat[][3], int16_t angle)
|
static void initYAxisRotation(int32_t mat[][3], int32_t angle)
|
||||||
{
|
{
|
||||||
mat[0][0] = cos(angle*DEG2RAD);
|
mat[0][0] = cos(angle*DEG2RAD);
|
||||||
mat[0][1] = 0;
|
mat[0][1] = 0;
|
||||||
|
@ -82,7 +82,7 @@ static void initYAxisRotation(int32_t mat[][3], int16_t angle)
|
||||||
mat[2][2] = cos(angle*DEG2RAD);
|
mat[2][2] = cos(angle*DEG2RAD);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void initZAxisRotation(int32_t mat[][3], int16_t angle)
|
static void initZAxisRotation(int32_t mat[][3], int32_t angle)
|
||||||
{
|
{
|
||||||
mat[0][0] = cos(angle*DEG2RAD);
|
mat[0][0] = cos(angle*DEG2RAD);
|
||||||
mat[0][1] = -sin(angle*DEG2RAD);
|
mat[0][1] = -sin(angle*DEG2RAD);
|
||||||
|
@ -95,7 +95,7 @@ static void initZAxisRotation(int32_t mat[][3], int16_t angle)
|
||||||
mat[2][2] = 1;
|
mat[2][2] = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void testCW(sensor_align_e rotation, int16_t angle)
|
static void testCW(sensor_align_e rotation, int32_t angle)
|
||||||
{
|
{
|
||||||
int32_t src[XYZ_AXIS_COUNT];
|
int32_t src[XYZ_AXIS_COUNT];
|
||||||
int32_t dest[XYZ_AXIS_COUNT];
|
int32_t dest[XYZ_AXIS_COUNT];
|
||||||
|
@ -153,7 +153,7 @@ static void testCW(sensor_align_e rotation, int16_t angle)
|
||||||
* Since the order of flip and rotation matters, these tests make the
|
* Since the order of flip and rotation matters, these tests make the
|
||||||
* assumption that the 'flip' occurs first, followed by clockwise rotation
|
* assumption that the 'flip' occurs first, followed by clockwise rotation
|
||||||
*/
|
*/
|
||||||
static void testCWFlip(sensor_align_e rotation, int16_t angle)
|
static void testCWFlip(sensor_align_e rotation, int32_t angle)
|
||||||
{
|
{
|
||||||
int32_t src[XYZ_AXIS_COUNT];
|
int32_t src[XYZ_AXIS_COUNT];
|
||||||
int32_t dest[XYZ_AXIS_COUNT];
|
int32_t dest[XYZ_AXIS_COUNT];
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue