mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Move the unit test framework out of the unit tests. Add unit tests for the k_typeid_* constants.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1543 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
27c36583d0
commit
d38874cd05
@ -4,6 +4,7 @@
|
|||||||
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Test.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
// we need to do this, even though normally it's a bad idea
|
// we need to do this, even though normally it's a bad idea
|
||||||
@ -11,61 +12,6 @@
|
|||||||
|
|
||||||
FastSerialPort(Serial, 0);
|
FastSerialPort(Serial, 0);
|
||||||
|
|
||||||
//
|
|
||||||
// Unit test framework
|
|
||||||
//
|
|
||||||
class Test
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
Test(const char *name);
|
|
||||||
~Test();
|
|
||||||
void require(bool expr, const char *source);
|
|
||||||
static void report();
|
|
||||||
|
|
||||||
private:
|
|
||||||
const char *_name;
|
|
||||||
bool _fail;
|
|
||||||
static int _passed;
|
|
||||||
static int _failed;
|
|
||||||
};
|
|
||||||
|
|
||||||
Test::Test(const char *name) :
|
|
||||||
_name(name),
|
|
||||||
_fail(false)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
Test::~Test()
|
|
||||||
{
|
|
||||||
Serial.printf("%s: %s\n", _fail ? "FAILED" : "passed", _name);
|
|
||||||
if (_fail) {
|
|
||||||
_failed++;
|
|
||||||
} else {
|
|
||||||
_passed++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
Test::require(bool expr, const char *source)
|
|
||||||
{
|
|
||||||
if (!expr) {
|
|
||||||
_fail = true;
|
|
||||||
Serial.printf("%s: fail: %s\n", _name, source);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
Test::report()
|
|
||||||
{
|
|
||||||
Serial.printf("\n%d passed %d failed\n", _passed, _failed);
|
|
||||||
}
|
|
||||||
|
|
||||||
int Test::_passed = 0;
|
|
||||||
int Test::_failed = 0;
|
|
||||||
|
|
||||||
#define TEST(name) Test _test(#name)
|
|
||||||
#define REQUIRE(expr) _test.require(expr, #expr)
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// Unit tests
|
// Unit tests
|
||||||
//
|
//
|
||||||
@ -140,6 +86,25 @@ setup(void)
|
|||||||
REQUIRE(AP_Float_negative_unity = -1.0);
|
REQUIRE(AP_Float_negative_unity = -1.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// AP_Var: type IDs
|
||||||
|
{
|
||||||
|
TEST(var_type_ids);
|
||||||
|
|
||||||
|
AP_Float f;
|
||||||
|
AP_Float16 fs;
|
||||||
|
AP_Int32 l;
|
||||||
|
AP_Int16 s;
|
||||||
|
AP_Int8 b;
|
||||||
|
|
||||||
|
REQUIRE(f.meta_type_id() == AP_Var::k_typeid_float);
|
||||||
|
REQUIRE(fs.meta_type_id() == AP_Var::k_typeid_float16);
|
||||||
|
REQUIRE(l.meta_type_id() == AP_Var::k_typeid_int32);
|
||||||
|
REQUIRE(s.meta_type_id() == AP_Var::k_typeid_int16);
|
||||||
|
REQUIRE(b.meta_type_id() == AP_Var::k_typeid_int8);
|
||||||
|
|
||||||
|
REQUIRE(AP_Var::k_typeid_float != AP_Var::k_typeid_int32);
|
||||||
|
}
|
||||||
|
|
||||||
// AP_Var: initial value
|
// AP_Var: initial value
|
||||||
{
|
{
|
||||||
TEST(var_initial_value);
|
TEST(var_initial_value);
|
||||||
|
Loading…
Reference in New Issue
Block a user