test_gnss.cpp 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include <ros/ros.h>
  17. #include <gtest/gtest.h>
  18. #include "gnss/geo_pos_conv.hpp"
  19. TEST(TestSuite, llhNmeaDegreesTest)
  20. {
  21. geo_pos_conv geo_;
  22. geo_.set_llh_nmea_degrees(0.000000, 0.000000, 10.124025);
  23. ASSERT_FLOAT_EQ(0.000000, geo_.geo_pos_conv::x());
  24. ASSERT_FLOAT_EQ(0.000000, geo_.geo_pos_conv::y());
  25. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  26. geo_.set_llh_nmea_degrees(1.000000, 1.000000, 10.124025);
  27. ASSERT_FLOAT_EQ(1842.720386, geo_.geo_pos_conv::x());
  28. ASSERT_FLOAT_EQ(1855.139262, geo_.geo_pos_conv::y());
  29. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  30. geo_.set_llh_nmea_degrees(-1.000000, -1.000000, 10.124025);
  31. ASSERT_FLOAT_EQ(-1842.720386, geo_.geo_pos_conv::x());
  32. ASSERT_FLOAT_EQ(-1855.139262, geo_.geo_pos_conv::y());
  33. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  34. geo_.set_llh_nmea_degrees(10.000000, 10.000000, 10.124025);
  35. ASSERT_FLOAT_EQ(18427.282074, geo_.geo_pos_conv::x());
  36. ASSERT_FLOAT_EQ(18551.341517, geo_.geo_pos_conv::y());
  37. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  38. geo_.set_llh_nmea_degrees(-10.000000, -10.000000, 10.124025);
  39. ASSERT_FLOAT_EQ(-18427.282074, geo_.geo_pos_conv::x());
  40. ASSERT_FLOAT_EQ(-18551.341517, geo_.geo_pos_conv::y());
  41. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  42. geo_.set_llh_nmea_degrees(100.000000, 100.000000, 10.124025);
  43. ASSERT_FLOAT_EQ(110580.283099, geo_.geo_pos_conv::x());
  44. ASSERT_FLOAT_EQ(111297.204780, geo_.geo_pos_conv::y());
  45. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  46. geo_.set_llh_nmea_degrees(-100.000000, -100.000000, 10.124025);
  47. ASSERT_FLOAT_EQ(-110580.283099, geo_.geo_pos_conv::x());
  48. ASSERT_FLOAT_EQ(-111297.204780, geo_.geo_pos_conv::y());
  49. ASSERT_FLOAT_EQ(10.124025, geo_.geo_pos_conv::z());
  50. }
  51. int main(int argc, char **argv)
  52. {
  53. testing::InitGoogleTest(&argc, argv);
  54. ros::init(argc, argv, "test_gnss");
  55. return RUN_ALL_TESTS();
  56. }