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 NoiseModelFactor1<Pose3> {
36 
37 private:
38 
40 
42 
43 public:
44 
46  typedef boost::shared_ptr<GPSFactor> shared_ptr;
47 
49  typedef GPSFactor This;
50 
52  GPSFactor(): nT_(0, 0, 0) {}
53 
54  ~GPSFactor() override {}
55 
63  GPSFactor(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
64  Base(model, key), nT_(gpsIn) {
65  }
66 
69  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
71  }
72 
74  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
75  DefaultKeyFormatter) const override;
76 
78  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
79 
81  Vector evaluateError(const Pose3& p,
82  boost::optional<Matrix&> H = boost::none) const override;
83 
84  inline const Point3 & measurementIn() const {
85  return nT_;
86  }
87 
93  static std::pair<Pose3, Vector3> EstimateState(double t1, const Point3& NED1,
94  double t2, const Point3& NED2, double timestamp);
95 
96 private:
97 
99  friend class boost::serialization::access;
100  template<class ARCHIVE>
101  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
102  ar
103  & boost::serialization::make_nvp("NoiseModelFactor1",
104  boost::serialization::base_object<Base>(*this));
105  ar & BOOST_SERIALIZATION_NVP(nT_);
106  }
107 };
108 
113 class GTSAM_EXPORT GPSFactor2: public NoiseModelFactor1<NavState> {
114 
115 private:
116 
118 
120 
121 public:
122 
124  typedef boost::shared_ptr<GPSFactor2> shared_ptr;
125 
127  typedef GPSFactor2 This;
128 
130  GPSFactor2():nT_(0, 0, 0) {}
131 
132  ~GPSFactor2() override {}
133 
135  GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
136  Base(model, key), nT_(gpsIn) {
137  }
138 
141  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
143  }
144 
146  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
147  DefaultKeyFormatter) const override;
148 
150  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
151 
153  Vector evaluateError(const NavState& p,
154  boost::optional<Matrix&> H = boost::none) const override;
155 
156  inline const Point3 & measurementIn() const {
157  return nT_;
158  }
159 
160 private:
161 
163  friend class boost::serialization::access;
164  template<class ARCHIVE>
165  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
166  ar
167  & boost::serialization::make_nvp("NoiseModelFactor1",
168  boost::serialization::base_object<Base>(*this));
169  ar & BOOST_SERIALIZATION_NVP(nT_);
170  }
171 };
172 
173 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
const Point3 & measurementIn() const
Definition: GPSFactor.h:156
GPSFactor2()
default constructor - only use for serialization
Definition: GPSFactor.h:130
void serialize(ARCHIVE &ar, const unsigned int)
Definition: GPSFactor.h:101
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:63
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
GPSFactor This
Typedef to this class.
Definition: GPSFactor.h:49
const Point3 & measurementIn() const
Definition: GPSFactor.h:84
NoiseModelFactor1< Pose3 > Base
Definition: GPSFactor.h:39
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:140
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
~GPSFactor2() override
Definition: GPSFactor.h:132
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< GPSFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:46
boost::shared_ptr< This > shared_ptr
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
GPSFactor2 This
Typedef to this class.
Definition: GPSFactor.h:127
Point3 nT_
Position measurement in cartesian coordinates.
Definition: GPSFactor.h:119
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Point3 nT_
Position measurement in cartesian coordinates.
Definition: GPSFactor.h:41
#define This
traits
Definition: chartTesting.h:28
~GPSFactor() override
Definition: GPSFactor.h:54
Non-linear factor base classes.
NoiseModelFactor1< NavState > Base
Definition: GPSFactor.h:117
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:68
float * p
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
boost::shared_ptr< GPSFactor2 > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:124
3D Pose
void serialize(ARCHIVE &ar, const unsigned int)
Definition: GPSFactor.h:165
GPSFactor2(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Constructor from a measurement in a Cartesian frame.
Definition: GPSFactor.h:135
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:09