GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
GPSFactor.h
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 
18 #pragma once
19 
22 #include <gtsam/geometry/Pose3.h>
23 
24 namespace gtsam {
25 
35 class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3> {
36 
37 private:
38 
40 
41  Point3 nT_;
42 
43 public:
44 
45  // Provide access to the Matrix& version of evaluateError:
46  using Base::evaluateError;
47 
49  typedef std::shared_ptr<GPSFactor> shared_ptr;
50 
52  typedef GPSFactor This;
53 
55  GPSFactor(): nT_(0, 0, 0) {}
56 
57  ~GPSFactor() override {}
58 
66  GPSFactor(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
67  Base(model, key), nT_(gpsIn) {
68  }
69 
71  gtsam::NonlinearFactor::shared_ptr clone() const override {
72  return std::static_pointer_cast<gtsam::NonlinearFactor>(
73  gtsam::NonlinearFactor::shared_ptr(new This(*this)));
74  }
75 
77  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
78  DefaultKeyFormatter) const override;
79 
81  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
82 
84  Vector evaluateError(const Pose3& p, OptionalMatrixType H) const override;
85 
86  inline const Point3 & measurementIn() const {
87  return nT_;
88  }
89 
95  static std::pair<Pose3, Vector3> EstimateState(double t1, const Point3& NED1,
96  double t2, const Point3& NED2, double timestamp);
97 
98 private:
99 
100 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
101  friend class boost::serialization::access;
103  template<class ARCHIVE>
104  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
105  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
106  ar
107  & boost::serialization::make_nvp("NoiseModelFactor1",
108  boost::serialization::base_object<Base>(*this));
109  ar & BOOST_SERIALIZATION_NVP(nT_);
110  }
111 #endif
112 };
113 
118 class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN<NavState> {
119 
120 private:
121 
123 
124  Point3 nT_;
125 
126 public:
127 
128  // Provide access to the Matrix& version of evaluateError:
129  using Base::evaluateError;
130 
132  typedef std::shared_ptr<GPSFactor2> shared_ptr;
133 
135  typedef GPSFactor2 This;
136 
138  GPSFactor2():nT_(0, 0, 0) {}
139 
140  ~GPSFactor2() override {}
141 
143  GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
144  Base(model, key), nT_(gpsIn) {
145  }
146 
148  gtsam::NonlinearFactor::shared_ptr clone() const override {
149  return std::static_pointer_cast<gtsam::NonlinearFactor>(
150  gtsam::NonlinearFactor::shared_ptr(new This(*this)));
151  }
152 
154  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
155  DefaultKeyFormatter) const override;
156 
158  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
159 
161  Vector evaluateError(const NavState& p, OptionalMatrixType H) const override;
162 
163  inline const Point3 & measurementIn() const {
164  return nT_;
165  }
166 
167 private:
168 
169 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
170  friend class boost::serialization::access;
172  template<class ARCHIVE>
173  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
174  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
175  ar
176  & boost::serialization::make_nvp("NoiseModelFactor1",
177  boost::serialization::base_object<Base>(*this));
178  ar & BOOST_SERIALIZATION_NVP(nT_);
179  }
180 #endif
181 };
182 
183 }
Definition: NavState.h:34
GPSFactor2()
default constructor - only use for serialization
Definition: GPSFactor.h:138
Definition: NonlinearFactor.h:431
GPSFactor(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame. Use GeographicLib to convert from geographic (la...
Definition: GPSFactor.h:66
GPSFactor()
Definition: GPSFactor.h:55
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
GPSFactor This
Typedef to this class.
Definition: GPSFactor.h:52
Definition: NonlinearFactor.h:68
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:148
Definition: Testable.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
std::shared_ptr< GPSFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:49
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
GPSFactor2 This
Typedef to this class.
Definition: GPSFactor.h:135
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
std::shared_ptr< GPSFactor2 > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:132
Definition: chartTesting.h:28
Definition: GPSFactor.h:118
Non-linear factor base classes.
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:71
Vector3 Point3
Definition: Point3.h:38
3D Pose
Definition: Pose3.h:37
GPSFactor2(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame.
Definition: GPSFactor.h:143
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: GPSFactor.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741