KalmanFilter.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 
27 #include <gtsam/base/Testable.h>
28 
29 #include <boost/make_shared.hpp>
30 #include <boost/assign/list_of.hpp>
31 
32 using namespace boost::assign;
33 using namespace std;
34 
35 namespace gtsam {
36 
37 /* ************************************************************************* */
38 // Auxiliary function to solve factor graph and return pointer to root conditional
40 KalmanFilter::solve(const GaussianFactorGraph& factorGraph) const {
41 
42  // Eliminate the graph using the provided Eliminate function
43  Ordering ordering(factorGraph.keys());
44  GaussianBayesNet::shared_ptr bayesNet = //
45  factorGraph.eliminateSequential(ordering, function_);
46 
47  // As this is a filter, all we need is the posterior P(x_t).
48  // This is the last GaussianConditional in the resulting BayesNet
49  GaussianConditional::shared_ptr posterior = *(--bayesNet->end());
50  return boost::make_shared<GaussianDensity>(*posterior);
51 }
52 
53 /* ************************************************************************* */
54 // Auxiliary function to create a small graph for predict or update and solve
56 KalmanFilter::fuse(const State& p, GaussianFactor::shared_ptr newFactor) const {
57 
58  // Create a factor graph
59  GaussianFactorGraph factorGraph;
60  factorGraph += p, newFactor;
61 
62  // Eliminate graph in order x0, x1, to get Bayes net P(x0|x1)P(x1)
63  return solve(factorGraph);
64 }
65 
66 /* ************************************************************************* */
68  const SharedDiagonal& P0) const {
69 
70  // Create a factor graph f(x0), eliminate it into P(x0)
71  GaussianFactorGraph factorGraph;
72  factorGraph += JacobianFactor(0, I_, x0, P0); // |x-x0|^2_diagSigma
73  return solve(factorGraph);
74 }
75 
76 /* ************************************************************************* */
78 
79  // Create a factor graph f(x0), eliminate it into P(x0)
80  GaussianFactorGraph factorGraph;
81  factorGraph += HessianFactor(0, x, P0); // 0.5*(x-x0)'*inv(Sigma)*(x-x0)
82  return solve(factorGraph);
83 }
84 
85 /* ************************************************************************* */
86 void KalmanFilter::print(const string& s) const {
87  cout << "KalmanFilter " << s << ", dim = " << n_ << endl;
88 }
89 
90 /* ************************************************************************* */
91 KalmanFilter::State KalmanFilter::predict(const State& p, const Matrix& F,
92  const Matrix& B, const Vector& u, const SharedDiagonal& model) const {
93 
94  // The factor related to the motion model is defined as
95  // f2(x_{t},x_{t+1}) = (F*x_{t} + B*u - x_{t+1}) * Q^-1 * (F*x_{t} + B*u - x_{t+1})^T
96  Key k = step(p);
97  return fuse(p,
98  boost::make_shared<JacobianFactor>(k, -F, k + 1, I_, B * u, model));
99 }
100 
101 /* ************************************************************************* */
102 KalmanFilter::State KalmanFilter::predictQ(const State& p, const Matrix& F,
103  const Matrix& B, const Vector& u, const Matrix& Q) const {
104 
105 #ifndef NDEBUG
106  DenseIndex n = F.cols();
107  assert(F.rows() == n);
108  assert(B.rows() == n);
109  assert(B.cols() == u.size());
110  assert(Q.rows() == n);
111  assert(Q.cols() == n);
112 #endif
113 
114  // The factor related to the motion model is defined as
115  // f2(x_{t},x_{t+1}) = (F*x_{t} + B*u - x_{t+1}) * Q^-1 * (F*x_{t} + B*u - x_{t+1})^T
116  // See documentation in HessianFactor, we have A1 = -F, A2 = I_, b = B*u:
117  // TODO: starts to seem more elaborate than straight-up KF equations?
118  Matrix M = Q.inverse(), Ft = trans(F);
119  Matrix G12 = -Ft * M, G11 = -G12 * F, G22 = M;
120  Vector b = B * u, g2 = M * b, g1 = -Ft * g2;
121  double f = dot(b, g2);
122  Key k = step(p);
123  return fuse(p,
124  boost::make_shared<HessianFactor>(k, k + 1, G11, G12, g1, G22, g2, f));
125 }
126 
127 /* ************************************************************************* */
128 KalmanFilter::State KalmanFilter::predict2(const State& p, const Matrix& A0,
129  const Matrix& A1, const Vector& b, const SharedDiagonal& model) const {
130  // Nhe factor related to the motion model is defined as
131  // f2(x_{t},x_{t+1}) = |A0*x_{t} + A1*x_{t+1} - b|^2
132  Key k = step(p);
133  return fuse(p, boost::make_shared<JacobianFactor>(k, A0, k + 1, A1, b, model));
134 }
135 
136 /* ************************************************************************* */
138  const Vector& z, const SharedDiagonal& model) const {
139  // The factor related to the measurements would be defined as
140  // f2 = (h(x_{t}) - z_{t}) * R^-1 * (h(x_{t}) - z_{t})^T
141  // = (x_{t} - z_{t}) * R^-1 * (x_{t} - z_{t})^T
142  Key k = step(p);
143  return fuse(p, boost::make_shared<JacobianFactor>(k, H, z, model));
144 }
145 
146 /* ************************************************************************* */
147 KalmanFilter::State KalmanFilter::updateQ(const State& p, const Matrix& H,
148  const Vector& z, const Matrix& Q) const {
149  Key k = step(p);
150  Matrix M = Q.inverse(), Ht = trans(H);
151  Matrix G = Ht * M * H;
152  Vector g = Ht * M * z;
153  double f = dot(z, M * z);
154  return fuse(p, boost::make_shared<HessianFactor>(k, G, g, f));
155 }
156 
157 /* ************************************************************************* */
158 
159 } // \namespace gtsam
160 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
def step(data, isam, result, truth, currPoseIndex)
Definition: visual_isam.py:82
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
Scalar * b
Definition: benchVecAdd.cpp:17
Concept check for values that can be used in unit tests.
def update(text)
Definition: relicense.py:46
JacobiRotation< float > G
noiseModel::Diagonal::shared_ptr model
static enum @843 ordering
GaussianDensity::shared_ptr State
Definition: KalmanFilter.h:56
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
static char trans
boost::shared_ptr< This > shared_ptr
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
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
void g(const string &key, int i)
Definition: testBTree.cpp:43
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Signature::Row F
Definition: Signature.cpp:53
Eigen::VectorXd Vector
Definition: Vector.h:38
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Contains the HessianFactor class, a general quadratic factor.
RealScalar s
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
internal::DoglegState State
static Symbol x0('x', 0)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF...
The quaternion class used to represent 3D orientations and rotations.
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1460
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
float * p
A Gaussian factor using the canonical parameters (information form)
boost::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
Chordal Bayes Net, the result of eliminating a factor graph.
const Point3 P0(0, 0, 0)
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
Pose3 g2(g1.expmap(h *V1_g1))
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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