ExtendedKalmanFilter.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 
19 // \callgraph
20 #pragma once
21 
24 
25 namespace gtsam {
26 
44 template <class VALUE>
46  // Check that VALUE type is a testable Manifold
48  BOOST_CONCEPT_ASSERT((IsManifold<VALUE>));
49 
50  public:
51  typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
52  typedef VALUE T;
53 
54  //@deprecated: any NoiseModelFactor will do, as long as they have the right keys
57 
58  protected:
59  T x_; // linearization point
60  JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_
61 
62  static T solve_(const GaussianFactorGraph& linearFactorGraph, const Values& linearizationPoints,
63  Key x, JacobianFactor::shared_ptr* newPrior);
64 
65  public:
68 
69  ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial);
70 
74 
76  void print(const std::string& s = "") const {
77  std::cout << s << "\n";
78  x_.print(s + "x");
79  priorFactor_->print(s + "density");
80  }
81 
85 
90  T predict(const NoiseModelFactor& motionFactor);
91 
96  T update(const NoiseModelFactor& measurementFactor);
97 
100  return priorFactor_;
101  }
102 
104 };
105 
106 } // namespace
107 
ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
NoiseModelFactor2< VALUE, VALUE > MotionFactor
const JacobianFactor::shared_ptr Density() const
Return current predictive (if called after predict)/posterior (if called after update) ...
Factor Graph consisting of non-linear factors.
BOOST_CONCEPT_ASSERT((IsTestable< VALUE >))
T update(const NoiseModelFactor &measurementFactor)
NoiseModelFactor1< VALUE > MeasurementFactor
static T solve_(const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior)
Class to perform generic Kalman Filtering using nonlinear factor graphs.
void print(const std::string &s="") const
print
JacobianFactor::shared_ptr priorFactor_
RealScalar s
T predict(const NoiseModelFactor &motionFactor)
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
boost::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:189
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
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 x
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
boost::shared_ptr< ExtendedKalmanFilter< VALUE > > shared_ptr


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