| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file    smallExample.h | 
					
						
							|  |  |  |  * @brief   Create small example with two poses and one landmark | 
					
						
							|  |  |  |  * @brief   smallExample | 
					
						
							|  |  |  |  * @author  Carlos Nieto | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // \callgraph
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 04:15:44 +08:00
										 |  |  | #include <tests/simulated2D.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-19 23:32:16 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							| 
									
										
										
										
											2012-06-10 02:52:22 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:21 +08:00
										 |  |  | #include <gtsam/linear/GaussianBayesNet.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  | #include <boost/assign/list_of.hpp>
 | 
					
						
							| 
									
										
										
										
											2009-08-22 06:23:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | namespace example { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create small example for non-linear factor graph | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph();
 | 
					
						
							|  |  |  | // inline NonlinearFactorGraph createNonlinearFactorGraph();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create values structure to go with it | 
					
						
							|  |  |  |  * The ground truth values structure for the example above | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline Values createValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /** Vector Values equivalent */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline VectorValues createVectorValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * create a noisy values structure for a nonlinear factor graph | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline boost::shared_ptr<const Values> sharedNoisyValues();
 | 
					
						
							|  |  |  | // inline Values createNoisyValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Zero delta config | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline VectorValues createZeroDelta();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Delta config that, when added to noisyValues, returns the ground truth | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline VectorValues createCorrectDelta();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * create a linear factor graph | 
					
						
							|  |  |  |  * The non-linear graph above evaluated at NoisyValues | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianFactorGraph createGaussianFactorGraph();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * create small Chordal Bayes Net x <- y | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianBayesNet createSmallGaussianBayesNet();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create really non-linear factor graph (cos/sin) | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline boost::shared_ptr<const NonlinearFactorGraph>
 | 
					
						
							|  |  |  | //sharedReallyNonlinearFactorGraph();
 | 
					
						
							|  |  |  | // inline NonlinearFactorGraph createReallyNonlinearFactorGraph();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create a full nonlinear smoother | 
					
						
							|  |  |  |  * @param T number of time-steps | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T);
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Create a Kalman smoother by linearizing a non-linear factor graph | 
					
						
							|  |  |  |  * @param T number of time-steps | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianFactorGraph createSmoother(int T);
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ******************************************************* */ | 
					
						
							|  |  |  | // Linear Constrained Examples
 | 
					
						
							|  |  |  | /* ******************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Creates a simple constrained graph with one linear factor and | 
					
						
							|  |  |  |  * one binary equality constraint that sets x = y | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianFactorGraph createSimpleConstraintGraph();
 | 
					
						
							|  |  |  | // inline VectorValues createSimpleConstraintValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Creates a simple constrained graph with one linear factor and | 
					
						
							|  |  |  |  * one binary constraint. | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianFactorGraph createSingleConstraintGraph();
 | 
					
						
							|  |  |  | // inline VectorValues createSingleConstraintValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * Creates a constrained graph with a linear factor and two | 
					
						
							|  |  |  |  * binary constraints that share a node | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline GaussianFactorGraph createMultiConstraintGraph();
 | 
					
						
							|  |  |  | // inline VectorValues createMultiConstraintValues();
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ******************************************************* */ | 
					
						
							|  |  |  | // Planar graph with easy subtree for SubgraphPreconditioner
 | 
					
						
							|  |  |  | /* ******************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /*
 | 
					
						
							|  |  |  |  * Create factor graph with N^2 nodes, for example for N=3 | 
					
						
							|  |  |  |  *  x13-x23-x33 | 
					
						
							|  |  |  |  *   |   |   | | 
					
						
							|  |  |  |  *  x12-x22-x32 | 
					
						
							|  |  |  |  *   |   |   | | 
					
						
							|  |  |  |  * -x11-x21-x31 | 
					
						
							|  |  |  |  * with x11 clamped at (1,1), and others related by 2D odometry. | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2019-04-11 10:30:21 +08:00
										 |  |  | // inline std::pair<GaussianFactorGraph, VectorValues> planarGraph(size_t N);
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /*
 | 
					
						
							|  |  |  |  * Create canonical ordering for planar graph that also works for tree | 
					
						
							|  |  |  |  * With x11 the root, e.g. for N=3 | 
					
						
							|  |  |  |  * x33 x23 x13 x32 x22 x12 x31 x21 x11 | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline Ordering planarOrdering(size_t N);
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /*
 | 
					
						
							|  |  |  |  * Split graph into tree and loop closing constraints, e.g., with N=3 | 
					
						
							|  |  |  |  *  x13-x23-x33 | 
					
						
							|  |  |  |  *   | | 
					
						
							|  |  |  |  *  x12-x22-x32 | 
					
						
							|  |  |  |  *   | | 
					
						
							|  |  |  |  * -x11-x21-x31 | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | // inline std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(
 | 
					
						
							|  |  |  | //    size_t N, const GaussianFactorGraph& original);
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Implementations
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | //  using namespace gtsam::noiseModel;
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace impl { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | typedef boost::shared_ptr<NonlinearFactor> shared_nlf; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  | static SharedDiagonal kSigma1_0 = noiseModel::Isotropic::Sigma(2,1.0); | 
					
						
							|  |  |  | static SharedDiagonal kSigma0_1 = noiseModel::Isotropic::Sigma(2,0.1); | 
					
						
							|  |  |  | static SharedDiagonal kSigma0_2 = noiseModel::Isotropic::Sigma(2,0.2); | 
					
						
							|  |  |  | static SharedDiagonal kConstrainedModel = noiseModel::Constrained::All(2); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  | static const Key _l1_=0, _x1_=1, _x2_=2; | 
					
						
							|  |  |  | static const Key _x_=0, _y_=1, _z_=2; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | } // \namespace impl
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  | inline boost::shared_ptr<const NonlinearFactorGraph> | 
					
						
							| 
									
										
										
										
											2019-09-26 11:02:21 +08:00
										 |  |  | sharedNonlinearFactorGraph(const SharedNoiseModel &noiseModel1 = impl::kSigma0_1, | 
					
						
							|  |  |  |                            const SharedNoiseModel &noiseModel2 = impl::kSigma0_2) { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // Create
 | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   boost::shared_ptr<NonlinearFactorGraph> nlfg(new NonlinearFactorGraph); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // prior on x1
 | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   Point2 mu(0, 0); | 
					
						
							|  |  |  |   shared_nlf f1(new simulated2D::Prior(mu, noiseModel1, X(1))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   nlfg->push_back(f1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // odometry between x1 and x2
 | 
					
						
							|  |  |  |   Point2 z2(1.5, 0); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   shared_nlf f2(new simulated2D::Odometry(z2, noiseModel1, X(1), X(2))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   nlfg->push_back(f2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // measurement between x1 and l1
 | 
					
						
							|  |  |  |   Point2 z3(0, -1); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   shared_nlf f3(new simulated2D::Measurement(z3, noiseModel2, X(1), L(1))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   nlfg->push_back(f3); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // measurement between x2 and l1
 | 
					
						
							|  |  |  |   Point2 z4(-1.5, -1.); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   shared_nlf f4(new simulated2D::Measurement(z4, noiseModel2, X(2), L(1))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   nlfg->push_back(f4); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return nlfg; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  | inline NonlinearFactorGraph | 
					
						
							| 
									
										
										
										
											2019-09-26 11:02:21 +08:00
										 |  |  | createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1 = impl::kSigma0_1, | 
					
						
							|  |  |  |                            const SharedNoiseModel &noiseModel2 = impl::kSigma0_2) { | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   return *sharedNonlinearFactorGraph(noiseModel1, noiseModel2); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Values createValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							|  |  |  |   Values c; | 
					
						
							|  |  |  |   c.insert(X(1), Point2(0.0, 0.0)); | 
					
						
							|  |  |  |   c.insert(X(2), Point2(1.5, 0.0)); | 
					
						
							|  |  |  |   c.insert(L(1), Point2(0.0, -1.0)); | 
					
						
							|  |  |  |   return c; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createVectorValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							| 
									
										
										
										
											2013-10-29 12:24:14 +08:00
										 |  |  |   VectorValues c = boost::assign::pair_list_of<Key, Vector> | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |     (_l1_, Vector2(0.0, -1.0)) | 
					
						
							|  |  |  |     (_x1_, Vector2(0.0, 0.0)) | 
					
						
							|  |  |  |     (_x2_, Vector2(1.5, 0.0)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return c; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline boost::shared_ptr<const Values> sharedNoisyValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							|  |  |  |   boost::shared_ptr<Values> c(new Values); | 
					
						
							|  |  |  |   c->insert(X(1), Point2(0.1, 0.1)); | 
					
						
							|  |  |  |   c->insert(X(2), Point2(1.4, 0.2)); | 
					
						
							|  |  |  |   c->insert(L(1), Point2(0.1, -1.1)); | 
					
						
							|  |  |  |   return c; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Values createNoisyValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return *sharedNoisyValues(); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createCorrectDelta() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   VectorValues c; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   c.insert(L(1), Vector2(-0.1, 0.1)); | 
					
						
							|  |  |  |   c.insert(X(1), Vector2(-0.1, -0.1)); | 
					
						
							|  |  |  |   c.insert(X(2), Vector2(0.1, -0.2)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return c; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createZeroDelta() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   VectorValues c; | 
					
						
							| 
									
										
										
										
											2016-04-16 04:54:46 +08:00
										 |  |  |   c.insert(L(1), Z_2x1); | 
					
						
							|  |  |  |   c.insert(X(1), Z_2x1); | 
					
						
							|  |  |  |   c.insert(X(2), Z_2x1); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return c; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianFactorGraph createGaussianFactorGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							|  |  |  |   // Create empty graph
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_]
 | 
					
						
							| 
									
										
										
										
											2016-04-16 05:30:54 +08:00
										 |  |  |   fg += JacobianFactor(X(1), 10*I_2x2, -1.0*Vector::Ones(2)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // odometry between x1 and x2: x2-x1=[0.2;-0.1]
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   fg += JacobianFactor(X(1), -10*I_2x2, X(2), 10*I_2x2, Vector2(2.0, -1.0)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // measurement between x1 and l1: l1-x1=[0.0;0.2]
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   fg += JacobianFactor(X(1), -5*I_2x2, L(1), 5*I_2x2, Vector2(0.0, 1.0)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // measurement between x2 and l1: l1-x2=[-0.2;0.3]
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   fg += JacobianFactor(X(2), -5*I_2x2, L(1), 5*I_2x2, Vector2(-1.0, 1.5)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return fg; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | /** create small Chordal Bayes Net x <- y
 | 
					
						
							|  |  |  |  * x y d | 
					
						
							|  |  |  |  * 1 1 9 | 
					
						
							|  |  |  |  *   1 5 | 
					
						
							|  |  |  |  */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianBayesNet createSmallGaussianBayesNet() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Matrix R11 = (Matrix(1, 1) << 1.0).finished(), S12 = (Matrix(1, 1) << 1.0).finished(); | 
					
						
							|  |  |  |   Matrix R22 = (Matrix(1, 1) << 1.0).finished(); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Vector d1(1), d2(1); | 
					
						
							|  |  |  |   d1(0) = 9; | 
					
						
							|  |  |  |   d2(0) = 5; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // define nodes and specify in reverse topological sort (i.e. parents last)
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   GaussianConditional::shared_ptr Px_y(new GaussianConditional(_x_, d1, R11, _y_, S12)); | 
					
						
							|  |  |  |   GaussianConditional::shared_ptr Py(new GaussianConditional(_y_, d2, R22)); | 
					
						
							|  |  |  |   GaussianBayesNet cbn; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   cbn.push_back(Px_y); | 
					
						
							|  |  |  |   cbn.push_back(Py); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return cbn; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Some nonlinear functions to optimize
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | namespace smallOptimize { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Point2 h(const Point2& v) { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return Point2(cos(v.x()), sin(v.y())); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Matrix H(const Point2& v) { | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |   return (Matrix(2, 2) << | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |       -sin(v.x()), 0.0, | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |       0.0, cos(v.y())).finished(); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | struct UnaryFactor: public gtsam::NoiseModelFactor1<Point2> { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Point2 z_; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : | 
					
						
							|  |  |  |     gtsam::NoiseModelFactor1<Point2>(model, key), z_(z) { | 
					
						
							|  |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-07-26 15:57:54 +08:00
										 |  |  |   Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const override { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |     if (A) *A = H(x); | 
					
						
							| 
									
										
										
										
											2016-06-06 14:52:04 +08:00
										 |  |  |     return (h(x) - z_); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-11-28 07:25:38 +08:00
										 |  |  |   gtsam::NonlinearFactor::shared_ptr clone() const override { | 
					
						
							|  |  |  |         return boost::static_pointer_cast<gtsam::NonlinearFactor>( | 
					
						
							|  |  |  |             gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this))); } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | }; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-11-28 07:25:38 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | inline NonlinearFactorGraph nonlinearFactorGraphWithGivenSigma(const double sigma) { | 
					
						
							|  |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							|  |  |  |   boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph); | 
					
						
							|  |  |  |   Point2 z(1.0, 0.0); | 
					
						
							|  |  |  |   boost::shared_ptr<smallOptimize::UnaryFactor> factor( | 
					
						
							|  |  |  |       new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   return *fg; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline boost::shared_ptr<const NonlinearFactorGraph> sharedReallyNonlinearFactorGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph); | 
					
						
							| 
									
										
										
										
											2014-12-22 01:44:38 +08:00
										 |  |  |   Point2 z(1.0, 0.0); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   double sigma = 0.1; | 
					
						
							|  |  |  |   boost::shared_ptr<smallOptimize::UnaryFactor> factor( | 
					
						
							|  |  |  |       new smallOptimize::UnaryFactor(z, noiseModel::Isotropic::Sigma(2,sigma), X(1))); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   return fg; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline NonlinearFactorGraph createReallyNonlinearFactorGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return *sharedReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-11-28 04:46:12 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | inline NonlinearFactorGraph sharedNonRobustFactorGraphWithOutliers() { | 
					
						
							|  |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph); | 
					
						
							|  |  |  |   Point2 z(0.0, 0.0); | 
					
						
							|  |  |  |   double sigma = 0.1; | 
					
						
							| 
									
										
										
										
											2020-11-28 05:18:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   boost::shared_ptr<PriorFactor<Point2>> factor( | 
					
						
							|  |  |  |       new PriorFactor<Point2>(X(1), z, noiseModel::Isotropic::Sigma(2,sigma))); | 
					
						
							| 
									
										
										
										
											2020-11-28 04:46:12 +08:00
										 |  |  |   // 3 noiseless inliers
 | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // 1 outlier
 | 
					
						
							|  |  |  |   Point2 z_out(1.0, 0.0); | 
					
						
							| 
									
										
										
										
											2020-11-28 05:18:36 +08:00
										 |  |  |   boost::shared_ptr<PriorFactor<Point2>> factor_out( | 
					
						
							|  |  |  |       new PriorFactor<Point2>(X(1), z_out, noiseModel::Isotropic::Sigma(2,sigma))); | 
					
						
							| 
									
										
										
										
											2020-11-28 04:46:12 +08:00
										 |  |  |   fg->push_back(factor_out); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return *fg; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | inline NonlinearFactorGraph sharedRobustFactorGraphWithOutliers() { | 
					
						
							|  |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph); | 
					
						
							|  |  |  |   Point2 z(0.0, 0.0); | 
					
						
							|  |  |  |   double sigma = 0.1; | 
					
						
							|  |  |  |   auto gmNoise = noiseModel::Robust::Create( | 
					
						
							|  |  |  |             noiseModel::mEstimator::GemanMcClure::Create(1.0), noiseModel::Isotropic::Sigma(2,sigma)); | 
					
						
							| 
									
										
										
										
											2020-11-28 05:18:36 +08:00
										 |  |  |   boost::shared_ptr<PriorFactor<Point2>> factor( | 
					
						
							|  |  |  |       new PriorFactor<Point2>(X(1), z, gmNoise)); | 
					
						
							| 
									
										
										
										
											2020-11-28 04:46:12 +08:00
										 |  |  |   // 3 noiseless inliers
 | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  |   fg->push_back(factor); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // 1 outlier
 | 
					
						
							|  |  |  |   Point2 z_out(1.0, 0.0); | 
					
						
							| 
									
										
										
										
											2020-11-28 05:18:36 +08:00
										 |  |  |   boost::shared_ptr<PriorFactor<Point2>> factor_out( | 
					
						
							|  |  |  |       new PriorFactor<Point2>(X(1), z_out, gmNoise)); | 
					
						
							| 
									
										
										
										
											2020-11-28 04:46:12 +08:00
										 |  |  |   fg->push_back(factor_out); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return *fg; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T) { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   NonlinearFactorGraph nlfg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Values poses; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // prior on x1
 | 
					
						
							|  |  |  |   Point2 x1(1.0, 0.0); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   shared_nlf prior(new simulated2D::Prior(x1, kSigma1_0, X(1))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   nlfg.push_back(prior); | 
					
						
							|  |  |  |   poses.insert(X(1), x1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   for (int t = 2; t <= T; t++) { | 
					
						
							|  |  |  |     // odometry between x_t and x_{t-1}
 | 
					
						
							|  |  |  |     Point2 odo(1.0, 0.0); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |     shared_nlf odometry(new simulated2D::Odometry(odo, kSigma1_0, X(t - 1), X(t))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |     nlfg.push_back(odometry); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // measurement on x_t is like perfect GPS
 | 
					
						
							|  |  |  |     Point2 xt(t, 0); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |     shared_nlf measurement(new simulated2D::Prior(xt, kSigma1_0, X(t))); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |     nlfg.push_back(measurement); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // initial estimate
 | 
					
						
							|  |  |  |     poses.insert(X(t), xt); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return std::make_pair(nlfg, poses); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianFactorGraph createSmoother(int T) { | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   NonlinearFactorGraph nlfg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Values poses; | 
					
						
							| 
									
										
										
										
											2019-04-11 10:30:21 +08:00
										 |  |  |   std::tie(nlfg, poses) = createNonlinearSmoother(T); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:21 +08:00
										 |  |  |   return *nlfg.linearize(poses); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianFactorGraph createSimpleConstraintGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   // create unary factor
 | 
					
						
							|  |  |  |   // prior on _x_, mean = [1,-1], sigma=0.1
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix Ax = I_2x2; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Vector b1(2); | 
					
						
							|  |  |  |   b1(0) = 1.0; | 
					
						
							|  |  |  |   b1(1) = -1.0; | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, kSigma0_1)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create binary constraint factor
 | 
					
						
							|  |  |  |   // between _x_ and _y_, that is going to be the only factor on _y_
 | 
					
						
							|  |  |  |   // |1 0||x_1| + |-1  0||y_1| = |0|
 | 
					
						
							|  |  |  |   // |0 1||x_2|   | 0 -1||y_2|   |0|
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix Ax1 = I_2x2; | 
					
						
							|  |  |  |   Matrix Ay1 = I_2x2 * -1; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector b2 = Vector2(0.0, 0.0); | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |       kConstrainedModel)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // construct the graph
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   fg.push_back(f1); | 
					
						
							|  |  |  |   fg.push_back(f2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return fg; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createSimpleConstraintValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   using symbol_shorthand::L; | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   VectorValues config; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector v = Vector2(1.0, -1.0); | 
					
						
							| 
									
										
										
										
											2013-08-06 21:44:22 +08:00
										 |  |  |   config.insert(_x_, v); | 
					
						
							|  |  |  |   config.insert(_y_, v); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return config; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianFactorGraph createSingleConstraintGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   // create unary factor
 | 
					
						
							|  |  |  |   // prior on _x_, mean = [1,-1], sigma=0.1
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix Ax = I_2x2; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   Vector b1(2); | 
					
						
							|  |  |  |   b1(0) = 1.0; | 
					
						
							|  |  |  |   b1(1) = -1.0; | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   //GaussianFactor::shared_ptr f1(new JacobianFactor(_x_, kSigma0_1->Whiten(Ax), kSigma0_1->whiten(b1), kSigma0_1));
 | 
					
						
							|  |  |  |   JacobianFactor::shared_ptr f1(new JacobianFactor(_x_, Ax, b1, kSigma0_1)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create binary constraint factor
 | 
					
						
							|  |  |  |   // between _x_ and _y_, that is going to be the only factor on _y_
 | 
					
						
							|  |  |  |   // |1 2||x_1| + |10 0||y_1| = |1|
 | 
					
						
							|  |  |  |   // |2 1||x_2|   |0 10||y_2|   |2|
 | 
					
						
							|  |  |  |   Matrix Ax1(2, 2); | 
					
						
							|  |  |  |   Ax1(0, 0) = 1.0; | 
					
						
							|  |  |  |   Ax1(0, 1) = 2.0; | 
					
						
							|  |  |  |   Ax1(1, 0) = 2.0; | 
					
						
							|  |  |  |   Ax1(1, 1) = 1.0; | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix Ay1 = I_2x2 * 10; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector b2 = Vector2(1.0, 2.0); | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   JacobianFactor::shared_ptr f2(new JacobianFactor(_x_, Ax1, _y_, Ay1, b2, | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |       kConstrainedModel)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // construct the graph
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   fg.push_back(f1); | 
					
						
							|  |  |  |   fg.push_back(f2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return fg; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createSingleConstraintValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							| 
									
										
										
										
											2013-10-29 12:24:14 +08:00
										 |  |  |   VectorValues config = boost::assign::pair_list_of<Key, Vector> | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |     (_x_, Vector2(1.0, -1.0)) | 
					
						
							|  |  |  |     (_y_, Vector2(0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return config; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline GaussianFactorGraph createMultiConstraintGraph() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  |   // unary factor 1
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix A = I_2x2; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector b = Vector2(-2.0, 2.0); | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |   JacobianFactor::shared_ptr lf1(new JacobianFactor(_x_, A, b, kSigma0_1)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // constraint 1
 | 
					
						
							|  |  |  |   Matrix A11(2, 2); | 
					
						
							|  |  |  |   A11(0, 0) = 1.0; | 
					
						
							|  |  |  |   A11(0, 1) = 2.0; | 
					
						
							|  |  |  |   A11(1, 0) = 2.0; | 
					
						
							|  |  |  |   A11(1, 1) = 1.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix A12(2, 2); | 
					
						
							|  |  |  |   A12(0, 0) = 10.0; | 
					
						
							|  |  |  |   A12(0, 1) = 0.0; | 
					
						
							|  |  |  |   A12(1, 0) = 0.0; | 
					
						
							|  |  |  |   A12(1, 1) = 10.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Vector b1(2); | 
					
						
							|  |  |  |   b1(0) = 1.0; | 
					
						
							|  |  |  |   b1(1) = 2.0; | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   JacobianFactor::shared_ptr lc1(new JacobianFactor(_x_, A11, _y_, A12, b1, | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |       kConstrainedModel)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // constraint 2
 | 
					
						
							|  |  |  |   Matrix A21(2, 2); | 
					
						
							|  |  |  |   A21(0, 0) = 3.0; | 
					
						
							|  |  |  |   A21(0, 1) = 4.0; | 
					
						
							|  |  |  |   A21(1, 0) = -1.0; | 
					
						
							|  |  |  |   A21(1, 1) = -2.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix A22(2, 2); | 
					
						
							|  |  |  |   A22(0, 0) = 1.0; | 
					
						
							|  |  |  |   A22(0, 1) = 1.0; | 
					
						
							|  |  |  |   A22(1, 0) = 1.0; | 
					
						
							|  |  |  |   A22(1, 1) = 2.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Vector b2(2); | 
					
						
							|  |  |  |   b2(0) = 3.0; | 
					
						
							|  |  |  |   b2(1) = 4.0; | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   JacobianFactor::shared_ptr lc2(new JacobianFactor(_x_, A21, _z_, A22, b2, | 
					
						
							| 
									
										
										
										
											2019-09-20 00:58:27 +08:00
										 |  |  |       kConstrainedModel)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // construct the graph
 | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   fg.push_back(lf1); | 
					
						
							|  |  |  |   fg.push_back(lc1); | 
					
						
							|  |  |  |   fg.push_back(lc2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return fg; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline VectorValues createMultiConstraintValues() { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							| 
									
										
										
										
											2013-10-29 12:24:14 +08:00
										 |  |  |   VectorValues config = boost::assign::pair_list_of<Key, Vector> | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |     (_x_, Vector2(-2.0, 2.0)) | 
					
						
							|  |  |  |     (_y_, Vector2(-0.1, 0.4)) | 
					
						
							|  |  |  |     (_z_, Vector2(-4.0, 5.0)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return config; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Create key for simulated planar graph
 | 
					
						
							|  |  |  | namespace impl { | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Symbol key(size_t x, size_t y) { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using symbol_shorthand::X; | 
					
						
							|  |  |  |   return X(1000*x+y); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | } // \namespace impl
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2019-04-11 10:30:21 +08:00
										 |  |  | inline std::pair<GaussianFactorGraph, VectorValues> planarGraph(size_t N) { | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   using namespace impl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // create empty graph
 | 
					
						
							|  |  |  |   NonlinearFactorGraph nlfg; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create almost hard constraint on x11, sigma=0 will work for PCG not for normal
 | 
					
						
							|  |  |  |   shared_nlf constraint(new simulated2D::Prior(Point2(1.0, 1.0), noiseModel::Isotropic::Sigma(2,1e-3), key(1,1))); | 
					
						
							|  |  |  |   nlfg.push_back(constraint); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create horizontal constraints, 1...N*(N-1)
 | 
					
						
							|  |  |  |   Point2 z1(1.0, 0.0); // move right
 | 
					
						
							|  |  |  |   for (size_t x = 1; x < N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y <= N; y++) { | 
					
						
							|  |  |  |       shared_nlf f(new simulated2D::Odometry(z1, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x + 1, y))); | 
					
						
							|  |  |  |       nlfg.push_back(f); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // Create vertical constraints, N*(N-1)+1..2*N*(N-1)
 | 
					
						
							|  |  |  |   Point2 z2(0.0, 1.0); // move up
 | 
					
						
							|  |  |  |   for (size_t x = 1; x <= N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y < N; y++) { | 
					
						
							|  |  |  |       shared_nlf f(new simulated2D::Odometry(z2, noiseModel::Isotropic::Sigma(2,0.01), key(x, y), key(x, y + 1))); | 
					
						
							|  |  |  |       nlfg.push_back(f); | 
					
						
							|  |  |  |     } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   // Create linearization and ground xtrue config
 | 
					
						
							|  |  |  |   Values zeros; | 
					
						
							|  |  |  |   for (size_t x = 1; x <= N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y <= N; y++) | 
					
						
							| 
									
										
										
										
											2016-06-06 14:52:04 +08:00
										 |  |  |       zeros.insert(key(x, y), Point2(0,0)); | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:21 +08:00
										 |  |  |   VectorValues xtrue; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   for (size_t x = 1; x <= N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y <= N; y++) | 
					
						
							| 
									
										
										
										
											2016-06-06 15:37:49 +08:00
										 |  |  |       xtrue.insert(key(x, y), Point2((double)x, (double)y)); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // linearize around zero
 | 
					
						
							| 
									
										
										
										
											2013-08-06 06:31:21 +08:00
										 |  |  |   boost::shared_ptr<GaussianFactorGraph> gfg = nlfg.linearize(zeros); | 
					
						
							| 
									
										
										
										
											2019-04-11 10:30:21 +08:00
										 |  |  |   return std::make_pair(*gfg, xtrue); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-02-24 07:53:48 +08:00
										 |  |  | inline Ordering planarOrdering(size_t N) { | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |   Ordering ordering; | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   for (size_t y = N; y >= 1; y--) | 
					
						
							|  |  |  |     for (size_t x = N; x >= 1; x--) | 
					
						
							|  |  |  |       ordering.push_back(impl::key(x, y)); | 
					
						
							|  |  |  |   return ordering; | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  | inline std::pair<GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitOffPlanarTree(size_t N, | 
					
						
							| 
									
										
										
										
											2013-07-30 10:11:34 +08:00
										 |  |  |     const GaussianFactorGraph& original) { | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  |   auto T = boost::make_shared<GaussianFactorGraph>(), C= boost::make_shared<GaussianFactorGraph>(); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add the x11 constraint to the tree
 | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  |   T->push_back(original[0]); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add all horizontal constraints to the tree
 | 
					
						
							|  |  |  |   size_t i = 1; | 
					
						
							|  |  |  |   for (size_t x = 1; x < N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y <= N; y++, i++) | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  |       T->push_back(original[i]); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Add first vertical column of constraints to T, others to C
 | 
					
						
							|  |  |  |   for (size_t x = 1; x <= N; x++) | 
					
						
							|  |  |  |     for (size_t y = 1; y < N; y++, i++) | 
					
						
							|  |  |  |       if (x == 1) | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  |         T->push_back(original[i]); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |       else | 
					
						
							| 
									
										
										
										
											2019-04-04 21:23:02 +08:00
										 |  |  |         C->push_back(original[i]); | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-11 22:36:50 +08:00
										 |  |  |   return std::make_pair(T, C); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2013-06-11 22:35:22 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } // \namespace example
 | 
					
						
							|  |  |  | } // \namespace gtsam
 |