smallExample.h
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 
19 // \callgraph
20 
21 
22 #pragma once
23 
24 #include <tests/simulated2D.h>
25 #include <gtsam/inference/Symbol.h>
29 #include <boost/assign/list_of.hpp>
30 
31 namespace gtsam {
32 namespace example {
33 
37 // inline boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph();
38 // inline NonlinearFactorGraph createNonlinearFactorGraph();
39 
44 // inline Values createValues();
45 
47 // inline VectorValues createVectorValues();
48 
52 // inline boost::shared_ptr<const Values> sharedNoisyValues();
53 // inline Values createNoisyValues();
54 
58 // inline VectorValues createZeroDelta();
59 
63 // inline VectorValues createCorrectDelta();
64 
69 // inline GaussianFactorGraph createGaussianFactorGraph();
70 
74 // inline GaussianBayesNet createSmallGaussianBayesNet();
75 
79 // inline boost::shared_ptr<const NonlinearFactorGraph>
80 //sharedReallyNonlinearFactorGraph();
81 // inline NonlinearFactorGraph createReallyNonlinearFactorGraph();
82 
87 // inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T);
88 
93 // inline GaussianFactorGraph createSmoother(int T);
94 
95 /* ******************************************************* */
96 // Linear Constrained Examples
97 /* ******************************************************* */
98 
103 // inline GaussianFactorGraph createSimpleConstraintGraph();
104 // inline VectorValues createSimpleConstraintValues();
105 
110 // inline GaussianFactorGraph createSingleConstraintGraph();
111 // inline VectorValues createSingleConstraintValues();
112 
117 // inline GaussianFactorGraph createMultiConstraintGraph();
118 // inline VectorValues createMultiConstraintValues();
119 
120 /* ******************************************************* */
121 // Planar graph with easy subtree for SubgraphPreconditioner
122 /* ******************************************************* */
123 
124 /*
125  * Create factor graph with N^2 nodes, for example for N=3
126  * x13-x23-x33
127  * | | |
128  * x12-x22-x32
129  * | | |
130  * -x11-x21-x31
131  * with x11 clamped at (1,1), and others related by 2D odometry.
132  */
133 // inline std::pair<GaussianFactorGraph, VectorValues> planarGraph(size_t N);
134 
135 /*
136  * Create canonical ordering for planar graph that also works for tree
137  * With x11 the root, e.g. for N=3
138  * x33 x23 x13 x32 x22 x12 x31 x21 x11
139  */
140 // inline Ordering planarOrdering(size_t N);
141 
142 /*
143  * Split graph into tree and loop closing constraints, e.g., with N=3
144  * x13-x23-x33
145  * |
146  * x12-x22-x32
147  * |
148  * -x11-x21-x31
149  */
150 // inline std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(
151 // size_t N, const GaussianFactorGraph& original);
152 
153 
154 
155 // Implementations
156 
157 // using namespace gtsam::noiseModel;
158 
159 namespace impl {
160 typedef boost::shared_ptr<NonlinearFactor> shared_nlf;
161 
166 
167 static const Key _l1_=0, _x1_=1, _x2_=2;
168 static const Key _x_=0, _y_=1, _z_=2;
169 } // \namespace impl
170 
171 
172 /* ************************************************************************* */
173 inline boost::shared_ptr<const NonlinearFactorGraph>
175  const SharedNoiseModel &noiseModel2 = impl::kSigma0_2) {
176  using namespace impl;
177  using symbol_shorthand::L;
178  using symbol_shorthand::X;
179  // Create
180  boost::shared_ptr<NonlinearFactorGraph> nlfg(new NonlinearFactorGraph);
181 
182  // prior on x1
183  Point2 mu(0, 0);
184  shared_nlf f1(new simulated2D::Prior(mu, noiseModel1, X(1)));
185  nlfg->push_back(f1);
186 
187  // odometry between x1 and x2
188  Point2 z2(1.5, 0);
189  shared_nlf f2(new simulated2D::Odometry(z2, noiseModel1, X(1), X(2)));
190  nlfg->push_back(f2);
191 
192  // measurement between x1 and l1
193  Point2 z3(0, -1);
194  shared_nlf f3(new simulated2D::Measurement(z3, noiseModel2, X(1), L(1)));
195  nlfg->push_back(f3);
196 
197  // measurement between x2 and l1
198  Point2 z4(-1.5, -1.);
199  shared_nlf f4(new simulated2D::Measurement(z4, noiseModel2, X(2), L(1)));
200  nlfg->push_back(f4);
201 
202  return nlfg;
203 }
204 
205 /* ************************************************************************* */
208  const SharedNoiseModel &noiseModel2 = impl::kSigma0_2) {
209  return *sharedNonlinearFactorGraph(noiseModel1, noiseModel2);
210 }
211 
212 /* ************************************************************************* */
214  using symbol_shorthand::X;
215  using symbol_shorthand::L;
216  Values c;
217  c.insert(X(1), Point2(0.0, 0.0));
218  c.insert(X(2), Point2(1.5, 0.0));
219  c.insert(L(1), Point2(0.0, -1.0));
220  return c;
221 }
222 
223 /* ************************************************************************* */
225  using namespace impl;
226  VectorValues c = boost::assign::pair_list_of<Key, Vector>
227  (_l1_, Vector2(0.0, -1.0))
228  (_x1_, Vector2(0.0, 0.0))
229  (_x2_, Vector2(1.5, 0.0));
230  return c;
231 }
232 
233 /* ************************************************************************* */
234 inline boost::shared_ptr<const Values> sharedNoisyValues() {
235  using symbol_shorthand::X;
236  using symbol_shorthand::L;
237  boost::shared_ptr<Values> c(new Values);
238  c->insert(X(1), Point2(0.1, 0.1));
239  c->insert(X(2), Point2(1.4, 0.2));
240  c->insert(L(1), Point2(0.1, -1.1));
241  return c;
242 }
243 
244 /* ************************************************************************* */
246  return *sharedNoisyValues();
247 }
248 
249 /* ************************************************************************* */
251  using symbol_shorthand::X;
252  using symbol_shorthand::L;
253  VectorValues c;
254  c.insert(L(1), Vector2(-0.1, 0.1));
255  c.insert(X(1), Vector2(-0.1, -0.1));
256  c.insert(X(2), Vector2(0.1, -0.2));
257  return c;
258 }
259 
260 /* ************************************************************************* */
262  using symbol_shorthand::X;
263  using symbol_shorthand::L;
264  VectorValues c;
265  c.insert(L(1), Z_2x1);
266  c.insert(X(1), Z_2x1);
267  c.insert(X(2), Z_2x1);
268  return c;
269 }
270 
271 /* ************************************************************************* */
273  using symbol_shorthand::X;
274  using symbol_shorthand::L;
275  // Create empty graph
277 
278  // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_]
279  fg += JacobianFactor(X(1), 10*I_2x2, -1.0*Vector::Ones(2));
280 
281  // odometry between x1 and x2: x2-x1=[0.2;-0.1]
282  fg += JacobianFactor(X(1), -10*I_2x2, X(2), 10*I_2x2, Vector2(2.0, -1.0));
283 
284  // measurement between x1 and l1: l1-x1=[0.0;0.2]
285  fg += JacobianFactor(X(1), -5*I_2x2, L(1), 5*I_2x2, Vector2(0.0, 1.0));
286 
287  // measurement between x2 and l1: l1-x2=[-0.2;0.3]
288  fg += JacobianFactor(X(2), -5*I_2x2, L(1), 5*I_2x2, Vector2(-1.0, 1.5));
289 
290  return fg;
291 }
292 
293 /* ************************************************************************* */
300  using namespace impl;
301  Matrix R11 = (Matrix(1, 1) << 1.0).finished(), S12 = (Matrix(1, 1) << 1.0).finished();
302  Matrix R22 = (Matrix(1, 1) << 1.0).finished();
303  Vector d1(1), d2(1);
304  d1(0) = 9;
305  d2(0) = 5;
306 
307  // define nodes and specify in reverse topological sort (i.e. parents last)
310  GaussianBayesNet cbn;
311  cbn.push_back(Px_y);
312  cbn.push_back(Py);
313 
314  return cbn;
315 }
316 
317 /* ************************************************************************* */
318 // Some nonlinear functions to optimize
319 /* ************************************************************************* */
320 namespace smallOptimize {
321 
322 inline Point2 h(const Point2& v) {
323  return Point2(cos(v.x()), sin(v.y()));
324 }
325 
326 inline Matrix H(const Point2& v) {
327  return (Matrix(2, 2) <<
328  -sin(v.x()), 0.0,
329  0.0, cos(v.y())).finished();
330 }
331 
332 struct UnaryFactor: public gtsam::NoiseModelFactor1<Point2> {
333 
335 
337  gtsam::NoiseModelFactor1<Point2>(model, key), z_(z) {
338  }
339 
340  Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const override {
341  if (A) *A = H(x);
342  return (h(x) - z_);
343  }
344 
346  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
348 };
349 
350 }
351 
352 /* ************************************************************************* */
354  using symbol_shorthand::X;
355  using symbol_shorthand::L;
356  boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph);
357  Point2 z(1.0, 0.0);
358  boost::shared_ptr<smallOptimize::UnaryFactor> factor(
360  fg->push_back(factor);
361  return *fg;
362 }
363 
364 /* ************************************************************************* */
365 inline boost::shared_ptr<const NonlinearFactorGraph> sharedReallyNonlinearFactorGraph() {
366  using symbol_shorthand::X;
367  using symbol_shorthand::L;
368  boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph);
369  Point2 z(1.0, 0.0);
370  double sigma = 0.1;
371  boost::shared_ptr<smallOptimize::UnaryFactor> factor(
373  fg->push_back(factor);
374  return fg;
375 }
376 
379 }
380 
381 /* ************************************************************************* */
383  using symbol_shorthand::X;
384  boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph);
385  Point2 z(0.0, 0.0);
386  double sigma = 0.1;
387 
388  boost::shared_ptr<PriorFactor<Point2>> factor(
389  new PriorFactor<Point2>(X(1), z, noiseModel::Isotropic::Sigma(2,sigma)));
390  // 3 noiseless inliers
391  fg->push_back(factor);
392  fg->push_back(factor);
393  fg->push_back(factor);
394 
395  // 1 outlier
396  Point2 z_out(1.0, 0.0);
397  boost::shared_ptr<PriorFactor<Point2>> factor_out(
398  new PriorFactor<Point2>(X(1), z_out, noiseModel::Isotropic::Sigma(2,sigma)));
399  fg->push_back(factor_out);
400 
401  return *fg;
402 }
403 
404 /* ************************************************************************* */
406  using symbol_shorthand::X;
407  boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph);
408  Point2 z(0.0, 0.0);
409  double sigma = 0.1;
410  auto gmNoise = noiseModel::Robust::Create(
412  boost::shared_ptr<PriorFactor<Point2>> factor(
413  new PriorFactor<Point2>(X(1), z, gmNoise));
414  // 3 noiseless inliers
415  fg->push_back(factor);
416  fg->push_back(factor);
417  fg->push_back(factor);
418 
419  // 1 outlier
420  Point2 z_out(1.0, 0.0);
421  boost::shared_ptr<PriorFactor<Point2>> factor_out(
422  new PriorFactor<Point2>(X(1), z_out, gmNoise));
423  fg->push_back(factor_out);
424 
425  return *fg;
426 }
427 
428 
429 /* ************************************************************************* */
430 inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T) {
431  using namespace impl;
432  using symbol_shorthand::X;
433  using symbol_shorthand::L;
434 
435  // Create
437  Values poses;
438 
439  // prior on x1
440  Point2 x1(1.0, 0.0);
442  nlfg.push_back(prior);
443  poses.insert(X(1), x1);
444 
445  for (int t = 2; t <= T; t++) {
446  // odometry between x_t and x_{t-1}
447  Point2 odo(1.0, 0.0);
449  nlfg.push_back(odometry);
450 
451  // measurement on x_t is like perfect GPS
452  Point2 xt(t, 0);
454  nlfg.push_back(measurement);
455 
456  // initial estimate
457  poses.insert(X(t), xt);
458  }
459 
460  return std::make_pair(nlfg, poses);
461 }
462 
463 /* ************************************************************************* */
466  Values poses;
467  std::tie(nlfg, poses) = createNonlinearSmoother(T);
468 
469  return *nlfg.linearize(poses);
470 }
471 
472 /* ************************************************************************* */
474  using namespace impl;
475  // create unary factor
476  // prior on _x_, mean = [1,-1], sigma=0.1
477  Matrix Ax = I_2x2;
478  Vector b1(2);
479  b1(0) = 1.0;
480  b1(1) = -1.0;
482 
483  // create binary constraint factor
484  // between _x_ and _y_, that is going to be the only factor on _y_
485  // |1 0||x_1| + |-1 0||y_1| = |0|
486  // |0 1||x_2| | 0 -1||y_2| |0|
487  Matrix Ax1 = I_2x2;
488  Matrix Ay1 = I_2x2 * -1;
489  Vector b2 = Vector2(0.0, 0.0);
492 
493  // construct the graph
495  fg.push_back(f1);
496  fg.push_back(f2);
497 
498  return fg;
499 }
500 
501 /* ************************************************************************* */
503  using namespace impl;
504  using symbol_shorthand::X;
505  using symbol_shorthand::L;
506  VectorValues config;
507  Vector v = Vector2(1.0, -1.0);
508  config.insert(_x_, v);
509  config.insert(_y_, v);
510  return config;
511 }
512 
513 /* ************************************************************************* */
515  using namespace impl;
516  // create unary factor
517  // prior on _x_, mean = [1,-1], sigma=0.1
518  Matrix Ax = I_2x2;
519  Vector b1(2);
520  b1(0) = 1.0;
521  b1(1) = -1.0;
522  //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, kSigma0_1->Whiten(Ax), kSigma0_1->whiten(b1), kSigma0_1));
524 
525  // create binary constraint factor
526  // between _x_ and _y_, that is going to be the only factor on _y_
527  // |1 2||x_1| + |10 0||y_1| = |1|
528  // |2 1||x_2| |0 10||y_2| |2|
529  Matrix Ax1(2, 2);
530  Ax1(0, 0) = 1.0;
531  Ax1(0, 1) = 2.0;
532  Ax1(1, 0) = 2.0;
533  Ax1(1, 1) = 1.0;
534  Matrix Ay1 = I_2x2 * 10;
535  Vector b2 = Vector2(1.0, 2.0);
538 
539  // construct the graph
541  fg.push_back(f1);
542  fg.push_back(f2);
543 
544  return fg;
545 }
546 
547 /* ************************************************************************* */
549  using namespace impl;
550  VectorValues config = boost::assign::pair_list_of<Key, Vector>
551  (_x_, Vector2(1.0, -1.0))
552  (_y_, Vector2(0.2, 0.1));
553  return config;
554 }
555 
556 /* ************************************************************************* */
558  using namespace impl;
559  // unary factor 1
560  Matrix A = I_2x2;
561  Vector b = Vector2(-2.0, 2.0);
563 
564  // constraint 1
565  Matrix A11(2, 2);
566  A11(0, 0) = 1.0;
567  A11(0, 1) = 2.0;
568  A11(1, 0) = 2.0;
569  A11(1, 1) = 1.0;
570 
571  Matrix A12(2, 2);
572  A12(0, 0) = 10.0;
573  A12(0, 1) = 0.0;
574  A12(1, 0) = 0.0;
575  A12(1, 1) = 10.0;
576 
577  Vector b1(2);
578  b1(0) = 1.0;
579  b1(1) = 2.0;
580  JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1,
582 
583  // constraint 2
584  Matrix A21(2, 2);
585  A21(0, 0) = 3.0;
586  A21(0, 1) = 4.0;
587  A21(1, 0) = -1.0;
588  A21(1, 1) = -2.0;
589 
590  Matrix A22(2, 2);
591  A22(0, 0) = 1.0;
592  A22(0, 1) = 1.0;
593  A22(1, 0) = 1.0;
594  A22(1, 1) = 2.0;
595 
596  Vector b2(2);
597  b2(0) = 3.0;
598  b2(1) = 4.0;
599  JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2,
601 
602  // construct the graph
604  fg.push_back(lf1);
605  fg.push_back(lc1);
606  fg.push_back(lc2);
607 
608  return fg;
609 }
610 
611 /* ************************************************************************* */
613  using namespace impl;
614  VectorValues config = boost::assign::pair_list_of<Key, Vector>
615  (_x_, Vector2(-2.0, 2.0))
616  (_y_, Vector2(-0.1, 0.4))
617  (_z_, Vector2(-4.0, 5.0));
618  return config;
619 }
620 
621 /* ************************************************************************* */
622 // Create key for simulated planar graph
623 namespace impl {
624 inline Symbol key(size_t x, size_t y) {
625  using symbol_shorthand::X;
626  return X(1000*x+y);
627 }
628 } // \namespace impl
629 
630 /* ************************************************************************* */
631 inline std::pair<GaussianFactorGraph, VectorValues> planarGraph(size_t N) {
632  using namespace impl;
633 
634  // create empty graph
636 
637  // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal
638  shared_nlf constraint(new simulated2D::Prior(Point2(1.0, 1.0), noiseModel::Isotropic::Sigma(2,1e-3), key(1,1)));
639  nlfg.push_back(constraint);
640 
641  // Create horizontal constraints, 1...N*(N-1)
642  Point2 z1(1.0, 0.0); // move right
643  for (size_t x = 1; x < N; x++)
644  for (size_t y = 1; y <= N; y++) {
646  nlfg.push_back(f);
647  }
648 
649  // Create vertical constraints, N*(N-1)+1..2*N*(N-1)
650  Point2 z2(0.0, 1.0); // move up
651  for (size_t x = 1; x <= N; x++)
652  for (size_t y = 1; y < N; y++) {
654  nlfg.push_back(f);
655  }
656 
657  // Create linearization and ground xtrue config
658  Values zeros;
659  for (size_t x = 1; x <= N; x++)
660  for (size_t y = 1; y <= N; y++)
661  zeros.insert(key(x, y), Point2(0,0));
662  VectorValues xtrue;
663  for (size_t x = 1; x <= N; x++)
664  for (size_t y = 1; y <= N; y++)
665  xtrue.insert(key(x, y), Point2((double)x, (double)y));
666 
667  // linearize around zero
668  boost::shared_ptr<GaussianFactorGraph> gfg = nlfg.linearize(zeros);
669  return std::make_pair(*gfg, xtrue);
670 }
671 
672 /* ************************************************************************* */
673 inline Ordering planarOrdering(size_t N) {
675  for (size_t y = N; y >= 1; y--)
676  for (size_t x = N; x >= 1; x--)
677  ordering.push_back(impl::key(x, y));
678  return ordering;
679 }
680 
681 /* ************************************************************************* */
682 inline std::pair<GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitOffPlanarTree(size_t N,
683  const GaussianFactorGraph& original) {
684  auto T = boost::make_shared<GaussianFactorGraph>(), C= boost::make_shared<GaussianFactorGraph>();
685 
686  // Add the x11 constraint to the tree
687  T->push_back(original[0]);
688 
689  // Add all horizontal constraints to the tree
690  size_t i = 1;
691  for (size_t x = 1; x < N; x++)
692  for (size_t y = 1; y <= N; y++, i++)
693  T->push_back(original[i]);
694 
695  // Add first vertical column of constraints to T, others to C
696  for (size_t x = 1; x <= N; x++)
697  for (size_t y = 1; y < N; y++, i++)
698  if (x == 1)
699  T->push_back(original[i]);
700  else
701  C->push_back(original[i]);
702 
703  return std::make_pair(T, C);
704 }
705 
706 /* ************************************************************************* */
707 
708 } // \namespace example
709 } // \namespace gtsam
static const Key _x_
Definition: smallExample.h:168
GaussianFactorGraph createMultiConstraintGraph()
Definition: smallExample.h:557
VectorValues createVectorValues()
Definition: smallExample.h:224
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
VectorValues createMultiConstraintValues()
Definition: smallExample.h:612
Values createNoisyValues()
Definition: smallExample.h:245
static SharedDiagonal kSigma1_0
Definition: smallExample.h:162
Scalar * y
GaussianFactorGraph createSmoother(int T)
Definition: smallExample.h:464
This is the base class for all measurement types.
Definition: Measurement.h:11
static const Key _x2_
Definition: smallExample.h:167
Factor Graph consisting of non-linear factors.
GaussianFactorGraph createGaussianFactorGraph()
Definition: smallExample.h:272
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector evaluateError(const Point2 &x, boost::optional< Matrix & > A=boost::none) const override
Definition: smallExample.h:340
static enum @843 ordering
static const Key _z_
Definition: smallExample.h:168
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
Definition: simulated2D.h:98
Vector2 Point2
Definition: Point2.h:27
double mu
ArrayXcf v
Definition: Cwise_arg.cpp:1
NonlinearFactorGraph sharedRobustFactorGraphWithOutliers()
Definition: smallExample.h:405
static const double sigma
NonlinearFactorGraph createReallyNonlinearFactorGraph()
Definition: smallExample.h:377
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
NonlinearFactorGraph nonlinearFactorGraphWithGivenSigma(const double sigma)
Definition: smallExample.h:353
VectorValues createSingleConstraintValues()
Definition: smallExample.h:548
MatrixXd L
Definition: LLT_example.cpp:6
double measurement(10.0)
Key X(std::uint64_t j)
double f2(const Vector2 &x)
#define N
Definition: gksort.c:12
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
static shared_ptr Create(const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise)
Definition: NoiseModel.cpp:665
Symbol key(size_t x, size_t y)
Definition: smallExample.h:624
Point2 z2
static SharedDiagonal kConstrainedModel
Definition: smallExample.h:165
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: smallExample.h:345
boost::shared_ptr< NonlinearFactor > shared_nlf
EIGEN_DEVICE_FUNC const CosReturnType cos() const
VectorValues createCorrectDelta()
Definition: smallExample.h:250
static const Unit3 z3
Eigen::VectorXd Vector
Definition: Vector.h:38
static SharedDiagonal kSigma0_1
Definition: smallExample.h:163
GaussianBayesNet createSmallGaussianBayesNet()
Definition: smallExample.h:299
boost::shared_ptr< const Values > sharedNoisyValues()
Definition: smallExample.h:234
boost::shared_ptr< const NonlinearFactorGraph > sharedReallyNonlinearFactorGraph()
Definition: smallExample.h:365
std::pair< NonlinearFactorGraph, Values > createNonlinearSmoother(int T)
Definition: smallExample.h:430
Matrix H(const Point2 &v)
Definition: smallExample.h:326
boost::shared_ptr< This > shared_ptr
Vector2 b2(4,-5)
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues createZeroDelta()
Definition: smallExample.h:261
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
Definition: smallExample.h:207
Linear Factor Graph where all factors are Gaussians.
const G & b
Definition: Group.h:83
GaussianFactorGraph createSimpleConstraintGraph()
Definition: smallExample.h:473
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
Ordering planarOrdering(size_t N)
Definition: smallExample.h:673
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
std::pair< GaussianFactorGraph, VectorValues > planarGraph(size_t N)
Definition: smallExample.h:631
Vector2 b1(2,-1)
UnaryFactor(const Point2 &z, const SharedNoiseModel &model, Key key)
Definition: smallExample.h:336
const double h
Point2 z1
measurement functions and derivatives for simulated 2D robot
Eigen::Vector2d Vector2
Definition: Vector.h:42
std::pair< GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitOffPlanarTree(size_t N, const GaussianFactorGraph &original)
Definition: smallExample.h:682
VectorValues createSimpleConstraintValues()
Definition: smallExample.h:502
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
double f4(double x, double y, double z)
Pose3 x1
Definition: testPose3.cpp:588
static SharedDiagonal kSigma0_2
Definition: smallExample.h:164
Key L(std::uint64_t j)
boost::shared_ptr< NonlinearFactor > shared_nlf
Definition: smallExample.h:160
double f3(double x1, double x2)
boost::shared_ptr< const NonlinearFactorGraph > sharedNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
Definition: smallExample.h:174
Chordal Bayes Net, the result of eliminating a factor graph.
EIGEN_DEVICE_FUNC const SinReturnType sin() const
static const Key _x1_
Definition: smallExample.h:167
Pose2 odometry(2.0, 0.0, 0.0)
Values createValues()
Definition: smallExample.h:213
NonlinearFactorGraph sharedNonRobustFactorGraphWithOutliers()
Definition: smallExample.h:382
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const Key _l1_
Definition: smallExample.h:167
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
GaussianFactorGraph createSingleConstraintGraph()
Definition: smallExample.h:514
#define X
Definition: icosphere.cpp:20
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
static const Key _y_
Definition: smallExample.h:168
iterator insert(const std::pair< Key, Vector > &key_value)
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Point2 t(10, 10)
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567
static shared_ptr All(size_t dim)
Definition: NoiseModel.h:467


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:13