mirror of https://github.com/ArduPilot/ardupilot
AP_Common: templatify bitmask tests
Enables testing of different widths and edge cases.
This commit is contained in:
parent
aff3af67e6
commit
521cf00964
|
@ -5,9 +5,10 @@
|
|||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
TEST(Bitmask, Tests)
|
||||
template<int N>
|
||||
void bitmask_tests(void)
|
||||
{
|
||||
Bitmask<49> x;
|
||||
Bitmask<N> x;
|
||||
EXPECT_EQ(0, x.count());
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
x.set(5);
|
||||
|
@ -18,16 +19,16 @@ TEST(Bitmask, Tests)
|
|||
EXPECT_EQ(-1, x.first_set());
|
||||
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
x.set(42);
|
||||
EXPECT_EQ(42, x.first_set());
|
||||
x.clear(42);
|
||||
x.set(N-7);
|
||||
EXPECT_EQ(N-7, x.first_set());
|
||||
x.clear(N-7);
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
x.set(0);
|
||||
x.set(5);
|
||||
x.set(6);
|
||||
x.set(48);
|
||||
x.set(N-1);
|
||||
EXPECT_EQ(4, x.count());
|
||||
EXPECT_EQ(0, x.first_set());
|
||||
EXPECT_EQ(0, x.first_set());
|
||||
|
@ -38,65 +39,82 @@ TEST(Bitmask, Tests)
|
|||
EXPECT_EQ(6, x.first_set());
|
||||
EXPECT_EQ(6, x.first_set());
|
||||
x.clear(6);
|
||||
EXPECT_EQ(48, x.first_set());
|
||||
EXPECT_EQ(48, x.first_set());
|
||||
x.clear(48);
|
||||
EXPECT_EQ(N-1, x.first_set());
|
||||
EXPECT_EQ(N-1, x.first_set());
|
||||
x.clear(N-1);
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
|
||||
Bitmask<49> x2;
|
||||
Bitmask<N> x2;
|
||||
x2 = x;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
x.set(50);
|
||||
x.set(N+1);
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
EXPECT_EXIT(x.set(50), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range");
|
||||
EXPECT_EXIT(x.set(N+1), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range");
|
||||
#endif
|
||||
|
||||
for (uint8_t i=0; i<49; i++) {
|
||||
for (uint8_t i=0; i<N; i++) {
|
||||
EXPECT_EQ(x2.get(i), x.get(i));
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
EXPECT_EQ(x2.get(50), x.get(50));
|
||||
EXPECT_EQ(x2.get(N+1), x.get(N+1));
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
EXPECT_EXIT(x2.get(50), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range");
|
||||
EXPECT_EXIT(x2.get(N+1), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bitmask_range");
|
||||
#endif
|
||||
}
|
||||
|
||||
TEST(Bitmask, SetAll)
|
||||
TEST(Bitmask, Tests)
|
||||
{
|
||||
Bitmask<49> x;
|
||||
bitmask_tests<49>();
|
||||
}
|
||||
|
||||
template<int N>
|
||||
void bitmask_setall(void)
|
||||
{
|
||||
Bitmask<N> x;
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
EXPECT_EQ(false, x.get(45));
|
||||
EXPECT_EQ(false, x.get(N-4));
|
||||
x.setall();
|
||||
EXPECT_EQ(0, x.first_set());
|
||||
x.clear(0);
|
||||
EXPECT_EQ(1, x.first_set());
|
||||
x.clear(1);
|
||||
EXPECT_EQ(2, x.first_set());
|
||||
EXPECT_EQ(true, x.get(45));
|
||||
EXPECT_EQ(true, x.get(N-4));
|
||||
EXPECT_EQ(false, x.empty());
|
||||
x.clearall();
|
||||
EXPECT_EQ(-1, x.first_set());
|
||||
EXPECT_EQ(false, x.get(45));
|
||||
EXPECT_EQ(false, x.get(N-4));
|
||||
EXPECT_EQ(true, x.empty());
|
||||
}
|
||||
|
||||
TEST(Bitmask, Assignment)
|
||||
TEST(Bitmask, SetAll)
|
||||
{
|
||||
Bitmask<49> x;
|
||||
bitmask_setall<49>();
|
||||
}
|
||||
|
||||
template<int N>
|
||||
void bitmask_assignment(void)
|
||||
{
|
||||
Bitmask<N> x;
|
||||
x.set(0);
|
||||
x.set(5);
|
||||
x.set(6);
|
||||
x.set(48);
|
||||
x.set(N-1);
|
||||
|
||||
Bitmask<49> y;
|
||||
Bitmask<N> y;
|
||||
y = x;
|
||||
x.clear(0);
|
||||
EXPECT_EQ(true, y.get(0));
|
||||
EXPECT_EQ(true, y.get(5));
|
||||
EXPECT_EQ(true, y.get(6));
|
||||
EXPECT_EQ(true, y.get(48));
|
||||
EXPECT_EQ(true, y.get(N-1));
|
||||
}
|
||||
|
||||
TEST(Bitmask, Assignment)
|
||||
{
|
||||
bitmask_assignment<49>();
|
||||
}
|
||||
|
||||
AP_GTEST_PANIC()
|
||||
|
|
Loading…
Reference in New Issue