Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
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 }