testExtendedKalmanFilter.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file testExtendedKalmanFilter
  10. * @author Stephen Williams
  11. */
  12. #include <gtsam/nonlinear/PriorFactor.h>
  13. #include <gtsam/slam/BetweenFactor.h>
  14. #include <gtsam/nonlinear/ExtendedKalmanFilter-inl.h>
  15. #include <gtsam/nonlinear/NonlinearFactor.h>
  16. #include <gtsam/inference/Symbol.h>
  17. #include <gtsam/geometry/Point2.h>
  18. #include <CppUnitLite/TestHarness.h>
  19. using namespace gtsam;
  20. // Convenience for named keys
  21. using symbol_shorthand::X;
  22. using symbol_shorthand::L;
  23. /* ************************************************************************* */
  24. TEST( ExtendedKalmanFilter, linear ) {
  25. // Create the TestKeys for our example
  26. Symbol x0('x',0), x1('x',1), x2('x',2), x3('x',3);
  27. // Create the Kalman Filter initialization point
  28. Point2 x_initial(0.0, 0.0);
  29. SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
  30. // Create an ExtendedKalmanFilter object
  31. ExtendedKalmanFilter<Point2> ekf(x0, x_initial, P_initial);
  32. // Create the controls and measurement properties for our example
  33. double dt = 1.0;
  34. Vector u = Vector2(1.0, 0.0);
  35. Point2 difference(u*dt);
  36. SharedDiagonal Q = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1), true);
  37. Point2 z1(1.0, 0.0);
  38. Point2 z2(2.0, 0.0);
  39. Point2 z3(3.0, 0.0);
  40. SharedDiagonal R = noiseModel::Diagonal::Sigmas(Vector2(0.25, 0.25), true);
  41. // Create the set of expected output TestValues
  42. Point2 expected1(1.0, 0.0);
  43. Point2 expected2(2.0, 0.0);
  44. Point2 expected3(3.0, 0.0);
  45. // Run iteration 1
  46. // Create motion factor
  47. BetweenFactor<Point2> factor1(x0, x1, difference, Q);
  48. Point2 predict1 = ekf.predict(factor1);
  49. EXPECT(assert_equal(expected1,predict1));
  50. // Create the measurement factor
  51. PriorFactor<Point2> factor2(x1, z1, R);
  52. Point2 update1 = ekf.update(factor2);
  53. EXPECT(assert_equal(expected1,update1));
  54. // Run iteration 2
  55. BetweenFactor<Point2> factor3(x1, x2, difference, Q);
  56. Point2 predict2 = ekf.predict(factor3);
  57. EXPECT(assert_equal(expected2,predict2));
  58. PriorFactor<Point2> factor4(x2, z2, R);
  59. Point2 update2 = ekf.update(factor4);
  60. EXPECT(assert_equal(expected2,update2));
  61. // Run iteration 3
  62. BetweenFactor<Point2> factor5(x2, x3, difference, Q);
  63. Point2 predict3 = ekf.predict(factor5);
  64. EXPECT(assert_equal(expected3,predict3));
  65. PriorFactor<Point2> factor6(x3, z3, R);
  66. Point2 update3 = ekf.update(factor6);
  67. EXPECT(assert_equal(expected3,update3));
  68. return;
  69. }
  70. // Create Motion Model Factor
  71. class NonlinearMotionModel : public NoiseModelFactor2<Point2,Point2> {
  72. typedef NoiseModelFactor2<Point2, Point2> Base;
  73. typedef NonlinearMotionModel This;
  74. protected:
  75. Matrix Q_;
  76. Matrix Q_invsqrt_;
  77. public:
  78. NonlinearMotionModel(){}
  79. NonlinearMotionModel(const Symbol& TestKey1, const Symbol& TestKey2) :
  80. Base(noiseModel::Diagonal::Sigmas(Vector2(1.0, 1.0)), TestKey1, TestKey2), Q_(2,2) {
  81. // Initialize motion model parameters:
  82. // w is vector of motion noise sigmas. The final covariance is calculated as G*w*w'*G'
  83. // In this model, Q is fixed, so it may be calculated in the constructor
  84. Matrix G(2,2);
  85. Matrix w(2,2);
  86. G << 1.0, 0.0, 0.0, 1.0;
  87. w << 1.0, 0.0, 0.0, 1.0;
  88. w = G*w;
  89. Q_ = w*w.transpose();
  90. Q_invsqrt_ = inverse_square_root(Q_);
  91. }
  92. ~NonlinearMotionModel() override {}
  93. // Calculate the next state prediction using the nonlinear function f()
  94. Point2 f(const Point2& x_t0) const {
  95. // Calculate f(x)
  96. double x = x_t0.x() * x_t0.x();
  97. double y = x_t0.x() * x_t0.y();
  98. Point2 x_t1(x,y);
  99. // In this example, the noiseModel remains constant
  100. return x_t1;
  101. }
  102. // Calculate the Jacobian of the nonlinear function f()
  103. Matrix F(const Point2& x_t0) const {
  104. // Calculate Jacobian of f()
  105. Matrix F = Matrix(2,2);
  106. F(0,0) = 2*x_t0.x();
  107. F(0,1) = 0.0;
  108. F(1,0) = x_t0.y();
  109. F(1,1) = x_t0.x();
  110. return F;
  111. }
  112. // Calculate the inverse square root of the motion model covariance, Q
  113. Matrix QInvSqrt(const Point2& x_t0) const {
  114. // This motion model has a constant covariance
  115. return Q_invsqrt_;
  116. }
  117. /* print */
  118. void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
  119. std::cout << s << ": NonlinearMotionModel\n";
  120. std::cout << " TestKey1: " << keyFormatter(key1()) << std::endl;
  121. std::cout << " TestKey2: " << keyFormatter(key2()) << std::endl;
  122. }
  123. /** Check if two factors are equal. Note type is IndexFactor and needs cast. */
  124. bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
  125. const This *e = dynamic_cast<const This*> (&f);
  126. return (e != nullptr) && (key1() == e->key1()) && (key2() == e->key2());
  127. }
  128. /**
  129. * calculate the error of the factor
  130. * Override for systems with unusual noise models
  131. */
  132. double error(const Values& c) const override {
  133. Vector w = whitenedError(c);
  134. return 0.5 * w.dot(w);
  135. }
  136. /** get the dimension of the factor (number of rows on linearization) */
  137. size_t dim() const override {
  138. return 2;
  139. }
  140. /** Vector of errors, whitened ! */
  141. Vector whitenedError(const Values& c) const {
  142. return QInvSqrt(c.at<Point2>(key1()))*unwhitenedError(c);
  143. }
  144. /**
  145. * Linearize a non-linearFactor2 to get a GaussianFactor
  146. * Ax-b \approx h(x1+dx1,x2+dx2)-z = h(x1,x2) + A2*dx1 + A2*dx2 - z
  147. * Hence b = z - h(x1,x2) = - error_vector(x)
  148. */
  149. boost::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
  150. const X1& x1 = c.at<X1>(key1());
  151. const X2& x2 = c.at<X2>(key2());
  152. Matrix A1, A2;
  153. Vector b = -evaluateError(x1, x2, A1, A2);
  154. SharedDiagonal constrained =
  155. boost::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
  156. if (constrained.get() != nullptr) {
  157. return JacobianFactor::shared_ptr(new JacobianFactor(key1(), A1, key2(),
  158. A2, b, constrained));
  159. }
  160. // "Whiten" the system before converting to a Gaussian Factor
  161. Matrix Qinvsqrt = QInvSqrt(x1);
  162. A1 = Qinvsqrt*A1;
  163. A2 = Qinvsqrt*A2;
  164. b = Qinvsqrt*b;
  165. return GaussianFactor::shared_ptr(new JacobianFactor(key1(), A1, key2(),
  166. A2, b, noiseModel::Unit::Create(b.size())));
  167. }
  168. /** vector of errors */
  169. Vector evaluateError(const Point2& p1, const Point2& p2,
  170. boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
  171. boost::none) const override {
  172. // error = p2 - f(p1)
  173. // H1 = d error / d p1 = -d f/ d p1 = -F
  174. // H2 = d error / d p2 = I
  175. Point2 prediction = f(p1);
  176. if(H1)
  177. *H1 = -F(p1);
  178. if(H2)
  179. *H2 = Matrix::Identity(dim(),dim());
  180. // Return the error between the prediction and the supplied value of p2
  181. return (p2 - prediction);
  182. }
  183. };
  184. // Create Measurement Model Factor
  185. class NonlinearMeasurementModel : public NoiseModelFactor1<Point2> {
  186. typedef NoiseModelFactor1<Point2> Base;
  187. typedef NonlinearMeasurementModel This;
  188. protected:
  189. Vector z_; /** The measurement */
  190. Matrix R_; /** The measurement error covariance */
  191. Matrix R_invsqrt_; /** The inv sqrt of the measurement error covariance */
  192. public:
  193. NonlinearMeasurementModel(){}
  194. NonlinearMeasurementModel(const Symbol& TestKey, Vector z) :
  195. Base(noiseModel::Unit::Create(z.size()), TestKey), z_(z), R_(1,1) {
  196. // Initialize nonlinear measurement model parameters:
  197. // z(t) = H*x(t) + v
  198. // where v ~ N(0, noiseModel_)
  199. R_ << 1.0;
  200. R_invsqrt_ = inverse_square_root(R_);
  201. }
  202. ~NonlinearMeasurementModel() override {}
  203. // Calculate the predicted measurement using the nonlinear function h()
  204. // Byproduct: updates Jacobian H, and noiseModel (R)
  205. Vector h(const Point2& x_t1) const {
  206. // Calculate prediction
  207. Vector z_hat(1);
  208. 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();
  209. return z_hat;
  210. }
  211. Matrix H(const Point2& x_t1) const {
  212. // Update Jacobian
  213. Matrix H(1,2);
  214. H(0,0) = 4*x_t1.x() - x_t1.y() - 2.5;
  215. H(0,1) = -1*x_t1.x() + 7;
  216. return H;
  217. }
  218. // Calculate the inverse square root of the motion model covariance, Q
  219. Matrix RInvSqrt(const Point2& x_t0) const {
  220. // This motion model has a constant covariance
  221. return R_invsqrt_;
  222. }
  223. /* print */
  224. void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
  225. std::cout << s << ": NonlinearMeasurementModel\n";
  226. std::cout << " TestKey: " << keyFormatter(key()) << std::endl;
  227. }
  228. /** Check if two factors are equal. Note type is IndexFactor and needs cast. */
  229. bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
  230. const This *e = dynamic_cast<const This*> (&f);
  231. return (e != nullptr) && Base::equals(f);
  232. }
  233. /**
  234. * calculate the error of the factor
  235. * Override for systems with unusual noise models
  236. */
  237. double error(const Values& c) const override {
  238. Vector w = whitenedError(c);
  239. return 0.5 * w.dot(w);
  240. }
  241. /** get the dimension of the factor (number of rows on linearization) */
  242. size_t dim() const override {
  243. return 1;
  244. }
  245. /** Vector of errors, whitened ! */
  246. Vector whitenedError(const Values& c) const {
  247. return RInvSqrt(c.at<Point2>(key()))*unwhitenedError(c);
  248. }
  249. /**
  250. * Linearize a nonlinearFactor1 measurement factor into a GaussianFactor
  251. * Ax-b \approx h(x1+dx1)-z = h(x1) + A1*dx1 - z
  252. * Hence b = z - h(x1) = - error_vector(x)
  253. */
  254. boost::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
  255. const X& x1 = c.at<X>(key());
  256. Matrix A1;
  257. Vector b = -evaluateError(x1, A1);
  258. SharedDiagonal constrained =
  259. boost::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
  260. if (constrained.get() != nullptr) {
  261. return JacobianFactor::shared_ptr(new JacobianFactor(key(), A1, b, constrained));
  262. }
  263. // "Whiten" the system before converting to a Gaussian Factor
  264. Matrix Rinvsqrt = RInvSqrt(x1);
  265. A1 = Rinvsqrt*A1;
  266. b = Rinvsqrt*b;
  267. return GaussianFactor::shared_ptr(new JacobianFactor(key(), A1, b, noiseModel::Unit::Create(b.size())));
  268. }
  269. /** vector of errors */
  270. Vector evaluateError(const Point2& p, boost::optional<Matrix&> H1 = boost::none) const override {
  271. // error = z - h(p)
  272. // H = d error / d p = -d h/ d p = -H
  273. Vector z_hat = h(p);
  274. if(H1){
  275. *H1 = -H(p);
  276. }
  277. // Return the error between the prediction and the supplied value of p2
  278. return z_ - z_hat;
  279. }
  280. };
  281. /* ************************************************************************* */
  282. TEST( ExtendedKalmanFilter, nonlinear ) {
  283. // Create the set of expected output TestValues (generated using Matlab Kalman Filter)
  284. Point2 expected_predict[10];
  285. Point2 expected_update[10];
  286. expected_predict[0] = Point2(0.81,0.99);
  287. expected_update[0] = Point2(0.824926197027,0.29509808);
  288. expected_predict[1] = Point2(0.680503230541,0.24343413);
  289. expected_update[1] = Point2(0.773360464065,0.43518355);
  290. expected_predict[2] = Point2(0.598086407378,0.33655375);
  291. expected_update[2] = Point2(0.908781566884,0.60766713);
  292. expected_predict[3] = Point2(0.825883936308,0.55223668);
  293. expected_update[3] = Point2(1.23221370495,0.74372849);
  294. expected_predict[4] = Point2(1.51835061468,0.91643243);
  295. expected_update[4] = Point2(1.32823362774,0.855855);
  296. expected_predict[5] = Point2(1.76420456986,1.1367754);
  297. expected_update[5] = Point2(1.36378040243,1.0623832);
  298. expected_predict[6] = Point2(1.85989698605,1.4488574);
  299. expected_update[6] = Point2(1.24068063304,1.3431964);
  300. expected_predict[7] = Point2(1.53928843321,1.6664778);
  301. expected_update[7] = Point2(1.04229257957,1.4856408);
  302. expected_predict[8] = Point2(1.08637382142,1.5484724);
  303. expected_update[8] = Point2(1.13201933157,1.5795507);
  304. expected_predict[9] = Point2(1.28146776705,1.7880819);
  305. expected_update[9] = Point2(1.22159588179,1.7434982);
  306. // Measurements
  307. double z[10];
  308. z[0] = 1.0;
  309. z[1] = 2.0;
  310. z[2] = 3.0;
  311. z[3] = 4.0;
  312. z[4] = 5.0;
  313. z[5] = 6.0;
  314. z[6] = 7.0;
  315. z[7] = 8.0;
  316. z[8] = 9.0;
  317. z[9] = 10.0;
  318. // Create the Kalman Filter initialization point
  319. Point2 x_initial(0.90, 1.10);
  320. SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
  321. // Create an ExtendedKalmanFilter object
  322. ExtendedKalmanFilter<Point2> ekf(X(0), x_initial, P_initial);
  323. // Enter Predict-Update Loop
  324. Point2 x_predict(0,0), x_update(0,0);
  325. for(unsigned int i = 0; i < 10; ++i){
  326. // Create motion factor
  327. NonlinearMotionModel motionFactor(X(i), X(i+1));
  328. x_predict = ekf.predict(motionFactor);
  329. // Create a measurement factor
  330. NonlinearMeasurementModel measurementFactor(X(i+1), (Vector(1) << z[i]).finished());
  331. x_update = ekf.update(measurementFactor);
  332. EXPECT(assert_equal(expected_predict[i],x_predict, 1e-6));
  333. EXPECT(assert_equal(expected_update[i], x_update, 1e-6));
  334. }
  335. return;
  336. }
  337. /* ************************************************************************* */
  338. int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
  339. /* ************************************************************************* */