mirror of https://github.com/ArduPilot/ardupilot
Tools: factor out common library for GSOF
* Add tests too Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
921ef6cd36
commit
724e61fa70
|
@ -38,6 +38,7 @@ COMMON_VEHICLE_DEPENDENT_LIBRARIES = [
|
||||||
'AP_Compass',
|
'AP_Compass',
|
||||||
'AP_Declination',
|
'AP_Declination',
|
||||||
'AP_GPS',
|
'AP_GPS',
|
||||||
|
'AP_GSOF',
|
||||||
'AP_HAL',
|
'AP_HAL',
|
||||||
'AP_HAL_Empty',
|
'AP_HAL_Empty',
|
||||||
'AP_InertialSensor',
|
'AP_InertialSensor',
|
||||||
|
|
|
@ -23,6 +23,7 @@ class AStyleChecker(object):
|
||||||
self.directories_to_check = [
|
self.directories_to_check = [
|
||||||
'libraries/AP_DDS',
|
'libraries/AP_DDS',
|
||||||
'libraries/AP_ExternalControl',
|
'libraries/AP_ExternalControl',
|
||||||
|
'libraries/AP_GSOF',
|
||||||
]
|
]
|
||||||
self.files_to_check = [
|
self.files_to_check = [
|
||||||
pathlib.Path(s) for s in [
|
pathlib.Path(s) for s in [
|
||||||
|
|
|
@ -157,7 +157,8 @@ AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, con
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const {
|
AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const
|
||||||
|
{
|
||||||
switch(com_port) {
|
switch(com_port) {
|
||||||
case static_cast<uint8_t>(HW_Port::COM1):
|
case static_cast<uint8_t>(HW_Port::COM1):
|
||||||
case static_cast<uint8_t>(HW_Port::COM2):
|
case static_cast<uint8_t>(HW_Port::COM2):
|
||||||
|
@ -168,7 +169,8 @@ AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
AP_GPS_GSOF::pack_state_data() {
|
AP_GPS_GSOF::pack_state_data()
|
||||||
|
{
|
||||||
// TODO should we pack time data if there is no fix?
|
// TODO should we pack time data if there is no fix?
|
||||||
state.time_week_ms = pos_time.time_week_ms;
|
state.time_week_ms = pos_time.time_week_ms;
|
||||||
state.time_week = pos_time.time_week;
|
state.time_week = pos_time.time_week;
|
||||||
|
|
|
@ -0,0 +1,3 @@
|
||||||
|
# GSOF Tests
|
||||||
|
|
||||||
|
A UDP packet of binary GSOF data is attached in the `gsof_data` file.
|
Binary file not shown.
|
@ -7,20 +7,34 @@
|
||||||
|
|
||||||
#include <AP_GSOF/AP_GSOF.h>
|
#include <AP_GSOF/AP_GSOF.h>
|
||||||
|
|
||||||
|
#include <cstdio>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
|
|
||||||
TEST(AP_GSOF, incomplete_packet)
|
TEST(AP_GSOF, incomplete_packet)
|
||||||
{
|
{
|
||||||
AP_GSOF gsof;
|
AP_GSOF gsof;
|
||||||
EXPECT_FALSE(gsof.parse(0));
|
EXPECT_FALSE(gsof.parse(0, 5));
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(AP_GSOF, packet1)
|
TEST(AP_GSOF, packet1)
|
||||||
{
|
{
|
||||||
// 02084072580000010a1e02e0680909009400000218000000000000000000000000000000000000000000000000080d000000000000000000000000000910000000000000000000000000000000000c260000000000000000000000000000000000000000000000000000000000000000000000000000a503
|
FILE* fp = std::fopen("libraries/AP_GSOF/tests/gsof_gps.dat", "rb");
|
||||||
|
EXPECT_NE(fp, nullptr);
|
||||||
AP_GSOF gsof;
|
AP_GSOF gsof;
|
||||||
EXPECT_FALSE(gsof.parse(0));
|
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()
|
AP_GTEST_MAIN()
|
||||||
|
|
Loading…
Reference in New Issue