AP_Common: add more unitttests

This commit is contained in:
Pierre Kancir 2021-06-19 17:04:17 +02:00 committed by Peter Barker
parent ece3cf5241
commit 983e402804
11 changed files with 348 additions and 7 deletions

View File

@ -237,6 +237,7 @@ class CoverageRunner(object):
root_dir + "/build/sitl_periph_gps/libraries/*",
root_dir + "/build/sitl_periph_gps/modules/*",
root_dir + "/libraries/*/examples/*",
root_dir + "/libraries/*/tests/*",
"-o", self.INFO_FILE
], stdout=tmp_file, stderr=subprocess.STDOUT, text=True, check=True)
if self.verbose:

View File

@ -184,7 +184,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
ret_alt_cm = alt_abs - alt_terr_cm;
return true;
}
return false;
return false; // LCOV_EXCL_LINE - not reachable
}
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const

View File

@ -1,15 +1,20 @@
#include <AP_gtest.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/Bitmask.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
TEST(Bitmask, Tests)
{
Bitmask<49> x;
EXPECT_EQ(0, x.count());
EXPECT_EQ(-1, x.first_set());
x.set(5);
EXPECT_EQ(1, x.count());
EXPECT_EQ(5, x.first_set());
x.clear(5);
EXPECT_EQ(0, x.count());
EXPECT_EQ(-1, x.first_set());
EXPECT_EQ(-1, x.first_set());
@ -23,6 +28,7 @@ TEST(Bitmask, Tests)
x.set(5);
x.set(6);
x.set(48);
EXPECT_EQ(4, x.count());
EXPECT_EQ(0, x.first_set());
EXPECT_EQ(0, x.first_set());
x.clear(0);
@ -36,6 +42,13 @@ TEST(Bitmask, Tests)
EXPECT_EQ(48, x.first_set());
x.clear(48);
EXPECT_EQ(-1, x.first_set());
Bitmask<49> x2;
x2 = x;
x.set(50);
for (uint8_t i=0; i<50; i++) {
EXPECT_EQ(x2.get(i), x.get(i));
}
}
TEST(Bitmask, SetAll)
@ -75,5 +88,3 @@ TEST(Bitmask, Assignment)
}
AP_GTEST_MAIN()
int hal = 0; // bizarrely, this fixes an undefined-symbol error but doesn't raise a type exception. Yay.

View File

@ -0,0 +1,35 @@
#include <AP_gtest.h>
int hal = 0;
class DummyDummy {
public:
double d = 42.0;
uint8_t count = 1;
};
TEST(AP_Common, TEST_CPP)
{
DummyDummy * test_new = new DummyDummy[0];
EXPECT_FALSE(test_new == nullptr);
EXPECT_TRUE(sizeof(test_new) == 8);
EXPECT_EQ(test_new->count, 0);
EXPECT_FLOAT_EQ(test_new->d, 0);
DummyDummy * test_d = (DummyDummy*) ::operator new (0);
EXPECT_FALSE(test_d == nullptr);
EXPECT_TRUE(sizeof(test_d) == 8);
EXPECT_EQ(test_d->count, 0);
EXPECT_FLOAT_EQ(test_d->d, 0);
DummyDummy * test_d2 = new DummyDummy;
EXPECT_TRUE(sizeof(test_d2) == 8);
EXPECT_EQ(test_d2->count, 1);
EXPECT_FLOAT_EQ(test_d2->d, 42.0);
delete[] test_new;
delete test_d;
delete test_d2;
}
AP_GTEST_MAIN()

View File

@ -12,6 +12,12 @@ TEST(ExpandingString, Tests)
EXPECT_EQ(5u, test_string->get_length());
EXPECT_FALSE(test_string->has_failed_allocation());
EXPECT_TRUE(test_string->append("Test2\n", 6));
test_string->~ExpandingString();
EXPECT_STRNE("Test\n", test_string->get_string());
test_string = new ExpandingString();
char long_string[2048];
std::fill(std::begin(long_string),std::end(long_string),'a');
test_string->printf("%s", long_string);
}
AP_GTEST_MAIN()

View File

@ -0,0 +1,115 @@
#include <AP_gtest.h>
#include <stdlib.h>
#include <AP_Common/ExpandingString.h>
/**
* This file test realloc failure on ExpandingString
*/
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static uint32_t count = 0;
void *realloc(void *ptr, size_t new_size) {
count++;
if (count < 3) {
if (new_size == 0) {
free(ptr);
return nullptr;
}
if (ptr == nullptr) {
return malloc(new_size);
}
void *new_mem = malloc(new_size);
if (new_mem != nullptr) {
memcpy(new_mem, ptr, new_size);
free(ptr);
}
return new_mem;
} else {
return nullptr;
}
}
// THAT IS UGLY HACK BUT IT WORKS ... it is just used to make print_vprintf return negative value.
class BufferPrinter : public AP_HAL::BetterStream {
public:
BufferPrinter(char* str, size_t size) :
_offs(0), _str(str), _size(size) {}
size_t write(uint8_t c) override { return 1; }
size_t write(const uint8_t *buffer, size_t size) override { return 1; }
size_t _offs;
char* const _str;
const size_t _size;
uint32_t available() override { return 0; }
int16_t read() override { return -1; }
uint32_t txspace() override { return 0; }
bool discard_input() override { return false; }
};
void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) {
BufferPrinter* p = static_cast<BufferPrinter*>(s);
if (count < 2) {
p->_offs = -1;
return;
}
if (count == 2) {
p->_offs = p->_size * 2;
} else {
p->_offs = p->_size;
}
return;
}
TEST(ExpandingString, Tests)
{
// Test print_vprintf failure.
ExpandingString *test_string = new ExpandingString();
test_string->printf("Test\n");
EXPECT_STREQ("", test_string->get_string());
EXPECT_STREQ("", test_string->get_writeable_string());
EXPECT_EQ(0u, test_string->get_length());
EXPECT_FALSE(test_string->has_failed_allocation());
// test failure on second printf expand()
test_string = new ExpandingString();
test_string->printf("Test\n");
EXPECT_STREQ("", test_string->get_string());
EXPECT_STREQ("", test_string->get_writeable_string());
EXPECT_EQ(0u, test_string->get_length());
EXPECT_TRUE(test_string->has_failed_allocation());
// Test realloc failure
test_string = new ExpandingString();
test_string->printf("Test\n");
EXPECT_STREQ(nullptr, test_string->get_string());
EXPECT_STREQ(nullptr, test_string->get_writeable_string());
EXPECT_EQ(0u, test_string->get_length());
EXPECT_TRUE(test_string->has_failed_allocation());
// test append failure
EXPECT_FALSE(test_string->append("Test2\n", 6));
// test failure on first printf realloc
test_string->printf("Test\n");
EXPECT_STREQ(nullptr, test_string->get_string());
EXPECT_STREQ(nullptr, test_string->get_writeable_string());
EXPECT_EQ(0u, test_string->get_length());
EXPECT_TRUE(test_string->has_failed_allocation());
// test failure on append realloc
test_string = new ExpandingString();
EXPECT_FALSE(test_string->append("Test2\n", 6));
EXPECT_TRUE(test_string->has_failed_allocation());
EXPECT_STREQ(nullptr, test_string->get_string());
EXPECT_EQ(0u, test_string->get_length());
test_string->~ExpandingString();
EXPECT_STRNE("Test\n", test_string->get_string());
}
TEST(ExpandingString, TestsFailure)
{
}
AP_GTEST_MAIN()

View File

@ -0,0 +1,32 @@
#include <AP_gtest.h>
#include <AP_Common/AP_FWVersion.h>
#include <GCS_MAVLink/GCS_Dummy.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
TEST(AP_FWVersion, FWVersion)
{
EXPECT_EQ(AP::fwversion().header, 0x61706677766572fbu);
EXPECT_EQ(AP::fwversion().header_version, 0x0100U);
EXPECT_EQ(AP::fwversion().pointer_size, static_cast<uint8_t>(sizeof(void*)));
EXPECT_EQ(AP::fwversion().reserved, 0);
EXPECT_EQ(AP::fwversion().vehicle_type, static_cast<uint8_t>(APM_BUILD_DIRECTORY));
EXPECT_EQ(AP::fwversion().board_type, static_cast<uint8_t>(CONFIG_HAL_BOARD));
EXPECT_EQ(AP::fwversion().board_subtype, static_cast<uint16_t>(CONFIG_HAL_BOARD_SUBTYPE));
EXPECT_EQ(AP::fwversion().major, FW_MAJOR);
EXPECT_EQ(AP::fwversion().minor, FW_MINOR);
EXPECT_EQ(AP::fwversion().patch, FW_PATCH);
EXPECT_EQ(AP::fwversion().fw_type, FW_TYPE);
EXPECT_EQ(AP::fwversion().os_sw_version, 0u);
EXPECT_STREQ(AP::fwversion().fw_string, THISFIRMWARE);
EXPECT_STREQ(AP::fwversion().fw_hash_str, "");
EXPECT_STREQ(AP::fwversion().fw_short_string, THISFIRMWARE);
EXPECT_EQ(AP::fwversion().middleware_name, nullptr);
EXPECT_EQ(AP::fwversion().middleware_hash_str, nullptr);
EXPECT_EQ(AP::fwversion().os_name, nullptr);
EXPECT_EQ(AP::fwversion().os_hash_str, nullptr);
}
AP_GTEST_MAIN()

View File

@ -4,7 +4,7 @@
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Terrain/AP_Terrain.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
int hal = 0;
class DummyAHRS: AP_AHRS_NavEKF {

View File

@ -0,0 +1,45 @@
#include <AP_gtest.h>
#include <AP_HAL/UARTDriver.h>
#include <AP_Common/NMEA.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
class DummyUart: public AP_HAL::UARTDriver {
public:
void begin(uint32_t baud) override { };
void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
void end() override { };
void flush() override { };
bool is_initialized() override { return true; };
void set_blocking_writes(bool blocking) override { };
bool tx_pending() override { return false; };
uint32_t available() override { return 1; };
uint32_t txspace() override { return _txspace; };
int16_t read() override { return 1; };
bool discard_input() override { return true; };
size_t write(uint8_t c) override { return 1; };
size_t write(const uint8_t *buffer, size_t size) override { return 1; };
void set_txspace(uint32_t space) {
_txspace = space;
}
uint32_t _txspace;
};
static DummyUart test_uart;
TEST(NMEA, Printf)
{
EXPECT_FALSE(nmea_printf(&test_uart, ""));
char test_string[] = "test\n"; // blabla not an NMEA string but whatever
const size_t len = strlen(test_string);
// test not enought space
test_uart.set_txspace(len-2);
EXPECT_FALSE(nmea_printf(&test_uart, test_string));
// normal test
test_uart.set_txspace(42);
EXPECT_TRUE(nmea_printf(&test_uart, test_string));
}
AP_GTEST_MAIN()

View File

@ -0,0 +1,79 @@
#include <AP_gtest.h>
#include <AP_HAL/UARTDriver.h>
#include <AP_Common/NMEA.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static uint32_t count = 0;
void *malloc(size_t size) {
if (count == 1) {
return nullptr;
}
return calloc(size, 1);
}
// THAT IS UGLY HACK BUT IT WORKS ... it is just used to make print_vprintf return negative value.
class BufferPrinter : public AP_HAL::BetterStream {
public:
BufferPrinter(char* str, size_t size) :
_offs(0), _str(str), _size(size) {}
size_t write(uint8_t c) override { return 1; }
size_t write(const uint8_t *buffer, size_t size) override { return 1; }
size_t _offs;
char* const _str;
const size_t _size;
uint32_t available() override { return 0; }
int16_t read() override { return -1; }
uint32_t txspace() override { return 0; }
bool discard_input() override { return false; }
};
void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) {
BufferPrinter* p = static_cast<BufferPrinter*>(s);
count++;
if (count < 3) {
p->_offs = 4;
return;
}
p->_offs = -1;
return;
}
class DummyUart: public AP_HAL::UARTDriver {
public:
void begin(uint32_t baud) override { };
void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) override { };
void end() override { };
void flush() override { };
bool is_initialized() override { return true; };
void set_blocking_writes(bool blocking) override { };
bool tx_pending() override { return false; };
uint32_t available() override { return 1; };
uint32_t txspace() override { return _txspace; };
int16_t read() override { return 1; };
bool discard_input() override { return true; };
size_t write(uint8_t c) override { return 1; };
size_t write(const uint8_t *buffer, size_t size) override { return 1; };
void set_txspace(uint32_t space) {
_txspace = space;
}
uint32_t _txspace;
};
static DummyUart test_uart;
TEST(NMEA, VAPrintf)
{
// test Malloc failure
EXPECT_FALSE(nmea_printf(&test_uart, "test"));
// test second vsnprintf failure;
EXPECT_FALSE(nmea_printf(&test_uart, "test"));
// test first vsnprintf failure;
EXPECT_FALSE(nmea_printf(&test_uart, "test"));
}
AP_GTEST_MAIN()

View File

@ -1,11 +1,10 @@
#include <AP_gtest.h>
#include <AP_Common/TSIndex.h>
DECLARE_TYPESAFE_INDEX(testTSIndex, uint8_t);
TEST(TSIndex, operators)
{
DECLARE_TYPESAFE_INDEX(testTSIndex, uint8_t);
testTSIndex test_value = testTSIndex();
EXPECT_EQ(0, test_value.get_int());
uint8_t test_eq = 1;
@ -33,4 +32,22 @@ TEST(TSIndex, operators)
EXPECT_EQ(test_eq, uint8_t(test_value));
}
TEST(TSIndex, RestrictIDArray)
{
testTSIndex i_0(0);
testTSIndex i_1(1);
RestrictIDTypeArray<int32_t , 2, testTSIndex> state{};
EXPECT_EQ(state[i_0], 0);
EXPECT_EQ(state[i_1], 0);
state[i_1] = 42;
EXPECT_EQ(state[i_1], 42);
const int32_t state_1 = state[i_1];
EXPECT_EQ(state_1, state[i_1]);
EXPECT_NE(state_1, state[i_0]);
const RestrictIDTypeArray<int32_t , 2, testTSIndex> state_const{42, 43};
EXPECT_TRUE(state_const[i_0] == 42);
EXPECT_TRUE(state_const[i_1] == 43);
}
AP_GTEST_MAIN()