GPSFactor.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 
19 #include "GPSFactor.h"
20 
21 using namespace std;
22 
23 namespace gtsam {
24 
25 //***************************************************************************
26 void GPSFactor::print(const string& s, const KeyFormatter& keyFormatter) const {
27  cout << (s.empty() ? "" : s + " ") << "GPSFactor on " << keyFormatter(key())
28  << "\n";
29  cout << " GPS measurement: " << nT_ << "\n";
30  noiseModel_->print(" noise model: ");
31 }
32 
33 //***************************************************************************
34 bool GPSFactor::equals(const NonlinearFactor& expected, double tol) const {
35  const This* e = dynamic_cast<const This*>(&expected);
36  return e != nullptr && Base::equals(*e, tol) && traits<Point3>::Equals(nT_, e->nT_, tol);
37 }
38 
39 //***************************************************************************
40 Vector GPSFactor::evaluateError(const Pose3& p,
41  boost::optional<Matrix&> H) const {
42  return p.translation(H) -nT_;
43 }
44 
45 //***************************************************************************
46 pair<Pose3, Vector3> GPSFactor::EstimateState(double t1, const Point3& NED1,
47  double t2, const Point3& NED2, double timestamp) {
48  // Estimate initial velocity as difference in NED frame
49  double dt = t2 - t1;
50  Point3 nV = (NED2 - NED1) / dt;
51 
52  // Estimate initial position as linear interpolation
53  Point3 nT = NED1 + nV * (timestamp - t1);
54 
55  // Estimate Rotation
56  double yaw = atan2(nV.y(), nV.x());
57  Rot3 nRy = Rot3::Yaw(yaw); // yaw frame
58  Point3 yV = nRy.inverse() * nV; // velocity in yaw frame
59  double pitch = -atan2(yV.z(), yV.x()), roll = 0;
60  Rot3 nRb = Rot3::Ypr(yaw, pitch, roll);
61 
62  // Construct initial pose
63  Pose3 nTb(nRb, nT); // nTb
64 
65  return make_pair(nTb, nV);
66 }
67 //***************************************************************************
68 void GPSFactor2::print(const string& s, const KeyFormatter& keyFormatter) const {
69  cout << s << "GPSFactor2 on " << keyFormatter(key()) << "\n";
70  cout << " GPS measurement: " << nT_.transpose() << endl;
71  noiseModel_->print(" noise model: ");
72 }
73 
74 //***************************************************************************
75 bool GPSFactor2::equals(const NonlinearFactor& expected, double tol) const {
76  const This* e = dynamic_cast<const This*>(&expected);
77  return e != nullptr && Base::equals(*e, tol) &&
78  traits<Point3>::Equals(nT_, e->nT_, tol);
79 }
80 
81 //***************************************************************************
82 Vector GPSFactor2::evaluateError(const NavState& p,
83  boost::optional<Matrix&> H) const {
84  return p.position(H) -nT_;
85 }
86 
87 //***************************************************************************
88 
89 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Matrix expected
Definition: testMatrix.cpp:974
Definition: Half.h:150
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
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
const double dt
Header file for GPS factor.
Eigen::VectorXd Vector
Definition: Vector.h:38
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
traits
Definition: chartTesting.h:28
const Point3 & position(OptionalJacobian< 3, 9 > H=boost::none) const
Definition: NavState.cpp:57
float * p
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
Rot3 nRb


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