1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465 |
- #include <AP_gtest.h>
- #include <AP_GPS/AP_GPS_NMEA.h>
- const AP_HAL::HAL &hal = AP_HAL::get_HAL();
- class AP_GPS_NMEA_Test
- {
- public:
- int32_t parse_decimal_100(const char *p) const
- {
- return AP_GPS_NMEA::_parse_decimal_100(p);
- }
- };
- TEST(AP_GPS_NMEA, parse_decimal_100)
- {
- AP_GPS_NMEA_Test test;
-
- ASSERT_EQ(100, test.parse_decimal_100("1.0"));
- ASSERT_EQ(100, test.parse_decimal_100("1.00"));
- ASSERT_EQ(100, test.parse_decimal_100("1.001"));
- ASSERT_EQ(101, test.parse_decimal_100("1.006"));
-
- ASSERT_EQ(100, test.parse_decimal_100("+1.0"));
- ASSERT_EQ(100, test.parse_decimal_100("+1.00"));
- ASSERT_EQ(100, test.parse_decimal_100("+1.001"));
- ASSERT_EQ(101, test.parse_decimal_100("+1.006"));
-
- ASSERT_EQ(0, test.parse_decimal_100("0.0"));
- ASSERT_EQ(0, test.parse_decimal_100("0.00"));
- ASSERT_EQ(0, test.parse_decimal_100("0.001"));
- ASSERT_EQ(1, test.parse_decimal_100("0.006"));
-
- ASSERT_EQ(-100, test.parse_decimal_100("-1.0"));
- ASSERT_EQ(-100, test.parse_decimal_100("-1.00"));
- ASSERT_EQ(-100, test.parse_decimal_100("-1.001"));
- ASSERT_EQ(-101, test.parse_decimal_100("-1.006"));
-
- ASSERT_EQ(100, test.parse_decimal_100("1"));
- ASSERT_EQ(-100, test.parse_decimal_100("-1"));
- }
- AP_GTEST_MAIN()
|