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  GTSAM_CONCEPT_ASSERT(IsManifold<VALUE>);
49 
50  public:
51  typedef std::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
52  typedef VALUE T;
53 
54  protected:
55  T x_; // linearization point
56  JacobianFactor::shared_ptr priorFactor_; // Gaussian density on x_
57 
58  static T solve_(const GaussianFactorGraph& linearFactorGraph, const Values& linearizationPoints,
59  Key x, JacobianFactor::shared_ptr* newPrior);
60 
61  public:
64 
65  ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial);
66 
70 
72  void print(const std::string& s = "") const {
73  std::cout << s << "\n";
74  x_.print(s + "x");
75  priorFactor_->print(s + "density");
76  }
77 
81 
87  T predict(const NoiseModelFactor& motionFactor);
88 
93  T update(const NoiseModelFactor& measurementFactor);
94 
97  return priorFactor_;
98  }
99 
101 };
102 
103 } // namespace
104 
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::ExtendedKalmanFilter::ExtendedKalmanFilter
ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
Definition: ExtendedKalmanFilter-inl.h:64
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::ExtendedKalmanFilter
Definition: ExtendedKalmanFilter.h:45
gtsam::noiseModel::Gaussian::shared_ptr
std::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:189
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::ExtendedKalmanFilter::print
void print(const std::string &s="") const
print
Definition: ExtendedKalmanFilter.h:72
gtsam::ExtendedKalmanFilter::update
T update(const NoiseModelFactor &measurementFactor)
Definition: ExtendedKalmanFilter-inl.h:104
gtsam::ExtendedKalmanFilter::priorFactor_
JacobianFactor::shared_ptr priorFactor_
Definition: ExtendedKalmanFilter.h:56
gtsam::ExtendedKalmanFilter::GTSAM_CONCEPT_ASSERT
GTSAM_CONCEPT_ASSERT(IsTestable< VALUE >)
gtsam::ExtendedKalmanFilter::solve_
static T solve_(const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior)
Definition: ExtendedKalmanFilter-inl.h:30
gtsam::ExtendedKalmanFilter::x_
T x_
Definition: ExtendedKalmanFilter.h:55
Eigen::Triplet
A small structure to hold a non zero as a triplet (i,j,value).
Definition: SparseUtil.h:162
gtsam::ExtendedKalmanFilter::predict
T predict(const NoiseModelFactor &motionFactor)
Definition: ExtendedKalmanFilter-inl.h:79
NonlinearFactor.h
Non-linear factor base classes.
gtsam
traits
Definition: chartTesting.h:28
ExtendedKalmanFilter-inl.h
Class to perform generic Kalman Filtering using nonlinear factor graphs.
gtsam::ExtendedKalmanFilter::shared_ptr
std::shared_ptr< ExtendedKalmanFilter< VALUE > > shared_ptr
Definition: ExtendedKalmanFilter.h:51
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::NoiseModelFactor
Definition: NonlinearFactor.h:197
gtsam::Values
Definition: Values.h:65
gtsam::JacobianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: JacobianFactor.h:97
gtsam::IsTestable
Definition: Testable.h:59
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::ExtendedKalmanFilter::Density
const JacobianFactor::shared_ptr Density() const
Return current predictive (if called after predict)/posterior (if called after update)
Definition: ExtendedKalmanFilter.h:96
gtsam::ExtendedKalmanFilter::T
VALUE T
Definition: ExtendedKalmanFilter.h:52


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:02:20