ardupilot/libraries/AP_GPS/tests/test_gps.cpp

66 lines
2.2 KiB
C++
Raw Normal View History

/*
* Copyright (C) 2016 Intel Corporation. All rights reserved.
*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#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;
/* Positive numbers with possible round/truncate */
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"));
/* Positive numbers with possible round/truncate with + signal */
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"));
/* Positive numbers in (0, 1) range, with possible round/truncate */
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"));
/* Negative numbers with possible round/truncate */
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"));
/* Integer numbers */
ASSERT_EQ(100, test.parse_decimal_100("1"));
ASSERT_EQ(-100, test.parse_decimal_100("-1"));
}
AP_GTEST_MAIN()