testExtendedKalmanFilter.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 
21 #include <gtsam/inference/Symbol.h>
22 #include <gtsam/geometry/Point2.h>
23 
25 
26 using namespace gtsam;
27 
28 // Convenience for named keys
31 
32 /* ************************************************************************* */
34 
35  // Create the TestKeys for our example
36  Symbol x0('x',0), x1('x',1), x2('x',2), x3('x',3);
37 
38  // Create the Kalman Filter initialization point
39  Point2 x_initial(0.0, 0.0);
41 
42  // Create an ExtendedKalmanFilter object
43  ExtendedKalmanFilter<Point2> ekf(x0, x_initial, P_initial);
44 
45  // Create the controls and measurement properties for our example
46  double dt = 1.0;
47  Vector u = Vector2(1.0, 0.0);
48  Point2 difference(u*dt);
50  Point2 z1(1.0, 0.0);
51  Point2 z2(2.0, 0.0);
52  Point2 z3(3.0, 0.0);
54 
55  // Create the set of expected output TestValues
56  Point2 expected1(1.0, 0.0);
57  Point2 expected2(2.0, 0.0);
58  Point2 expected3(3.0, 0.0);
59 
60  // Run iteration 1
61  // Create motion factor
62  BetweenFactor<Point2> factor1(x0, x1, difference, Q);
63  Point2 predict1 = ekf.predict(factor1);
64  EXPECT(assert_equal(expected1,predict1));
65 
66  // Create the measurement factor
68  Point2 update1 = ekf.update(factor2);
69  EXPECT(assert_equal(expected1,update1));
70 
71  // Run iteration 2
72  BetweenFactor<Point2> factor3(x1, x2, difference, Q);
73  Point2 predict2 = ekf.predict(factor3);
74  EXPECT(assert_equal(expected2,predict2));
75 
76  PriorFactor<Point2> factor4(x2, z2, R);
77  Point2 update2 = ekf.update(factor4);
78  EXPECT(assert_equal(expected2,update2));
79 
80  // Run iteration 3
81  BetweenFactor<Point2> factor5(x2, x3, difference, Q);
82  Point2 predict3 = ekf.predict(factor5);
83  EXPECT(assert_equal(expected3,predict3));
84 
85  PriorFactor<Point2> factor6(x3, z3, R);
86  Point2 update3 = ekf.update(factor6);
87  EXPECT(assert_equal(expected3,update3));
88 
89  return;
90 }
91 
92 
93 // Create Motion Model Factor
94 class NonlinearMotionModel : public NoiseModelFactor2<Point2,Point2> {
95 
98 
99 protected:
102 
103 public:
105 
106  NonlinearMotionModel(const Symbol& TestKey1, const Symbol& TestKey2) :
107  Base(noiseModel::Diagonal::Sigmas(Vector2(1.0, 1.0)), TestKey1, TestKey2), Q_(2,2) {
108 
109  // Initialize motion model parameters:
110  // w is vector of motion noise sigmas. The final covariance is calculated as G*w*w'*G'
111  // In this model, Q is fixed, so it may be calculated in the constructor
112  Matrix G(2,2);
113  Matrix w(2,2);
114 
115  G << 1.0, 0.0, 0.0, 1.0;
116  w << 1.0, 0.0, 0.0, 1.0;
117 
118  w = G*w;
119  Q_ = w*w.transpose();
120  Q_invsqrt_ = inverse_square_root(Q_);
121  }
122 
123  ~NonlinearMotionModel() override {}
124 
125  // Calculate the next state prediction using the nonlinear function f()
126  Point2 f(const Point2& x_t0) const {
127 
128  // Calculate f(x)
129  double x = x_t0.x() * x_t0.x();
130  double y = x_t0.x() * x_t0.y();
131  Point2 x_t1(x,y);
132 
133  // In this example, the noiseModel remains constant
134  return x_t1;
135  }
136 
137  // Calculate the Jacobian of the nonlinear function f()
138  Matrix F(const Point2& x_t0) const {
139  // Calculate Jacobian of f()
140  Matrix F = Matrix(2,2);
141  F(0,0) = 2*x_t0.x();
142  F(0,1) = 0.0;
143  F(1,0) = x_t0.y();
144  F(1,1) = x_t0.x();
145 
146  return F;
147  }
148 
149  // Calculate the inverse square root of the motion model covariance, Q
150  Matrix QInvSqrt(const Point2& x_t0) const {
151  // This motion model has a constant covariance
152  return Q_invsqrt_;
153  }
154 
155  /* print */
156  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
157  std::cout << s << ": NonlinearMotionModel\n";
158  std::cout << " TestKey1: " << keyFormatter(key1()) << std::endl;
159  std::cout << " TestKey2: " << keyFormatter(key2()) << std::endl;
160  }
161 
163  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
164  const This *e = dynamic_cast<const This*> (&f);
165  return (e != nullptr) && (key1() == e->key1()) && (key2() == e->key2());
166  }
167 
172  double error(const Values& c) const override {
173  Vector w = whitenedError(c);
174  return 0.5 * w.dot(w);
175  }
176 
178  size_t dim() const override {
179  return 2;
180  }
181 
183  Vector whitenedError(const Values& c) const {
184  return QInvSqrt(c.at<Point2>(key1()))*unwhitenedError(c);
185  }
186 
192  boost::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
193  const X1& x1 = c.at<X1>(key1());
194  const X2& x2 = c.at<X2>(key2());
195  Matrix A1, A2;
196  Vector b = -evaluateError(x1, x2, A1, A2);
197  SharedDiagonal constrained =
198  boost::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
199  if (constrained.get() != nullptr) {
201  A2, b, constrained));
202  }
203  // "Whiten" the system before converting to a Gaussian Factor
204  Matrix Qinvsqrt = QInvSqrt(x1);
205  A1 = Qinvsqrt*A1;
206  A2 = Qinvsqrt*A2;
207  b = Qinvsqrt*b;
209  A2, b, noiseModel::Unit::Create(b.size())));
210  }
211 
214  boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
215  boost::none) const override {
216 
217  // error = p2 - f(p1)
218  // H1 = d error / d p1 = -d f/ d p1 = -F
219  // H2 = d error / d p2 = I
220  Point2 prediction = f(p1);
221 
222  if(H1)
223  *H1 = -F(p1);
224 
225  if(H2)
226  *H2 = Matrix::Identity(dim(),dim());
227 
228  // Return the error between the prediction and the supplied value of p2
229  return (p2 - prediction);
230  }
231 
232 };
233 
234 // Create Measurement Model Factor
236 
239 
240 protected:
245 public:
247 
249  Base(noiseModel::Unit::Create(z.size()), TestKey), z_(z), R_(1,1) {
250 
251  // Initialize nonlinear measurement model parameters:
252  // z(t) = H*x(t) + v
253  // where v ~ N(0, noiseModel_)
254  R_ << 1.0;
255  R_invsqrt_ = inverse_square_root(R_);
256  }
257 
259 
260  // Calculate the predicted measurement using the nonlinear function h()
261  // Byproduct: updates Jacobian H, and noiseModel (R)
262  Vector h(const Point2& x_t1) const {
263 
264  // Calculate prediction
265  Vector z_hat(1);
266  z_hat(0) = 2*x_t1.x()*x_t1.x() - x_t1.x()*x_t1.y() - 2.5*x_t1.x() + 7*x_t1.y();
267 
268  return z_hat;
269  }
270 
271  Matrix H(const Point2& x_t1) const {
272  // Update Jacobian
273  Matrix H(1,2);
274  H(0,0) = 4*x_t1.x() - x_t1.y() - 2.5;
275  H(0,1) = -1*x_t1.x() + 7;
276 
277  return H;
278  }
279 
280  // Calculate the inverse square root of the motion model covariance, Q
281  Matrix RInvSqrt(const Point2& x_t0) const {
282  // This motion model has a constant covariance
283  return R_invsqrt_;
284  }
285 
286  /* print */
287  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
288  std::cout << s << ": NonlinearMeasurementModel\n";
289  std::cout << " TestKey: " << keyFormatter(key()) << std::endl;
290  }
291 
293  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
294  const This *e = dynamic_cast<const This*> (&f);
295  return (e != nullptr) && Base::equals(f);
296  }
297 
302  double error(const Values& c) const override {
303  Vector w = whitenedError(c);
304  return 0.5 * w.dot(w);
305  }
306 
308  size_t dim() const override {
309  return 1;
310  }
311 
313  Vector whitenedError(const Values& c) const {
314  return RInvSqrt(c.at<Point2>(key()))*unwhitenedError(c);
315  }
316 
322  boost::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
323  const X& x1 = c.at<X>(key());
324  Matrix A1;
325  Vector b = -evaluateError(x1, A1);
326  SharedDiagonal constrained =
327  boost::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
328  if (constrained.get() != nullptr) {
329  return JacobianFactor::shared_ptr(new JacobianFactor(key(), A1, b, constrained));
330  }
331  // "Whiten" the system before converting to a Gaussian Factor
332  Matrix Rinvsqrt = RInvSqrt(x1);
333  A1 = Rinvsqrt*A1;
334  b = Rinvsqrt*b;
336  }
337 
339  Vector evaluateError(const Point2& p, boost::optional<Matrix&> H1 = boost::none) const override {
340  // error = z - h(p)
341  // H = d error / d p = -d h/ d p = -H
342  Vector z_hat = h(p);
343 
344  if(H1){
345  *H1 = -H(p);
346  }
347 
348  // Return the error between the prediction and the supplied value of p2
349  return z_ - z_hat;
350  }
351 
352 };
353 
354 
355 /* ************************************************************************* */
356 TEST( ExtendedKalmanFilter, nonlinear ) {
357 
358  // Create the set of expected output TestValues (generated using Matlab Kalman Filter)
359  Point2 expected_predict[10];
360  Point2 expected_update[10];
361  expected_predict[0] = Point2(0.81,0.99);
362  expected_update[0] = Point2(0.824926197027,0.29509808);
363  expected_predict[1] = Point2(0.680503230541,0.24343413);
364  expected_update[1] = Point2(0.773360464065,0.43518355);
365  expected_predict[2] = Point2(0.598086407378,0.33655375);
366  expected_update[2] = Point2(0.908781566884,0.60766713);
367  expected_predict[3] = Point2(0.825883936308,0.55223668);
368  expected_update[3] = Point2(1.23221370495,0.74372849);
369  expected_predict[4] = Point2(1.51835061468,0.91643243);
370  expected_update[4] = Point2(1.32823362774,0.855855);
371  expected_predict[5] = Point2(1.76420456986,1.1367754);
372  expected_update[5] = Point2(1.36378040243,1.0623832);
373  expected_predict[6] = Point2(1.85989698605,1.4488574);
374  expected_update[6] = Point2(1.24068063304,1.3431964);
375  expected_predict[7] = Point2(1.53928843321,1.6664778);
376  expected_update[7] = Point2(1.04229257957,1.4856408);
377  expected_predict[8] = Point2(1.08637382142,1.5484724);
378  expected_update[8] = Point2(1.13201933157,1.5795507);
379  expected_predict[9] = Point2(1.28146776705,1.7880819);
380  expected_update[9] = Point2(1.22159588179,1.7434982);
381 
382  // Measurements
383  double z[10];
384  z[0] = 1.0;
385  z[1] = 2.0;
386  z[2] = 3.0;
387  z[3] = 4.0;
388  z[4] = 5.0;
389  z[5] = 6.0;
390  z[6] = 7.0;
391  z[7] = 8.0;
392  z[8] = 9.0;
393  z[9] = 10.0;
394 
395  // Create the Kalman Filter initialization point
396  Point2 x_initial(0.90, 1.10);
397  SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
398 
399  // Create an ExtendedKalmanFilter object
400  ExtendedKalmanFilter<Point2> ekf(X(0), x_initial, P_initial);
401 
402  // Enter Predict-Update Loop
403  Point2 x_predict(0,0), x_update(0,0);
404  for(unsigned int i = 0; i < 10; ++i){
405  // Create motion factor
406  NonlinearMotionModel motionFactor(X(i), X(i+1));
407  x_predict = ekf.predict(motionFactor);
408 
409  // Create a measurement factor
410  NonlinearMeasurementModel measurementFactor(X(i+1), (Vector(1) << z[i]).finished());
411  x_update = ekf.update(measurementFactor);
412 
413  EXPECT(assert_equal(expected_predict[i],x_predict, 1e-6));
414  EXPECT(assert_equal(expected_update[i], x_update, 1e-6));
415  }
416 
417  return;
418 }
419 
420 
421 /* ************************************************************************* */
422 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
423 /* ************************************************************************* */
NoiseModelFactor2< Point2, Point2 > Base
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Scalar * y
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector h(const Point2 &x_t1) const
static int runAllTests(TestResult &result)
Vector3f p1
JacobiRotation< float > G
NonlinearMeasurementModel(const Symbol &TestKey, Vector z)
Vector2 Point2
Definition: Point2.h:27
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Matrix H(const Point2 &x_t1) const
Key X(std::uint64_t j)
NoiseModelFactor1< Point2 > Base
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
Matrix F(const Point2 &x_t0) const
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Point2 z2
JacobianFactor factor3(keyY, A32, keyZ, A33, b3, noiseModel::Isotropic::Sigma(2, sigma3))
T update(const NoiseModelFactor &measurementFactor)
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:608
Vector whitenedError(const Values &c) const
const double dt
double error(const Values &c) const override
const Symbol key1('v', 1)
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
Signature::Row F
Definition: Signature.cpp:53
static const Unit3 z3
Class to perform generic Kalman Filtering using nonlinear factor graphs.
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
#define EXPECT(condition)
Definition: Test.h:151
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
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
T predict(const NoiseModelFactor &motionFactor)
Vector evaluateError(const Point2 &p, boost::optional< Matrix & > H1=boost::none) const override
Matrix QInvSqrt(const Point2 &x_t0) const
double error(const Values &c) const override
const G & b
Definition: Group.h:83
RowVector3d w
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
static Symbol x0('x', 0)
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
const double h
Point2 z1
Matrix inverse_square_root(const Matrix &A)
Definition: Matrix.cpp:551
Eigen::Vector2d Vector2
Definition: Vector.h:42
Non-linear factor base classes.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
The quaternion class used to represent 3D orientations and rotations.
Pose3 x1
Definition: testPose3.cpp:588
const Symbol key2('v', 2)
Key L(std::uint64_t j)
NonlinearMeasurementModel This
NonlinearMotionModel(const Symbol &TestKey1, const Symbol &TestKey2)
float * p
TEST(LPInitSolver, InfiniteLoopSingleVar)
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
boost::shared_ptr< GaussianFactor > linearize(const Values &c) const override
static Point3 p2
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Vector whitenedError(const Values &c) const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
const G double tol
Definition: Group.h:83
Vector evaluateError(const Point2 &p1, const Point2 &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix RInvSqrt(const Point2 &x_t0) const
#define X
Definition: icosphere.cpp:20
Point2 f(const Point2 &x_t0) const
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
2D Point
size_t dim() const override
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:35