novatel_gps_tests.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
31 
32 #include <gtest/gtest.h>
33 
34 #include <ros/ros.h>
35 #include <ros/package.h>
36 
37 TEST(NovatelGpsTestSuite, testGpsFixParsing)
38 {
40 
41  std::string path = ros::package::getPath("novatel_gps_driver");
42  gps.wait_for_sync_ = true;
43 
44  ASSERT_TRUE(gps.Connect(path + "/test/bestpos-bestvel-psrdop2-sync.pcap",
46 
47  std::vector<gps_common::GPSFixPtr> fix_messages;
48 
50  {
51  std::vector<gps_common::GPSFixPtr> tmp_messages;
52  gps.GetFixMessages(tmp_messages);
53  fix_messages.insert(fix_messages.end(), tmp_messages.begin(), tmp_messages.end());
54  }
55 
56  ASSERT_EQ(22, fix_messages.size());
57 
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);
63 }
64 
65 TEST(NovatelGpsTestSuite, testCorrImuDataParsing)
66 {
68 
69  std::string path = ros::package::getPath("novatel_gps_driver");
70  ASSERT_TRUE(gps.Connect(path + "/test/corrimudata.pcap", novatel_gps_driver::NovatelGps::PCAP));
71 
72  std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> imu_messages;
73 
75  {
76  std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> tmp_messages;
77  gps.GetNovatelCorrectedImuData(tmp_messages);
78  imu_messages.insert(imu_messages.end(), tmp_messages.begin(), tmp_messages.end());
79  }
80 
81  ASSERT_EQ(26, imu_messages.size());
82 
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);
92 }
93 
94 int main(int argc, char **argv)
95 {
96  ros::init(argc, argv, "novatel_gps_test_suite", ros::init_options::AnonymousName);
97  ros::NodeHandle nh;
98 
99  testing::InitGoogleTest(&argc, argv);
100 
101  return RUN_ALL_TESTS();
102 }
msg
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)
Definition: novatel_gps.cpp:89


novatel_gps_driver
Author(s):
autogenerated on Thu Jul 16 2020 03:17:30