forked from Archive/PX4-Autopilot
unit_test inline implementation and remove module build
This commit is contained in:
parent
f282f50cff
commit
a02caff1bc
|
@ -63,7 +63,6 @@ set(config_module_list
|
|||
#modules/commander/commander_tests
|
||||
#lib/controllib/controllib_test
|
||||
#modules/mavlink/mavlink_tests
|
||||
#modules/unit_test
|
||||
#modules/uORB/uORB_tests
|
||||
#systemcmds/tests
|
||||
|
||||
|
|
|
@ -84,7 +84,6 @@ set(config_module_list
|
|||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -86,7 +86,6 @@ set(config_module_list
|
|||
modules/mc_pos_control/mc_pos_control_tests
|
||||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -84,7 +84,6 @@ set(config_module_list
|
|||
modules/mc_pos_control/mc_pos_control_tests
|
||||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -91,7 +91,6 @@ set(config_module_list
|
|||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -90,7 +90,6 @@ set(config_module_list
|
|||
modules/mc_pos_control/mc_pos_control_tests
|
||||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -91,7 +91,6 @@ set(config_module_list
|
|||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -89,7 +89,6 @@ set(config_module_list
|
|||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -51,7 +51,6 @@ set(config_module_list
|
|||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <drivers/sf0x/sf0x_parser.h>
|
||||
|
||||
|
|
|
@ -53,15 +53,28 @@ class __EXPORT UnitTest
|
|||
{
|
||||
public:
|
||||
|
||||
UnitTest();
|
||||
virtual ~UnitTest();
|
||||
UnitTest() = default;
|
||||
virtual ~UnitTest() = default;
|
||||
|
||||
/// @brief Override to run your unit tests. Unit tests should be called using ut_run_test macro.
|
||||
/// @return true: all unit tests succeeded, false: one or more unit tests failed
|
||||
virtual bool run_tests(void) = 0;
|
||||
|
||||
/// @brief Prints results from running of unit tests.
|
||||
void print_results(void);
|
||||
void print_results()
|
||||
{
|
||||
if (_tests_failed) {
|
||||
PX4_ERR("SOME TESTS FAILED");
|
||||
|
||||
} else {
|
||||
PX4_INFO("ALL TESTS PASSED");
|
||||
}
|
||||
|
||||
PX4_INFO(" Tests passed : %d", _tests_passed);
|
||||
PX4_INFO(" Tests failed : %d", _tests_failed);
|
||||
PX4_INFO(" Tested assertions : %d", _assertions);
|
||||
}
|
||||
|
||||
|
||||
/// @brief Macro to create a function which will run a unit test class and print results.
|
||||
#define ut_declare_test(test_function, test_class) \
|
||||
|
@ -175,14 +188,21 @@ protected:
|
|||
virtual void _init(void) { }; ///< Run before each unit test. Override to provide custom behavior.
|
||||
virtual void _cleanup(void) { }; ///< Run after each unit test. Override to provide custom behavior.
|
||||
|
||||
void _print_assert(const char *msg, const char *test, const char *file, int line);
|
||||
void _print_compare(const char *msg, const char *v1_text, int v1, const char *v2_text, int v2, const char *file,
|
||||
int line);
|
||||
void _print_assert(const char *msg, const char *test, const char *file, int line)
|
||||
{
|
||||
PX4_ERR("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
|
||||
}
|
||||
|
||||
int _tests_run; ///< The number of individual unit tests run
|
||||
int _tests_failed; ///< The number of unit tests which failed
|
||||
int _tests_passed; ///< The number of unit tests which passed
|
||||
int _assertions; ///< Total number of assertions tested by all unit tests
|
||||
void _print_compare(const char *msg, const char *v1_text, int v1, const char *v2_text, int v2, const char *file,
|
||||
int line)
|
||||
{
|
||||
PX4_ERR("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
|
||||
}
|
||||
|
||||
int _tests_run{0}; ///< The number of individual unit tests run
|
||||
int _tests_failed{0}; ///< The number of unit tests which failed
|
||||
int _tests_passed{0}; ///< The number of unit tests which passed
|
||||
int _assertions{0}; ///< Total number of assertions tested by all unit tests
|
||||
};
|
||||
|
||||
#endif /* UNIT_TEST_H_ */
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
#include "state_machine_helper_test.h"
|
||||
|
||||
#include "../state_machine_helper.h"
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
class StateMachineHelperTest : public UnitTest
|
||||
{
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
#include "../mavlink_bridge_header.h"
|
||||
#include "../mavlink_ftp.h"
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
*/
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
|
||||
extern "C" __EXPORT int mc_pos_control_tests_main(int argc, char *argv[]);
|
||||
|
|
|
@ -1,41 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE modules__unit_test
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
unit_test.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
|
@ -1,76 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Simon Wilks <sjwilks@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "unit_test.h"
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
UnitTest::UnitTest() :
|
||||
_tests_run(0),
|
||||
_tests_failed(0),
|
||||
_tests_passed(0),
|
||||
_assertions(0)
|
||||
{
|
||||
}
|
||||
|
||||
UnitTest::~UnitTest()
|
||||
{
|
||||
}
|
||||
|
||||
void UnitTest::print_results()
|
||||
{
|
||||
if (_tests_failed) {
|
||||
PX4_ERR("SOME TESTS FAILED");
|
||||
|
||||
} else {
|
||||
PX4_INFO("ALL TESTS PASSED");
|
||||
}
|
||||
|
||||
PX4_INFO(" Tests passed : %d", _tests_passed);
|
||||
PX4_INFO(" Tests failed : %d", _tests_failed);
|
||||
PX4_INFO(" Tested assertions : %d", _assertions);
|
||||
}
|
||||
|
||||
/// @brief Used internally to the ut_assert macro to print assert failures.
|
||||
void UnitTest::_print_assert(const char *msg, const char *test, const char *file, int line)
|
||||
{
|
||||
PX4_ERR("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
|
||||
}
|
||||
|
||||
/// @brief Used internally to the ut_compare macro to print assert failures.
|
||||
void UnitTest::_print_compare(const char *msg, const char *v1_text, int v1, const char *v2_text, int v2,
|
||||
const char *file, int line)
|
||||
{
|
||||
PX4_ERR("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
|
||||
}
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <geo/geo.h>
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
#include <math.h>
|
||||
#include <float.h>
|
||||
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
#include <px4iofirmware/protocol.h>
|
||||
|
||||
int test_conv(int argc, char *argv[])
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <cfloat>
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <systemlib/hysteresis/hysteresis.h>
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <matrix/math.hpp>
|
||||
#include <matrix/filter.hpp>
|
||||
|
|
|
@ -64,7 +64,7 @@
|
|||
|
||||
#include "tests_main.h"
|
||||
|
||||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
static int mixer_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#include <unit_test/unit_test.h>
|
||||
#include <unit_test.h>
|
||||
|
||||
class ParameterTest : public UnitTest
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue