32 #include <gtest/gtest.h> 37 TEST(NovatelGpsTestSuite, testGpsFixParsing)
44 ASSERT_TRUE(gps.
Connect(path +
"/test/bestpos-bestvel-psrdop2-sync.pcap",
47 std::vector<gps_common::GPSFixPtr> fix_messages;
51 std::vector<gps_common::GPSFixPtr> tmp_messages;
53 fix_messages.insert(fix_messages.end(), tmp_messages.begin(), tmp_messages.end());
56 ASSERT_EQ(22, fix_messages.size());
58 EXPECT_DOUBLE_EQ(fix_messages.front()->latitude, 29.443917634921949);
59 EXPECT_DOUBLE_EQ(fix_messages.front()->longitude, -98.614755510637181);
60 EXPECT_DOUBLE_EQ(fix_messages.front()->speed, 0.041456376659522925);
61 EXPECT_DOUBLE_EQ(fix_messages.front()->track, 135.51629763185957);
62 EXPECT_DOUBLE_EQ(fix_messages.front()->gdop, 1.9980000257492065);
65 TEST(NovatelGpsTestSuite, testCorrImuDataParsing)
72 std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> imu_messages;
76 std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> tmp_messages;
78 imu_messages.insert(imu_messages.end(), tmp_messages.begin(), tmp_messages.end());
81 ASSERT_EQ(26, imu_messages.size());
83 novatel_gps_msgs::NovatelCorrectedImuDataPtr
msg = imu_messages.front();
84 EXPECT_EQ(1820, msg->gps_week_num);
85 EXPECT_DOUBLE_EQ(160205.899999999994, msg->gps_seconds);
86 EXPECT_DOUBLE_EQ(0.0000039572689929003956, msg->pitch_rate);
87 EXPECT_DOUBLE_EQ(0.0000028926313702935847, msg->roll_rate);
88 EXPECT_DOUBLE_EQ(0.0000027924848999730557, msg->yaw_rate);
89 EXPECT_DOUBLE_EQ(-0.00062560456243879322, msg->lateral_acceleration);
90 EXPECT_DOUBLE_EQ(0.00034037959880710289, msg->longitudinal_acceleration);
91 EXPECT_DOUBLE_EQ(-0.0000051257464089797534, msg->vertical_acceleration);
94 int main(
int argc,
char **argv)
99 testing::InitGoogleTest(&argc, argv);
101 return RUN_ALL_TESTS();
void GetFixMessages(std::vector< gps_common::GPSFixPtr > &fix_messages)
Provides any GPSFix messages that have been generated since the last time this was called...
TEST(NovatelGpsTestSuite, testGpsFixParsing)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void GetNovatelCorrectedImuData(std::vector< novatel_gps_msgs::NovatelCorrectedImuDataPtr > &imu_messages)
Provides any CORRIMUDATA messages that have been received since the last time this was called...
ReadResult ProcessData()
Processes any data that has been received from the device since the last time this message was called...
ROSLIB_DECL std::string getPath(const std::string &package_name)
bool Connect(const std::string &device, ConnectionType connection)