elaboratePoint2KalmanFilter.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 
25 //#include <gtsam/nonlinear/Ordering.h>
26 #include <gtsam/inference/Symbol.h>
30 #include <gtsam/geometry/Point2.h>
31 
32 using namespace std;
33 using namespace gtsam;
34 
35 int main() {
36 
37  // [code below basically does SRIF with Cholesky]
38 
39  // Create a factor graph to perform the inference
41 
42  // Create the desired ordering
44 
45  // Create a structure to hold the linearization points
46  Values linearizationPoints;
47 
48  // Ground truth example
49  // Start at origin, move to the right (x-axis): 0,0 0,1 0,2
50  // Motion model is just moving to the right (x'-x)^2
51  // Measurements are GPS like, (x-z)^2, where z is a 2D measurement
52  // i.e., we should get 0,0 0,1 0,2 if there is no noise
53 
54  // Create new state variable
55  Symbol x0('x',0);
56  ordering->insert(x0, 0);
57 
58  // Initialize state x0 (2D point) at origin by adding a prior factor, i.e., Bayes net P(x0)
59  // This is equivalent to x_0 and P_0
60  Point2 x_initial(0,0);
61  SharedDiagonal P_initial = noiseModel::Diagonal::Sigmas((Vec(2) << 0.1, 0.1));
62  PriorFactor<Point2> factor1(x0, x_initial, P_initial);
63  // Linearize the factor and add it to the linear factor graph
64  linearizationPoints.insert(x0, x_initial);
65  linearFactorGraph->push_back(factor1.linearize(linearizationPoints, *ordering));
66 
67 
68  // Now predict the state at t=1, i.e. argmax_{x1} P(x1) = P(x1|x0) P(x0)
69  // In Kalman Filter notation, this is x_{t+1|t} and P_{t+1|t}
70  // For the Kalman Filter, this requires a motion model, f(x_{t}) = x_{t+1|t)
71  // Assuming the system is linear, this will be of the form f(x_{t}) = F*x_{t} + B*u_{t} + w
72  // where F is the state transition model/matrix, B is the control input model,
73  // and w is zero-mean, Gaussian white noise with covariance Q
74  // Note, in some models, Q is actually derived as G*w*G^T where w models uncertainty of some
75  // physical property, such as velocity or acceleration, and G is derived from physics
76  //
77  // For the purposes of this example, let us assume we are using a constant-position model and
78  // the controls are driving the point to the right at 1 m/s. Then, F = [1 0 ; 0 1], B = [1 0 ; 0 1]
79  // and u = [1 ; 0]. Let us also assume that the process noise Q = [0.1 0 ; 0 0.1];
80  //
81  // In the case of factor graphs, the factor related to the motion model would be defined as
82  // f2 = (f(x_{t}) - x_{t+1}) * Q^-1 * (f(x_{t}) - x_{t+1})^T
83  // Conveniently, there is a factor type, called a BetweenFactor, that can generate this factor
84  // given the expected difference, f(x_{t}) - x_{t+1}, and Q.
85  // so, difference = x_{t+1} - x_{t} = F*x_{t} + B*u_{t} - I*x_{t}
86  // = (F - I)*x_{t} + B*u_{t}
87  // = B*u_{t} (for our example)
88  Symbol x1('x',1);
89  ordering->insert(x1, 1);
90 
91  Point2 difference(1,0);
92  SharedDiagonal Q = noiseModel::Diagonal::Sigmas((Vec(2) << 0.1, 0.1));
93  BetweenFactor<Point2> factor2(x0, x1, difference, Q);
94  // Linearize the factor and add it to the linear factor graph
95  linearizationPoints.insert(x1, x_initial);
96  linearFactorGraph->push_back(factor2.linearize(linearizationPoints, *ordering));
97 
98  // We have now made the small factor graph f1-(x0)-f2-(x1)
99  // where factor f1 is just the prior from time t0, P(x0)
100  // and factor f2 is from the motion model
101  // Eliminate this in order x0, x1, to get Bayes net P(x0|x1)P(x1)
102  // As this is a filter, all we need is the posterior P(x1), so we just keep the root of the Bayes net
103  //
104  // Because of the way GTSAM works internally, we have used nonlinear class even though this example
105  // system is linear. We first convert the nonlinear factor graph into a linear one, using the specified
106  // ordering. Linear factors are simply numbered, and are not accessible via named key like the nonlinear
107  // variables. Also, the nonlinear factors are linearized around an initial estimate. For a true linear
108  // system, the initial estimate is not important.
109 
110  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x0,x1) = P(x0|x1)*P(x1) )
111  GaussianSequentialSolver solver0(*linearFactorGraph);
112  GaussianBayesNet::shared_ptr linearBayesNet = solver0.eliminate();
113 
114  // Extract the current estimate of x1,P1 from the Bayes Network
115  VectorValues result = optimize(*linearBayesNet);
116  Point2 x1_predict = linearizationPoints.at<Point2>(x1).retract(result[ordering->at(x1)]);
117  x1_predict.print("X1 Predict");
118 
119  // Update the new linearization point to the new estimate
120  linearizationPoints.update(x1, x1_predict);
121 
122 
123 
124  // Create a new, empty graph and add the prior from the previous step
125  linearFactorGraph = GaussianFactorGraph::shared_ptr(new GaussianFactorGraph);
126 
127  // Convert the root conditional, P(x1) in this case, into a Prior for the next step
128  // Some care must be done here, as the linearization point in future steps will be different
129  // than what was used when the factor was created.
130  // f = || F*dx1' - (F*x0 - x1) ||^2, originally linearized at x1 = x0
131  // After this step, the factor needs to be linearized around x1 = x1_predict
132  // This changes the factor to f = || F*dx1'' - b'' ||^2
133  // = || F*(dx1' - (dx1' - dx1'')) - b'' ||^2
134  // = || F*dx1' - F*(dx1' - dx1'') - b'' ||^2
135  // = || F*dx1' - (b'' + F(dx1' - dx1'')) ||^2
136  // -> b' = b'' + F(dx1' - dx1'')
137  // -> b'' = b' - F(dx1' - dx1'')
138  // = || F*dx1'' - (b' - F(dx1' - dx1'')) ||^2
139  // = || F*dx1'' - (b' - F(x_predict - x_inital)) ||^2
140  const GaussianConditional::shared_ptr& cg0 = linearBayesNet->back();
141  assert(cg0->nrFrontals() == 1);
142  assert(cg0->nrParents() == 0);
143  linearFactorGraph->add(0, cg0->R(), cg0->d() - cg0->R()*result[ordering->at(x1)], noiseModel::Diagonal::Sigmas(cg0->get_sigmas(), true));
144 
145  // Create the desired ordering
147  ordering->insert(x1, 0);
148 
149  // Now, a measurement, z1, has been received, and the Kalman Filter should be "Updated"/"Corrected"
150  // This is equivalent to saying P(x1|z1) ~ P(z1|x1)*P(x1) ~ f3(x1)*f4(x1;z1)
151  // where f3 is the prior from the previous step, and
152  // where f4 is a measurement factor
153  //
154  // So, now we need to create the measurement factor, f4
155  // For the Kalman Filter, this is the measurement function, h(x_{t}) = z_{t}
156  // Assuming the system is linear, this will be of the form h(x_{t}) = H*x_{t} + v
157  // where H is the observation model/matrix, and v is zero-mean, Gaussian white noise with covariance R
158  //
159  // For the purposes of this example, let us assume we have something like a GPS that returns
160  // the current position of the robot. For this simple example, we can use a PriorFactor to model the
161  // observation as it depends on only a single state variable, x1. To model real sensor observations
162  // generally requires the creation of a new factor type. For example, factors for range sensors, bearing
163  // sensors, and camera projections have already been added to GTSAM.
164  //
165  // In the case of factor graphs, the factor related to the measurements would be defined as
166  // f4 = (h(x_{t}) - z_{t}) * R^-1 * (h(x_{t}) - z_{t})^T
167  // = (x_{t} - z_{t}) * R^-1 * (x_{t} - z_{t})^T
168  // This can be modeled using the PriorFactor, where the mean is z_{t} and the covariance is R.
169  Point2 z1(1.0, 0.0);
170  SharedDiagonal R1 = noiseModel::Diagonal::Sigmas((Vec(2) << 0.25, 0.25));
171  PriorFactor<Point2> factor4(x1, z1, R1);
172  // Linearize the factor and add it to the linear factor graph
173  linearFactorGraph->push_back(factor4.linearize(linearizationPoints, *ordering));
174 
175  // We have now made the small factor graph f3-(x1)-f4
176  // where factor f3 is the prior from previous time ( P(x1) )
177  // and factor f4 is from the measurement, z1 ( P(x1|z1) )
178  // Eliminate this in order x1, to get Bayes net P(x1)
179  // As this is a filter, all we need is the posterior P(x1), so we just keep the root of the Bayes net
180  // We solve as before...
181 
182  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x0,x1) = P(x0|x1)*P(x1) )
183  GaussianSequentialSolver solver1(*linearFactorGraph);
184  linearBayesNet = solver1.eliminate();
185 
186  // Extract the current estimate of x1 from the Bayes Network
187  result = optimize(*linearBayesNet);
188  Point2 x1_update = linearizationPoints.at<Point2>(x1).retract(result[ordering->at(x1)]);
189  x1_update.print("X1 Update");
190 
191  // Update the linearization point to the new estimate
192  linearizationPoints.update(x1, x1_update);
193 
194 
195 
196 
197 
198 
199  // Wash, rinse, repeat for another time step
200  // Create a new, empty graph and add the prior from the previous step
201  linearFactorGraph = GaussianFactorGraph::shared_ptr(new GaussianFactorGraph);
202 
203  // Convert the root conditional, P(x1) in this case, into a Prior for the next step
204  // The linearization point of this prior must be moved to the new estimate of x, and the key/index needs to be reset to 0,
205  // the first key in the next iteration
206  const GaussianConditional::shared_ptr& cg1 = linearBayesNet->back();
207  assert(cg1->nrFrontals() == 1);
208  assert(cg1->nrParents() == 0);
209  JacobianFactor tmpPrior1 = JacobianFactor(*cg1);
210  linearFactorGraph->add(0, tmpPrior1.getA(tmpPrior1.begin()), tmpPrior1.getb() - tmpPrior1.getA(tmpPrior1.begin()) * result[ordering->at(x1)], tmpPrior1.get_model());
211 
212  // Create a key for the new state
213  Symbol x2('x',2);
214 
215  // Create the desired ordering
217  ordering->insert(x1, 0);
218  ordering->insert(x2, 1);
219 
220  // Create a nonlinear factor describing the motion model
221  difference = Point2(1,0);
222  Q = noiseModel::Diagonal::Sigmas((Vec(2) <, 0.1, 0.1));
223  BetweenFactor<Point2> factor6(x1, x2, difference, Q);
224 
225  // Linearize the factor and add it to the linear factor graph
226  linearizationPoints.insert(x2, x1_update);
227  linearFactorGraph->push_back(factor6.linearize(linearizationPoints, *ordering));
228 
229  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x1,x2) = P(x1|x2)*P(x2) )
230  GaussianSequentialSolver solver2(*linearFactorGraph);
231  linearBayesNet = solver2.eliminate();
232 
233  // Extract the current estimate of x2 from the Bayes Network
234  result = optimize(*linearBayesNet);
235  Point2 x2_predict = linearizationPoints.at<Point2>(x2).retract(result[ordering->at(x2)]);
236  x2_predict.print("X2 Predict");
237 
238  // Update the linearization point to the new estimate
239  linearizationPoints.update(x2, x2_predict);
240 
241 
242 
243  // Now add the next measurement
244  // Create a new, empty graph and add the prior from the previous step
245  linearFactorGraph = GaussianFactorGraph::shared_ptr(new GaussianFactorGraph);
246 
247  // Convert the root conditional, P(x1) in this case, into a Prior for the next step
248  const GaussianConditional::shared_ptr& cg2 = linearBayesNet->back();
249  assert(cg2->nrFrontals() == 1);
250  assert(cg2->nrParents() == 0);
251  JacobianFactor tmpPrior2 = JacobianFactor(*cg2);
252  linearFactorGraph->add(0, tmpPrior2.getA(tmpPrior2.begin()), tmpPrior2.getb() - tmpPrior2.getA(tmpPrior2.begin()) * result[ordering->at(x2)], tmpPrior2.get_model());
253 
254  // Create the desired ordering
256  ordering->insert(x2, 0);
257 
258  // And update using z2 ...
259  Point2 z2(2.0, 0.0);
260  SharedDiagonal R2 = noiseModel::Diagonal::Sigmas((Vec(2) << 0.25, 0.25));
261  PriorFactor<Point2> factor8(x2, z2, R2);
262 
263  // Linearize the factor and add it to the linear factor graph
264  linearFactorGraph->push_back(factor8.linearize(linearizationPoints, *ordering));
265 
266  // We have now made the small factor graph f7-(x2)-f8
267  // where factor f7 is the prior from previous time ( P(x2) )
268  // and factor f8 is from the measurement, z2 ( P(x2|z2) )
269  // Eliminate this in order x2, to get Bayes net P(x2)
270  // As this is a filter, all we need is the posterior P(x2), so we just keep the root of the Bayes net
271  // We solve as before...
272 
273  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x0,x1) = P(x0|x1)*P(x1) )
274  GaussianSequentialSolver solver3(*linearFactorGraph);
275  linearBayesNet = solver3.eliminate();
276 
277  // Extract the current estimate of x2 from the Bayes Network
278  result = optimize(*linearBayesNet);
279  Point2 x2_update = linearizationPoints.at<Point2>(x2).retract(result[ordering->at(x2)]);
280  x2_update.print("X2 Update");
281 
282  // Update the linearization point to the new estimate
283  linearizationPoints.update(x2, x2_update);
284 
285 
286 
287 
288 
289 
290  // Wash, rinse, repeat for a third time step
291  // Create a new, empty graph and add the prior from the previous step
292  linearFactorGraph = GaussianFactorGraph::shared_ptr(new GaussianFactorGraph);
293 
294  // Convert the root conditional, P(x1) in this case, into a Prior for the next step
295  const GaussianConditional::shared_ptr& cg3 = linearBayesNet->back();
296  assert(cg3->nrFrontals() == 1);
297  assert(cg3->nrParents() == 0);
298  JacobianFactor tmpPrior3 = JacobianFactor(*cg3);
299  linearFactorGraph->add(0, tmpPrior3.getA(tmpPrior3.begin()), tmpPrior3.getb() - tmpPrior3.getA(tmpPrior3.begin()) * result[ordering->at(x2)], tmpPrior3.get_model());
300 
301  // Create a key for the new state
302  Symbol x3('x',3);
303 
304  // Create the desired ordering
306  ordering->insert(x2, 0);
307  ordering->insert(x3, 1);
308 
309  // Create a nonlinear factor describing the motion model
310  difference = Point2(1,0);
311  Q = noiseModel::Diagonal::Sigmas((Vec(2) << 0.1, 0.1));
312  BetweenFactor<Point2> factor10(x2, x3, difference, Q);
313 
314  // Linearize the factor and add it to the linear factor graph
315  linearizationPoints.insert(x3, x2_update);
316  linearFactorGraph->push_back(factor10.linearize(linearizationPoints, *ordering));
317 
318  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x1,x2) = P(x1|x2)*P(x2) )
319  GaussianSequentialSolver solver4(*linearFactorGraph);
320  linearBayesNet = solver4.eliminate();
321 
322  // Extract the current estimate of x3 from the Bayes Network
323  result = optimize(*linearBayesNet);
324  Point2 x3_predict = linearizationPoints.at<Point2>(x3).retract(result[ordering->at(x3)]);
325  x3_predict.print("X3 Predict");
326 
327  // Update the linearization point to the new estimate
328  linearizationPoints.update(x3, x3_predict);
329 
330 
331 
332  // Now add the next measurement
333  // Create a new, empty graph and add the prior from the previous step
334  linearFactorGraph = GaussianFactorGraph::shared_ptr(new GaussianFactorGraph);
335 
336  // Convert the root conditional, P(x1) in this case, into a Prior for the next step
337  const GaussianConditional::shared_ptr& cg4 = linearBayesNet->back();
338  assert(cg4->nrFrontals() == 1);
339  assert(cg4->nrParents() == 0);
340  JacobianFactor tmpPrior4 = JacobianFactor(*cg4);
341  linearFactorGraph->add(0, tmpPrior4.getA(tmpPrior4.begin()), tmpPrior4.getb() - tmpPrior4.getA(tmpPrior4.begin()) * result[ordering->at(x3)], tmpPrior4.get_model());
342 
343  // Create the desired ordering
345  ordering->insert(x3, 0);
346 
347  // And update using z3 ...
348  Point2 z3(3.0, 0.0);
349  SharedDiagonal R3 = noiseModel::Diagonal::Sigmas((Vec(2) << 0.25, 0.25));
350  PriorFactor<Point2> factor12(x3, z3, R3);
351 
352  // Linearize the factor and add it to the linear factor graph
353  linearFactorGraph->push_back(factor12.linearize(linearizationPoints, *ordering));
354 
355  // We have now made the small factor graph f11-(x3)-f12
356  // where factor f11 is the prior from previous time ( P(x3) )
357  // and factor f12 is from the measurement, z3 ( P(x3|z3) )
358  // Eliminate this in order x3, to get Bayes net P(x3)
359  // As this is a filter, all we need is the posterior P(x3), so we just keep the root of the Bayes net
360  // We solve as before...
361 
362  // Solve the linear factor graph, converting it into a linear Bayes Network ( P(x0,x1) = P(x0|x1)*P(x1) )
363  GaussianSequentialSolver solver5(*linearFactorGraph);
364  linearBayesNet = solver5.eliminate();
365 
366  // Extract the current estimate of x2 from the Bayes Network
367  result = optimize(*linearBayesNet);
368  Point2 x3_update = linearizationPoints.at<Point2>(x3).retract(result[ordering->at(x3)]);
369  x3_update.print("X3 Update");
370 
371  // Update the linearization point to the new estimate
372  linearizationPoints.update(x3, x3_update);
373 
374 
375 
376  return 0;
377 }
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::GaussianFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactorGraph.h:82
simple_graph::factor2
auto factor2
Definition: testJacobianFactor.cpp:203
optimize
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:64
gtsam::JacobianFactor::get_model
const SharedDiagonal & get_model() const
Definition: JacobianFactor.h:292
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
simple::R3
static Rot3 R3
Definition: testInitializePose3.cpp:54
gtsam::utils.numerical_derivative.retract
def retract(a, np.ndarray xi)
Definition: numerical_derivative.py:44
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
gtsam::Values::update
void update(Key j, const Value &val)
Definition: Values.cpp:169
gtsam::Factor::begin
const_iterator begin() const
Definition: Factor.h:146
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::Ordering::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: inference/Ordering.h:45
x3
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
gtsam::JacobianFactor::getb
const constBVector getb() const
Definition: JacobianFactor.h:298
Point2.h
2D Point
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
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
PriorFactor.h
z3
static const Unit3 z3
Definition: testRotateFactor.cpp:44
gtsam::VectorValues
Definition: VectorValues.h:74
BetweenFactor.h
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
x0
static Symbol x0('x', 0)
Symbol.h
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
ordering
static enum @1096 ordering
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: SFMdata.h:40
NoiseModel.h
gtsam::JacobianFactor::getA
constABlock getA(const_iterator variable) const
Definition: JacobianFactor.h:301
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
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::Ordering
Definition: inference/Ordering.h:33
gtsam::GaussianBayesNet::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: GaussianBayesNet.h:42
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Vec
Matrix< Scalar, Dynamic, 1 > Vec
Definition: gemv_common.h:17
simple_graph::factor1
auto factor1
Definition: testJacobianFactor.cpp:196
z2
static const Unit3 z2
Definition: testRotateFactor.cpp:43
gtsam::Symbol
Definition: inference/Symbol.h:37
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
main
int main()
Definition: elaboratePoint2KalmanFilter.cpp:35


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:15