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 
37 class GTSAM_EXPORT GPSFactor: public NoiseModelFactorN<Pose3> {
38 
39 private:
40 
42 
44 
45 public:
46 
47  // Provide access to the Matrix& version of evaluateError:
48  using Base::evaluateError;
49 
51  typedef std::shared_ptr<GPSFactor> shared_ptr;
52 
54  typedef GPSFactor This;
55 
57  GPSFactor(): nT_(0, 0, 0) {}
58 
59  ~GPSFactor() override {}
60 
68  GPSFactor(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
69  Base(model, key), nT_(gpsIn) {
70  }
71 
74  return std::static_pointer_cast<gtsam::NonlinearFactor>(
76  }
77 
79  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
80  DefaultKeyFormatter) const override;
81 
83  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
84 
86  Vector evaluateError(const Pose3& p, OptionalMatrixType H) const override;
87 
89  inline const Point3 & measurementIn() const {
90  return nT_;
91  }
92 
98  static std::pair<Pose3, Vector3> EstimateState(double t1, const Point3& NED1,
99  double t2, const Point3& NED2, double timestamp);
100 
101 private:
102 
103 #if GTSAM_ENABLE_BOOST_SERIALIZATION
104  friend class boost::serialization::access;
106  template<class ARCHIVE>
107  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
108  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
109  ar
110  & boost::serialization::make_nvp("NoiseModelFactor1",
111  boost::serialization::base_object<Base>(*this));
112  ar & BOOST_SERIALIZATION_NVP(nT_);
113  }
114 #endif
115 };
116 
124 class GTSAM_EXPORT GPSFactorArm: public NoiseModelFactorN<Pose3> {
125 
126 private:
127 
129 
132 
134 public:
135 
136  // Provide access to the Matrix& version of evaluateError:
137  using Base::evaluateError;
138 
140  typedef std::shared_ptr<GPSFactorArm> shared_ptr;
141 
144 
146  GPSFactorArm():nT_(0, 0, 0), bL_(0, 0, 0) {}
147 
148  ~GPSFactorArm() override {}
149 
156  GPSFactorArm(Key key, const Point3& gpsIn, const Point3& leverArm, const SharedNoiseModel& model) :
157  Base(model, key), nT_(gpsIn), bL_(leverArm) {
158  }
159 
162  return std::static_pointer_cast<gtsam::NonlinearFactor>(
164  }
165 
167  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
168  DefaultKeyFormatter) const override;
169 
171  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
172 
174  Vector evaluateError(const Pose3& p, OptionalMatrixType H) const override;
175 
177  inline const Point3 & measurementIn() const {
178  return nT_;
179  }
180 
182  inline const Point3 & leverArm() const {
183  return bL_;
184  }
185 
186 };
187 
196 class GTSAM_EXPORT GPSFactorArmCalib: public NoiseModelFactorN<Pose3, Point3> {
197 
198 private:
199 
201 
203 
204 public:
205 
206  // Provide access to the Matrix& version of evaluateError:
207  using Base::evaluateError;
208 
210  typedef std::shared_ptr<GPSFactorArmCalib> shared_ptr;
211 
214 
216  GPSFactorArmCalib() : nT_(0, 0, 0) {}
217 
218  ~GPSFactorArmCalib() override {}
219 
228  Base(model, key1, key2), nT_(gpsIn) {
229  }
230 
233  return std::static_pointer_cast<gtsam::NonlinearFactor>(
235  }
236 
238  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
239  DefaultKeyFormatter) const override;
240 
242  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
243 
245  Vector evaluateError(const Pose3& p, const Point3& bL, OptionalMatrixType H1,
246  OptionalMatrixType H2) const override;
247 
249  inline const Point3 & measurementIn() const {
250  return nT_;
251  }
252 };
253 
260 class GTSAM_EXPORT GPSFactor2: public NoiseModelFactorN<NavState> {
261 
262 private:
263 
265 
267 
268 public:
269 
270  // Provide access to the Matrix& version of evaluateError:
271  using Base::evaluateError;
272 
274  typedef std::shared_ptr<GPSFactor2> shared_ptr;
275 
277  typedef GPSFactor2 This;
278 
280  GPSFactor2():nT_(0, 0, 0) {}
281 
282  ~GPSFactor2() override {}
283 
289  GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :
290  Base(model, key), nT_(gpsIn) {
291  }
292 
295  return std::static_pointer_cast<gtsam::NonlinearFactor>(
297  }
298 
300  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
301  DefaultKeyFormatter) const override;
302 
304  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
305 
307  Vector evaluateError(const NavState& p, OptionalMatrixType H) const override;
308 
310  inline const Point3 & measurementIn() const {
311  return nT_;
312  }
313 
314 private:
315 
316 #if GTSAM_ENABLE_BOOST_SERIALIZATION
317  friend class boost::serialization::access;
319  template<class ARCHIVE>
320  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
321  // NoiseModelFactor1 instead of NoiseModelFactorN for backward compatibility
322  ar
323  & boost::serialization::make_nvp("NoiseModelFactor1",
324  boost::serialization::base_object<Base>(*this));
325  ar & BOOST_SERIALIZATION_NVP(nT_);
326  }
327 #endif
328 };
329 
337 class GTSAM_EXPORT GPSFactor2Arm: public NoiseModelFactorN<NavState> {
338 
339 private:
340 
342 
345 
347 public:
348 
349  // Provide access to the Matrix& version of evaluateError:
350  using Base::evaluateError;
351 
353  typedef std::shared_ptr<GPSFactor2Arm> shared_ptr;
354 
357 
359  GPSFactor2Arm():nT_(0, 0, 0), bL_(0, 0, 0) {}
360 
361  ~GPSFactor2Arm() override {}
362 
369  GPSFactor2Arm(Key key, const Point3& gpsIn, const Point3& leverArm, const SharedNoiseModel& model) :
370  Base(model, key), nT_(gpsIn), bL_(leverArm) {
371  }
372 
375  return std::static_pointer_cast<gtsam::NonlinearFactor>(
377  }
378 
380  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
381  DefaultKeyFormatter) const override;
382 
384  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
385 
387  Vector evaluateError(const NavState& p, OptionalMatrixType H) const override;
388 
390  inline const Point3 & measurementIn() const {
391  return nT_;
392  }
393 
395  inline const Point3 & leverArm() const {
396  return bL_;
397  }
398 
399 };
400 
408 class GTSAM_EXPORT GPSFactor2ArmCalib: public NoiseModelFactorN<NavState, Point3> {
409 
410 private:
411 
413 
415 
416 public:
417 
418  // Provide access to the Matrix& version of evaluateError:
419  using Base::evaluateError;
420 
422  typedef std::shared_ptr<GPSFactor2ArmCalib> shared_ptr;
423 
426 
428  GPSFactor2ArmCalib():nT_(0, 0, 0) {}
429 
430  ~GPSFactor2ArmCalib() override {}
431 
439  Base(model, key1, key2), nT_(gpsIn) {
440  }
441 
444  return std::static_pointer_cast<gtsam::NonlinearFactor>(
446  }
447 
449  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
450  DefaultKeyFormatter) const override;
451 
453  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
454 
456  Vector evaluateError(const NavState& p, const Point3& bL,
458  OptionalMatrixType H2) const override;
459 
461  inline const Point3 & measurementIn() const {
462  return nT_;
463  }
464 };
465 
466 }
key1
const Symbol key1('v', 1)
gtsam::GPSFactorArm::GPSFactorArm
GPSFactorArm(Key key, const Point3 &gpsIn, const Point3 &leverArm, const SharedNoiseModel &model)
Definition: GPSFactor.h:156
gtsam::GPSFactorArm
Definition: GPSFactor.h:124
gtsam::GPSFactorArm::~GPSFactorArm
~GPSFactorArm() override
Definition: GPSFactor.h:148
gtsam::GPSFactorArm::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:161
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:79
gtsam::GPSFactor2Arm::~GPSFactor2Arm
~GPSFactor2Arm() override
Definition: GPSFactor.h:361
gtsam::GPSFactorArm::Base
NoiseModelFactorN< Pose3 > Base
Definition: GPSFactor.h:128
gtsam::GPSFactor2::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:310
gtsam::GPSFactor2Arm::GPSFactor2Arm
GPSFactor2Arm()
default constructor - only use for serialization
Definition: GPSFactor.h:359
gtsam::GPSFactor::This
GPSFactor This
Typedef to this class.
Definition: GPSFactor.h:54
gtsam::GPSFactorArmCalib
Definition: GPSFactor.h:196
gtsam::GPSFactor2Arm::GPSFactor2Arm
GPSFactor2Arm(Key key, const Point3 &gpsIn, const Point3 &leverArm, const SharedNoiseModel &model)
Definition: GPSFactor.h:369
gtsam::GPSFactor2::Base
NoiseModelFactorN< NavState > Base
Definition: GPSFactor.h:264
gtsam::GPSFactor2ArmCalib::shared_ptr
std::shared_ptr< GPSFactor2ArmCalib > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:422
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::GPSFactor2ArmCalib::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:461
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::GPSFactor::shared_ptr
std::shared_ptr< GPSFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:51
gtsam::GPSFactor2Arm::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:390
gtsam::GPSFactorArmCalib::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:249
gtsam::GPSFactor2ArmCalib::GPSFactor2ArmCalib
GPSFactor2ArmCalib(Key key1, Key key2, const Point3 &gpsIn, const SharedNoiseModel &model)
Definition: GPSFactor.h:438
gtsam::GPSFactor2::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:266
gtsam::GPSFactorArmCalib::Base
NoiseModelFactorN< Pose3, Point3 > Base
Definition: GPSFactor.h:200
gtsam::GPSFactorArm::shared_ptr
std::shared_ptr< GPSFactorArm > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:140
gtsam::GPSFactor::GPSFactor
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:68
gtsam::NavState
Definition: NavState.h:38
gtsam::GPSFactor2Arm::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:343
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::GPSFactor2Arm::bL_
Point3 bL_
Definition: GPSFactor.h:344
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::GPSFactor2ArmCalib::~GPSFactor2ArmCalib
~GPSFactor2ArmCalib() override
Definition: GPSFactor.h:430
gtsam::GPSFactor2::GPSFactor2
GPSFactor2()
default constructor - only use for serialization
Definition: GPSFactor.h:280
gtsam::GPSFactor2::~GPSFactor2
~GPSFactor2() override
Definition: GPSFactor.h:282
gtsam::GPSFactor::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:73
gtsam::GPSFactor2::shared_ptr
std::shared_ptr< GPSFactor2 > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:274
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam::GPSFactor::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:43
key2
const Symbol key2('v', 2)
gtsam::KeyFormatter
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
gtsam::Pose3
Definition: Pose3.h:37
gtsam::GPSFactorArmCalib::GPSFactorArmCalib
GPSFactorArmCalib()
default constructor - only use for serialization
Definition: GPSFactor.h:216
NavState.h
Navigation state composing of attitude, position, and velocity.
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:434
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::GPSFactor2Arm::leverArm
const Point3 & leverArm() const
return the lever arm, a position in the body frame
Definition: GPSFactor.h:395
gtsam::GPSFactor2ArmCalib::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:414
gtsam::GPSFactorArmCalib::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:232
gtsam::GPSFactor2ArmCalib::Base
NoiseModelFactorN< NavState, Point3 > Base
Definition: GPSFactor.h:412
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::GPSFactor::Base
NoiseModelFactorN< Pose3 > Base
Definition: GPSFactor.h:41
gtsam::GPSFactorArmCalib::shared_ptr
std::shared_ptr< GPSFactorArmCalib > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:210
gtsam::GPSFactor2ArmCalib::GPSFactor2ArmCalib
GPSFactor2ArmCalib()
default constructor - only use for serialization
Definition: GPSFactor.h:428
gtsam::GPSFactorArmCalib::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:202
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::GPSFactorArm::bL_
Point3 bL_
Definition: GPSFactor.h:131
gtsam::equals
Definition: Testable.h:112
key
const gtsam::Symbol key('X', 0)
gtsam::GPSFactor::~GPSFactor
~GPSFactor() override
Definition: GPSFactor.h:59
NonlinearFactor.h
Non-linear factor base classes.
gtsam::GPSFactor2ArmCalib::This
GPSFactor2ArmCalib This
Typedef to this class.
Definition: GPSFactor.h:425
gtsam::GPSFactorArmCalib::~GPSFactorArmCalib
~GPSFactorArmCalib() override
Definition: GPSFactor.h:218
gtsam::GPSFactor2Arm::This
GPSFactor2Arm This
Typedef to this class.
Definition: GPSFactor.h:356
gtsam::GPSFactor2::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:294
gtsam
traits
Definition: SFMdata.h:40
gtsam::GPSFactorArm::leverArm
const Point3 & leverArm() const
return the lever arm, a position in the body frame
Definition: GPSFactor.h:182
gtsam::GPSFactorArmCalib::GPSFactorArmCalib
GPSFactorArmCalib(Key key1, Key key2, const Point3 &gpsIn, const SharedNoiseModel &model)
Definition: GPSFactor.h:227
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::GPSFactor2ArmCalib::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:443
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::GPSFactor2::GPSFactor2
GPSFactor2(Key key, const Point3 &gpsIn, const SharedNoiseModel &model)
Definition: GPSFactor.h:289
gtsam::GPSFactorArm::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:177
This
#define This
Definition: ActiveSetSolver-inl.h:27
gtsam::GPSFactor2Arm
Definition: GPSFactor.h:337
gtsam::GPSFactor::GPSFactor
GPSFactor()
Definition: GPSFactor.h:57
gtsam::GPSFactor2ArmCalib
Definition: GPSFactor.h:408
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::GPSFactor2
Definition: GPSFactor.h:260
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:56
gtsam::GPSFactor2Arm::Base
NoiseModelFactorN< NavState > Base
Definition: GPSFactor.h:341
example::leverArm
static const Point3 leverArm(0.1, 0.2, 0.3)
gtsam::GPSFactor2Arm::shared_ptr
std::shared_ptr< GPSFactor2Arm > shared_ptr
shorthand for a smart pointer to a factor
Definition: GPSFactor.h:353
gtsam::GPSFactorArm::This
GPSFactorArm This
Typedef to this class.
Definition: GPSFactor.h:143
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::GPSFactor::measurementIn
const Point3 & measurementIn() const
return the measurement, in the navigation frame
Definition: GPSFactor.h:89
gtsam::GPSFactor2Arm::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: GPSFactor.h:374
gtsam::GPSFactorArm::GPSFactorArm
GPSFactorArm()
default constructor - only use for serialization
Definition: GPSFactor.h:146
gtsam::GPSFactor
Definition: GPSFactor.h:37
gtsam::GPSFactorArmCalib::This
GPSFactorArmCalib This
Typedef to this class.
Definition: GPSFactor.h:213
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::GPSFactor2::This
GPSFactor2 This
Typedef to this class.
Definition: GPSFactor.h:277
gtsam::GPSFactorArm::nT_
Point3 nT_
Position measurement in cartesian coordinates (navigation frame)
Definition: GPSFactor.h:130


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:45