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 NoiseModelFactorN<Point2,Point2> {
95 
98 
99 protected:
102 
103 public:
104 
105  // Provide access to the Matrix& version of evaluateError:
106  using Base::evaluateError;
107 
109 
110  NonlinearMotionModel(const Symbol& TestKey1, const Symbol& TestKey2) :
111  Base(noiseModel::Diagonal::Sigmas(Vector2(1.0, 1.0)), TestKey1, TestKey2), Q_(2,2) {
112 
113  // Initialize motion model parameters:
114  // w is vector of motion noise sigmas. The final covariance is calculated as G*w*w'*G'
115  // In this model, Q is fixed, so it may be calculated in the constructor
116  Matrix G(2,2);
117  Matrix w(2,2);
118 
119  G << 1.0, 0.0, 0.0, 1.0;
120  w << 1.0, 0.0, 0.0, 1.0;
121 
122  w = G*w;
123  Q_ = w*w.transpose();
124  Q_invsqrt_ = inverse_square_root(Q_);
125  }
126 
127  ~NonlinearMotionModel() override {}
128 
129  // Calculate the next state prediction using the nonlinear function f()
130  Point2 f(const Point2& x_t0) const {
131 
132  // Calculate f(x)
133  double x = x_t0.x() * x_t0.x();
134  double y = x_t0.x() * x_t0.y();
135  Point2 x_t1(x,y);
136 
137  // In this example, the noiseModel remains constant
138  return x_t1;
139  }
140 
141  // Calculate the Jacobian of the nonlinear function f()
142  Matrix F(const Point2& x_t0) const {
143  // Calculate Jacobian of f()
144  Matrix F = Matrix(2,2);
145  F(0,0) = 2*x_t0.x();
146  F(0,1) = 0.0;
147  F(1,0) = x_t0.y();
148  F(1,1) = x_t0.x();
149 
150  return F;
151  }
152 
153  // Calculate the inverse square root of the motion model covariance, Q
154  Matrix QInvSqrt(const Point2& x_t0) const {
155  // This motion model has a constant covariance
156  return Q_invsqrt_;
157  }
158 
159  /* print */
160  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
161  std::cout << s << ": NonlinearMotionModel\n";
162  std::cout << " TestKey1: " << keyFormatter(key<1>()) << std::endl;
163  std::cout << " TestKey2: " << keyFormatter(key<2>()) << std::endl;
164  }
165 
167  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
168  const This *e = dynamic_cast<const This*> (&f);
169  return (e != nullptr) && (key<1>() == e->key<1>()) && (key<2>() == e->key<2>());
170  }
171 
176  double error(const Values& c) const override {
177  Vector w = whitenedError(c);
178  return 0.5 * w.dot(w);
179  }
180 
182  size_t dim() const override {
183  return 2;
184  }
185 
187  Vector whitenedError(const Values& c) const {
188  return QInvSqrt(c.at<Point2>(key<1>()))*unwhitenedError(c);
189  }
190 
196  std::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
197  using X1 = ValueType<1>;
198  using X2 = ValueType<2>;
199  const X1& x1 = c.at<X1>(key<1>());
200  const X2& x2 = c.at<X2>(key<2>());
201  Matrix A1, A2;
202  Vector b = -evaluateError(x1, x2, A1, A2);
203  SharedDiagonal constrained =
204  std::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
205  if (constrained.get() != nullptr) {
206  return JacobianFactor::shared_ptr(new JacobianFactor(key<1>(), A1, key<2>(),
207  A2, b, constrained));
208  }
209  // "Whiten" the system before converting to a Gaussian Factor
210  Matrix Qinvsqrt = QInvSqrt(x1);
211  A1 = Qinvsqrt*A1;
212  A2 = Qinvsqrt*A2;
213  b = Qinvsqrt*b;
214  return GaussianFactor::shared_ptr(new JacobianFactor(key<1>(), A1, key<2>(),
215  A2, b, noiseModel::Unit::Create(b.size())));
216  }
217 
220  OptionalMatrixType H1, OptionalMatrixType H2) const override {
221 
222  // error = p2 - f(p1)
223  // H1 = d error / d p1 = -d f/ d p1 = -F
224  // H2 = d error / d p2 = I
225  Point2 prediction = f(p1);
226 
227  if(H1)
228  *H1 = -F(p1);
229 
230  if(H2)
231  *H2 = Matrix::Identity(dim(),dim());
232 
233  // Return the error between the prediction and the supplied value of p2
234  return (p2 - prediction);
235  }
236 
237 };
238 
239 // Create Measurement Model Factor
241 
244 
245 protected:
250 public:
251 
252  // Provide access to the Matrix& version of evaluateError:
253  using Base::evaluateError;
254 
256 
258  Base(noiseModel::Unit::Create(z.size()), TestKey), z_(z), R_(1,1) {
259 
260  // Initialize nonlinear measurement model parameters:
261  // z(t) = H*x(t) + v
262  // where v ~ N(0, noiseModel_)
263  R_ << 1.0;
264  R_invsqrt_ = inverse_square_root(R_);
265  }
266 
268 
269  // Calculate the predicted measurement using the nonlinear function h()
270  // Byproduct: updates Jacobian H, and noiseModel (R)
271  Vector h(const Point2& x_t1) const {
272 
273  // Calculate prediction
274  Vector z_hat(1);
275  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();
276 
277  return z_hat;
278  }
279 
280  Matrix H(const Point2& x_t1) const {
281  // Update Jacobian
282  Matrix H(1,2);
283  H(0,0) = 4*x_t1.x() - x_t1.y() - 2.5;
284  H(0,1) = -1*x_t1.x() + 7;
285 
286  return H;
287  }
288 
289  // Calculate the inverse square root of the motion model covariance, Q
290  Matrix RInvSqrt(const Point2& x_t0) const {
291  // This motion model has a constant covariance
292  return R_invsqrt_;
293  }
294 
295  /* print */
296  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
297  std::cout << s << ": NonlinearMeasurementModel\n";
298  std::cout << " TestKey: " << keyFormatter(key()) << std::endl;
299  }
300 
302  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
303  const This *e = dynamic_cast<const This*> (&f);
304  return (e != nullptr) && Base::equals(f);
305  }
306 
311  double error(const Values& c) const override {
312  Vector w = whitenedError(c);
313  return 0.5 * w.dot(w);
314  }
315 
317  size_t dim() const override {
318  return 1;
319  }
320 
322  Vector whitenedError(const Values& c) const {
323  return RInvSqrt(c.at<Point2>(key()))*unwhitenedError(c);
324  }
325 
331  std::shared_ptr<GaussianFactor> linearize(const Values& c) const override {
332  using X = ValueType<1>;
333  const X& x1 = c.at<X>(key());
334  Matrix A1;
335  Vector b = -evaluateError(x1, A1);
336  SharedDiagonal constrained =
337  std::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
338  if (constrained.get() != nullptr) {
339  return JacobianFactor::shared_ptr(new JacobianFactor(key(), A1, b, constrained));
340  }
341  // "Whiten" the system before converting to a Gaussian Factor
342  Matrix Rinvsqrt = RInvSqrt(x1);
343  A1 = Rinvsqrt*A1;
344  b = Rinvsqrt*b;
346  }
347 
349  Vector evaluateError(const Point2& p, OptionalMatrixType H1) const override {
350  // error = z - h(p)
351  // H = d error / d p = -d h/ d p = -H
352  Vector z_hat = h(p);
353 
354  if(H1){
355  *H1 = -H(p);
356  }
357 
358  // Return the error between the prediction and the supplied value of p2
359  return z_ - z_hat;
360  }
361 
362 };
363 
364 
365 /* ************************************************************************* */
366 TEST( ExtendedKalmanFilter, nonlinear ) {
367 
368  // Create the set of expected output TestValues (generated using Matlab Kalman Filter)
369  Point2 expected_predict[10];
370  Point2 expected_update[10];
371  expected_predict[0] = Point2(0.81,0.99);
372  expected_update[0] = Point2(0.824926197027,0.29509808);
373  expected_predict[1] = Point2(0.680503230541,0.24343413);
374  expected_update[1] = Point2(0.773360464065,0.43518355);
375  expected_predict[2] = Point2(0.598086407378,0.33655375);
376  expected_update[2] = Point2(0.908781566884,0.60766713);
377  expected_predict[3] = Point2(0.825883936308,0.55223668);
378  expected_update[3] = Point2(1.23221370495,0.74372849);
379  expected_predict[4] = Point2(1.51835061468,0.91643243);
380  expected_update[4] = Point2(1.32823362774,0.855855);
381  expected_predict[5] = Point2(1.76420456986,1.1367754);
382  expected_update[5] = Point2(1.36378040243,1.0623832);
383  expected_predict[6] = Point2(1.85989698605,1.4488574);
384  expected_update[6] = Point2(1.24068063304,1.3431964);
385  expected_predict[7] = Point2(1.53928843321,1.6664778);
386  expected_update[7] = Point2(1.04229257957,1.4856408);
387  expected_predict[8] = Point2(1.08637382142,1.5484724);
388  expected_update[8] = Point2(1.13201933157,1.5795507);
389  expected_predict[9] = Point2(1.28146776705,1.7880819);
390  expected_update[9] = Point2(1.22159588179,1.7434982);
391 
392  // Measurements
393  double z[10];
394  z[0] = 1.0;
395  z[1] = 2.0;
396  z[2] = 3.0;
397  z[3] = 4.0;
398  z[4] = 5.0;
399  z[5] = 6.0;
400  z[6] = 7.0;
401  z[7] = 8.0;
402  z[8] = 9.0;
403  z[9] = 10.0;
404 
405  // Create the Kalman Filter initialization point
406  Point2 x_initial(0.90, 1.10);
407  SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
408 
409  // Create an ExtendedKalmanFilter object
410  ExtendedKalmanFilter<Point2> ekf(X(0), x_initial, P_initial);
411 
412  // Enter Predict-Update Loop
413  Point2 x_predict(0,0), x_update(0,0);
414  for(unsigned int i = 0; i < 10; ++i){
415  // Create motion factor
416  NonlinearMotionModel motionFactor(X(i), X(i+1));
417  x_predict = ekf.predict(motionFactor);
418 
419  // Create a measurement factor
420  NonlinearMeasurementModel measurementFactor(X(i+1), (Vector(1) << z[i]).finished());
421  x_update = ekf.update(measurementFactor);
422 
423  EXPECT(assert_equal(expected_predict[i],x_predict, 1e-6));
424  EXPECT(assert_equal(expected_update[i], x_update, 1e-6));
425  }
426 
427  return;
428 }
429 
430 
431 /* ************************************************************************* */
432 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
433 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
NonlinearMotionModel::NonlinearMotionModel
NonlinearMotionModel(const Symbol &TestKey1, const Symbol &TestKey2)
Definition: testExtendedKalmanFilter.cpp:110
H
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
Definition: gnuplot_common_settings.hh:74
NonlinearMeasurementModel::evaluateError
Vector evaluateError(const Point2 &p, OptionalMatrixType H1) const override
Definition: testExtendedKalmanFilter.cpp:349
NonlinearMotionModel::~NonlinearMotionModel
~NonlinearMotionModel() override
Definition: testExtendedKalmanFilter.cpp:127
NonlinearMotionModel::QInvSqrt
Matrix QInvSqrt(const Point2 &x_t0) const
Definition: testExtendedKalmanFilter.cpp:154
simple_graph::factor2
auto factor2
Definition: testJacobianFactor.cpp:203
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
NonlinearMeasurementModel::h
Vector h(const Point2 &x_t1) const
Definition: testExtendedKalmanFilter.cpp:271
TestHarness.h
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
NonlinearMeasurementModel::Base
NoiseModelFactorN< Point2 > Base
Definition: testExtendedKalmanFilter.cpp:242
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
NonlinearMeasurementModel::NonlinearMeasurementModel
NonlinearMeasurementModel()
Definition: testExtendedKalmanFilter.cpp:255
gtsam::inverse_square_root
Matrix inverse_square_root(const Matrix &A)
Definition: Matrix.cpp:550
NonlinearMeasurementModel::z_
Vector z_
Definition: testExtendedKalmanFilter.cpp:246
NonlinearMotionModel::Q_
Matrix Q_
Definition: testExtendedKalmanFilter.cpp:100
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
NonlinearMotionModel::f
Point2 f(const Point2 &x_t0) const
Definition: testExtendedKalmanFilter.cpp:130
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
dt
const double dt
Definition: testVelocityConstraint.cpp:15
main
int main()
Definition: testExtendedKalmanFilter.cpp:432
NonlinearMotionModel::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &c) const override
Definition: testExtendedKalmanFilter.cpp:196
NonlinearMotionModel::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: testExtendedKalmanFilter.cpp:160
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
NonlinearMeasurementModel::R_invsqrt_
Matrix R_invsqrt_
Definition: testExtendedKalmanFilter.cpp:248
NonlinearMeasurementModel
Definition: testExtendedKalmanFilter.cpp:240
NonlinearMotionModel::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: testExtendedKalmanFilter.cpp:167
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:270
NonlinearMotionModel::Q_invsqrt_
Matrix Q_invsqrt_
Definition: testExtendedKalmanFilter.cpp:101
X
#define X
Definition: icosphere.cpp:20
gtsam::Factor
Definition: Factor.h:69
gtsam::ExtendedKalmanFilter
Definition: ExtendedKalmanFilter.h:45
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
x3
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Point2.h
2D Point
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam::symbol_shorthand::X
Key X(std::uint64_t j)
Definition: inference/Symbol.h:171
PriorFactor.h
z3
static const Unit3 z3
Definition: testRotateFactor.cpp:44
NonlinearMotionModel::F
Matrix F(const Point2 &x_t0) const
Definition: testExtendedKalmanFilter.cpp:142
NonlinearMeasurementModel::NonlinearMeasurementModel
NonlinearMeasurementModel(const Symbol &TestKey, Vector z)
Definition: testExtendedKalmanFilter.cpp:257
NonlinearMeasurementModel::H
Matrix H(const Point2 &x_t1) const
Definition: testExtendedKalmanFilter.cpp:280
gtsam::ExtendedKalmanFilter::update
T update(const NoiseModelFactor &measurementFactor)
Definition: ExtendedKalmanFilter-inl.h:104
BetweenFactor.h
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::KeyFormatter
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
NonlinearMeasurementModel::error
double error(const Values &c) const override
Definition: testExtendedKalmanFilter.cpp:311
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
A2
static const double A2[]
Definition: expn.h:7
x0
static Symbol x0('x', 0)
NonlinearMotionModel::whitenedError
Vector whitenedError(const Values &c) const
Definition: testExtendedKalmanFilter.cpp:187
NonlinearMotionModel::This
NonlinearMotionModel This
Definition: testExtendedKalmanFilter.cpp:97
Symbol.h
gtsam::symbol_shorthand::L
Key L(std::uint64_t j)
Definition: inference/Symbol.h:159
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
Vector2
Definition: test_operator_overloading.cpp:18
NonlinearMotionModel::NonlinearMotionModel
NonlinearMotionModel()
Definition: testExtendedKalmanFilter.cpp:108
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
NonlinearMotionModel::Base
NoiseModelFactorN< Point2, Point2 > Base
Definition: testExtendedKalmanFilter.cpp:96
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
NonlinearMeasurementModel::whitenedError
Vector whitenedError(const Values &c) const
Definition: testExtendedKalmanFilter.cpp:322
NonlinearMotionModel::error
double error(const Values &c) const override
Definition: testExtendedKalmanFilter.cpp:176
NonlinearMeasurementModel::This
NonlinearMeasurementModel This
Definition: testExtendedKalmanFilter.cpp:243
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
gtsam::ExtendedKalmanFilter::predict
T predict(const NoiseModelFactor &motionFactor)
Definition: ExtendedKalmanFilter-inl.h:79
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
NonlinearFactor.h
Non-linear factor base classes.
simple_graph::factor3
auto factor3
Definition: testJacobianFactor.cpp:210
gtsam::b
const G & b
Definition: Group.h:79
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
NonlinearMotionModel
Definition: testExtendedKalmanFilter.cpp:94
gtsam
traits
Definition: chartTesting.h:28
ExtendedKalmanFilter-inl.h
Class to perform generic Kalman Filtering using nonlinear factor graphs.
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
gtsam::Values
Definition: Values.h:65
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
NonlinearMeasurementModel::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: testExtendedKalmanFilter.cpp:296
p
float * p
Definition: Tutorial_Map_using.cpp:9
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
gtsam::Diagonal
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
Definition: ScenarioRunner.h:27
A1
static const double A1[]
Definition: expn.h:6
NonlinearMeasurementModel::RInvSqrt
Matrix RInvSqrt(const Point2 &x_t0) const
Definition: testExtendedKalmanFilter.cpp:290
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
NonlinearMeasurementModel::~NonlinearMeasurementModel
~NonlinearMeasurementModel() override
Definition: testExtendedKalmanFilter.cpp:267
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::JacobianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: JacobianFactor.h:97
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
NonlinearMeasurementModel::dim
size_t dim() const override
Definition: testExtendedKalmanFilter.cpp:317
NonlinearMotionModel::dim
size_t dim() const override
Definition: testExtendedKalmanFilter.cpp:182
NonlinearMeasurementModel::R_
Matrix R_
Definition: testExtendedKalmanFilter.cpp:247
gtsam::NoiseModelFactorN< Point2, Point2 >::ValueType
typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type ValueType
Definition: NonlinearFactor.h:525
NonlinearMotionModel::evaluateError
Vector evaluateError(const Point2 &p1, const Point2 &p2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Definition: testExtendedKalmanFilter.cpp:219
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
R
Rot2 R(Rot2::fromAngle(0.1))
simple_graph::factor1
auto factor1
Definition: testJacobianFactor.cpp:196
NonlinearMeasurementModel::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &c) const override
Definition: testExtendedKalmanFilter.cpp:331
z2
static const Unit3 z2
Definition: testRotateFactor.cpp:43
gtsam::Symbol
Definition: inference/Symbol.h:37
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
NonlinearMeasurementModel::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: testExtendedKalmanFilter.cpp:302


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:09:14