ExtendedKalmanFilter-inl.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 #pragma once
20 
25 
26 namespace gtsam {
27 
28  /* ************************************************************************* */
29  template<class VALUE>
31  const GaussianFactorGraph& linearFactorGraph,
32  const Values& linearizationPoint, Key lastKey,
34  {
35  // Compute the marginal on the last key
36  // Solve the linear factor graph, converting it into a linear Bayes Network
37  // P(x0,x1) = P(x0|x1)*P(x1)
38  const Ordering lastKeyAsOrdering{lastKey};
39  const GaussianConditional::shared_ptr marginal =
40  linearFactorGraph.marginalMultifrontalBayesNet(lastKeyAsOrdering)->front();
41 
42  // Extract the current estimate of x1,P1
43  VectorValues result = marginal->solve(VectorValues());
44  const T& current = linearizationPoint.at<T>(lastKey);
45  T x = traits<T>::Retract(current, result[lastKey]);
46 
47  // Create a Jacobian Factor from the root node of the produced Bayes Net.
48  // This will act as a prior for the next iteration.
49  // The linearization point of this prior must be moved to the new estimate of x,
50  // and the key/index needs to be reset to 0, the first key in the next iteration.
51  assert(marginal->nrFrontals() == 1);
52  assert(marginal->nrParents() == 0);
53  *newPrior = std::make_shared<JacobianFactor>(
54  marginal->keys().front(),
55  marginal->getA(marginal->begin()),
56  marginal->getb() - marginal->getA(marginal->begin()) * result[lastKey],
57  marginal->get_model());
58 
59  return x;
60  }
61 
62  /* ************************************************************************* */
63  template <class VALUE>
65  Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
66  : x_(x_initial) // Set the initial linearization point
67  {
68  // Create a Jacobian Prior Factor directly P_initial.
69  // Since x0 is set to the provided mean, the b vector in the prior will be zero
70  // TODO(Frank): is there a reason why noiseModel is not simply P_initial?
71  int n = traits<T>::GetDimension(x_initial);
73  new JacobianFactor(key_initial, P_initial->R(), Vector::Zero(n),
75  }
76 
77  /* ************************************************************************* */
78  template<class VALUE>
80  const NoiseModelFactor& motionFactor) {
81  const auto keys = motionFactor.keys();
82 
83  // Create a Gaussian Factor Graph
84  GaussianFactorGraph linearFactorGraph;
85 
86  // Add in previous posterior as prior on the first state
87  linearFactorGraph.push_back(priorFactor_);
88 
89  // Linearize motion model and add it to the Kalman Filter graph
90  Values linearizationPoint;
91  linearizationPoint.insert(keys[0], x_);
92  linearizationPoint.insert(keys[1], x_); // TODO should this really be x_ ?
93  linearFactorGraph.push_back(motionFactor.linearize(linearizationPoint));
94 
95  // Solve the factor graph and update the current state estimate
96  // and the posterior for the next iteration.
97  x_ = solve_(linearFactorGraph, linearizationPoint, keys[1], &priorFactor_);
98 
99  return x_;
100  }
101 
102  /* ************************************************************************* */
103  template<class VALUE>
105  const NoiseModelFactor& measurementFactor) {
106  const auto keys = measurementFactor.keys();
107 
108  // Create a Gaussian Factor Graph
109  GaussianFactorGraph linearFactorGraph;
110 
111  // Add in the prior on the first state
112  linearFactorGraph.push_back(priorFactor_);
113 
114  // Linearize measurement factor and add it to the Kalman Filter graph
115  Values linearizationPoint;
116  linearizationPoint.insert(keys[0], x_);
117  linearFactorGraph.push_back(measurementFactor.linearize(linearizationPoint));
118 
119  // Solve the factor graph and update the current state estimate
120  // and the prior factor for the next iteration
121  x_ = solve_(linearFactorGraph, linearizationPoint, keys[0], &priorFactor_);
122 
123  return x_;
124  }
125 
126 } // namespace gtsam
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::ExtendedKalmanFilter::ExtendedKalmanFilter
ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
Definition: ExtendedKalmanFilter-inl.h:64
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
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::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::EliminateableFactorGraph::marginalMultifrontalBayesNet
std::shared_ptr< BayesNetType > marginalMultifrontalBayesNet(const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:230
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
gtsam::noiseModel::Gaussian::shared_ptr
std::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:189
result
Values result
Definition: OdometryOptimize.cpp:8
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::NoiseModelFactor::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Definition: NonlinearFactor.cpp:150
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
gtsam::VectorValues
Definition: VectorValues.h:74
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::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
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::predict
T predict(const NoiseModelFactor &motionFactor)
Definition: ExtendedKalmanFilter-inl.h:79
ExtendedKalmanFilter.h
Class to perform generic Kalman Filtering using nonlinear factor graphs.
NonlinearFactor.h
Non-linear factor base classes.
gtsam
traits
Definition: chartTesting.h:28
gtsam::traits
Definition: Group.h:36
gtsam::NoiseModelFactor
Definition: NonlinearFactor.h:197
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:142
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::GaussianConditional::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianConditional.h:46
gtsam::JacobianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: JacobianFactor.h:97
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::ExtendedKalmanFilter::T
VALUE T
Definition: ExtendedKalmanFilter.h:52


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