testGPSFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/base/Testable.h>
22 
24 
25 #include <GeographicLib/Config.h>
27 
28 using namespace std;
29 using namespace gtsam;
30 using namespace GeographicLib;
31 
32 #if GEOGRAPHICLIB_VERSION_MINOR<37
33 static const auto& kWGS84 = Geocentric::WGS84;
34 #else
35 static const auto& kWGS84 = Geocentric::WGS84();
36 #endif
37 
38 // *************************************************************************
39 namespace example {
40 // ENU Origin is where the plane was in hold next to runway
41 const double lat0 = 33.86998, lon0 = -84.30626, h0 = 274;
42 
43 // Convert from GPS to ENU
45 
46 // Dekalb-Peachtree Airport runway 2L
47 const double lat = 33.87071, lon = -84.30482, h = 274;
48 }
49 
50 // *************************************************************************
51 TEST( GPSFactor, Constructor ) {
52  using namespace example;
53 
54  // From lat-lon to geocentric
55  double E, N, U;
56  origin_ENU.Forward(lat, lon, h, E, N, U);
57  EXPECT_DOUBLES_EQUAL(133.24, E, 1e-2);
58  EXPECT_DOUBLES_EQUAL(80.98, N, 1e-2);
59  EXPECT_DOUBLES_EQUAL(0, U, 1e-2);
60 
61  // Factor
62  Key key(1);
63  SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25);
64  GPSFactor factor(key, Point3(E, N, U), model);
65 
66  // Create a linearization point at zero error
67  Pose3 T(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(E, N, U));
68  EXPECT(assert_equal(Z_3x1,factor.evaluateError(T),1e-5));
69 
70  // Calculate numerical derivatives
71  Matrix expectedH = numericalDerivative11<Vector,Pose3>(
72  boost::bind(&GPSFactor::evaluateError, &factor, _1, boost::none), T);
73 
74  // Use the factor to calculate the derivative
75  Matrix actualH;
76  factor.evaluateError(T, actualH);
77 
78  // Verify we get the expected error
79  EXPECT(assert_equal(expectedH, actualH, 1e-8));
80 }
81 
82 // *************************************************************************
83 TEST( GPSFactor2, Constructor ) {
84  using namespace example;
85 
86  // From lat-lon to geocentric
87  double E, N, U;
88  origin_ENU.Forward(lat, lon, h, E, N, U);
89 
90  // Factor
91  Key key(1);
92  SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25);
93  GPSFactor2 factor(key, Point3(E, N, U), model);
94 
95  // Create a linearization point at zero error
96  NavState T(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(E, N, U), Vector3::Zero());
97  EXPECT(assert_equal(Z_3x1,factor.evaluateError(T),1e-5));
98 
99  // Calculate numerical derivatives
100  Matrix expectedH = numericalDerivative11<Vector,NavState>(
101  boost::bind(&GPSFactor2::evaluateError, &factor, _1, boost::none), T);
102 
103  // Use the factor to calculate the derivative
104  Matrix actualH;
105  factor.evaluateError(T, actualH);
106 
107  // Verify we get the expected error
108  EXPECT(assert_equal(expectedH, actualH, 1e-8));
109 }
110 
111 //***************************************************************************
112 TEST(GPSData, init) {
113 
114  // GPS Reading 1 will be ENU origin
115  double t1 = 84831;
116  Point3 NED1(0, 0, 0);
117  LocalCartesian enu(35.4393283333333, -119.062986666667, 275.54, kWGS84);
118 
119  // GPS Readin 2
120  double t2 = 84831.5;
121  double E, N, U;
122  enu.Forward(35.4394633333333, -119.063146666667, 276.52, E, N, U);
123  Point3 NED2(N, E, -U);
124 
125  // Estimate initial state
126  Pose3 T;
127  Vector3 nV;
128  boost::tie(T, nV) = GPSFactor::EstimateState(t1, NED1, t2, NED2, 84831.0796);
129 
130  // Check values values
131  EXPECT(assert_equal((Vector )Vector3(29.9575, -29.0564, -1.95993), nV, 1e-4));
132  EXPECT( assert_equal(Rot3::Ypr(-0.770131, 0.046928, 0), T.rotation(), 1e-5));
133  Point3 expectedT(2.38461, -2.31289, -0.156011);
134  EXPECT(assert_equal(expectedT, T.translation(), 1e-5));
135 }
136 
137 // *************************************************************************
138 int main() {
139  TestResult tr;
140  return TestRegistry::runAllTests(tr);
141 }
142 // *************************************************************************
TEST(GPSFactor, Constructor)
Key E(std::uint64_t j)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Header for GeographicLib::LocalCartesian class.
static const double lat
noiseModel::Diagonal::shared_ptr model
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
const double h0
static const auto & kWGS84
Definition: Half.h:150
Some functions to compute numerical derivatives.
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
#define N
Definition: gksort.c:12
LocalCartesian origin_ENU(lat0, lon0, h0, kWGS84)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
Point2 expectedT(-0.0446635, 0.29552)
Header file for GPS factor.
Eigen::VectorXd Vector
Definition: Vector.h:38
Vector evaluateError(const NavState &p, boost::optional< Matrix & > H=boost::none) const override
vector of errors
Definition: GPSFactor.cpp:82
const double lat0
#define EXPECT(condition)
Definition: Test.h:151
Eigen::Triplet< double > T
Namespace for GeographicLib.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const double lon0
Local cartesian coordinates.
int main()
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
const double h
void Forward(real lat, real lon, real h, real &x, real &y, real &z) const
Vector evaluateError(const Pose3 &p, boost::optional< Matrix & > H=boost::none) const override
vector of errors
Definition: GPSFactor.cpp:40
static const double lon
Vector3 Point3
Definition: Point3.h:35
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:11