// Tests for the GSOF parser. // * ./waf tests // * ./build/sitl/tests/test_gsof #include #include #include #include const AP_HAL::HAL &hal = AP_HAL::get_HAL(); TEST(AP_GSOF, incomplete_packet) { AP_GSOF gsof; EXPECT_FALSE(gsof.parse(0, 5)); } TEST(AP_GSOF, packet1) { GTEST_SKIP() << "There is not yet a convention for loading in a data file in a cross-platform way in AP for unit tests"; FILE* fp = std::fopen("libraries/AP_GSOF/tests/gsof_gps.dat", "rb"); EXPECT_NE(fp, nullptr); AP_GSOF gsof; char c = 0; bool parsed = false; while (c != EOF) { c = fgetc (fp); parsed |= gsof.parse((uint8_t)c, 5); } EXPECT_TRUE(parsed); fclose(fp); } AP_GTEST_MAIN()