novatel_gps_tests.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <novatel_gps_driver/novatel_gps.h>
00031 
00032 #include <gtest/gtest.h>
00033 
00034 #include <ros/ros.h>
00035 #include <ros/package.h>
00036 
00037 TEST(NovatelGpsTestSuite, testGpsFixParsing)
00038 {
00039   novatel_gps_driver::NovatelGps gps;
00040 
00041   std::string path = ros::package::getPath("novatel_gps_driver");
00042   ASSERT_TRUE(gps.Connect(path + "/test/gpgga-gprmc-bestpos.pcap", novatel_gps_driver::NovatelGps::PCAP));
00043 
00044   std::vector<gps_common::GPSFixPtr> fix_messages;
00045 
00046   while (gps.IsConnected() && gps.ProcessData() == novatel_gps_driver::NovatelGps::READ_SUCCESS)
00047   {
00048     std::vector<gps_common::GPSFixPtr> tmp_messages;
00049     gps.GetFixMessages(tmp_messages);
00050     fix_messages.insert(fix_messages.end(), tmp_messages.begin(), tmp_messages.end());
00051   }
00052 
00053   ASSERT_EQ(40, fix_messages.size());
00054 }
00055 
00056 TEST(NovatelGpsTestSuite, testCorrImuDataParsing)
00057 {
00058   novatel_gps_driver::NovatelGps gps;
00059 
00060   std::string path = ros::package::getPath("novatel_gps_driver");
00061   ASSERT_TRUE(gps.Connect(path + "/test/corrimudata.pcap", novatel_gps_driver::NovatelGps::PCAP));
00062 
00063   std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> imu_messages;
00064 
00065   while (gps.IsConnected() && gps.ProcessData() == novatel_gps_driver::NovatelGps::READ_SUCCESS)
00066   {
00067     std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> tmp_messages;
00068     gps.GetNovatelCorrectedImuData(tmp_messages);
00069     imu_messages.insert(imu_messages.end(), tmp_messages.begin(), tmp_messages.end());
00070   }
00071 
00072   ASSERT_EQ(26, imu_messages.size());
00073 
00074   novatel_gps_msgs::NovatelCorrectedImuDataPtr msg = imu_messages.front();
00075   EXPECT_EQ(1820, msg->gps_week_num);
00076   EXPECT_DOUBLE_EQ(160205.899999999994, msg->gps_seconds);
00077   EXPECT_DOUBLE_EQ(0.0000039572689929003956, msg->pitch_rate);
00078   EXPECT_DOUBLE_EQ(0.0000028926313702935847, msg->roll_rate);
00079   EXPECT_DOUBLE_EQ(0.0000027924848999730557, msg->yaw_rate);
00080   EXPECT_DOUBLE_EQ(-0.00062560456243879322, msg->lateral_acceleration);
00081   EXPECT_DOUBLE_EQ(0.00034037959880710289, msg->longitudinal_acceleration);
00082   EXPECT_DOUBLE_EQ(-0.0000051257464089797534, msg->vertical_acceleration);
00083 }
00084 
00085 int main(int argc, char **argv)
00086 {
00087   ros::init(argc, argv, "novatel_gps_test_suite", ros::init_options::AnonymousName);
00088   ros::NodeHandle nh;
00089 
00090   testing::InitGoogleTest(&argc, argv);
00091 
00092   return RUN_ALL_TESTS();
00093 }


novatel_gps_driver
Author(s):
autogenerated on Sun Oct 8 2017 02:40:29