testNonlinearFactorGraph.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
21 #include <gtsam/base/Testable.h>
22 #include <gtsam/base/Matrix.h>
23 #include <tests/smallExample.h>
25 #include <gtsam/inference/Symbol.h>
28 #include <gtsam/geometry/Pose2.h>
29 #include <gtsam/geometry/Pose3.h>
30 #include <gtsam/sam/RangeFactor.h>
32 
34 
35 /*STL/C++*/
36 #include <iostream>
37 
38 using namespace std;
39 using namespace gtsam;
40 using namespace example;
41 
44 
45 /* ************************************************************************* */
47 {
50  CHECK( fg.equals(fg2) );
51 }
52 
53 /* ************************************************************************* */
55 {
58  double actual1 = fg.error(c1);
59  DOUBLES_EQUAL( 0.0, actual1, 1e-9 );
60 
62  double actual2 = fg.error(c2);
63  DOUBLES_EQUAL( 5.625, actual2, 1e-9 );
64 }
65 
66 /* ************************************************************************* */
68 {
70  KeySet actual = fg.keys();
71  LONGS_EQUAL(3, (long)actual.size());
72  KeySet::const_iterator it = actual.begin();
73  LONGS_EQUAL((long)L(1), (long)*(it++));
74  LONGS_EQUAL((long)X(1), (long)*(it++));
75  LONGS_EQUAL((long)X(2), (long)*(it++));
76 }
77 
78 /* ************************************************************************* */
79 TEST( NonlinearFactorGraph, GET_ORDERING)
80 {
81  const Ordering expected{L(1), X(2), X(1)}; // For starting with l1,x1,x2
83  Ordering actual = Ordering::Colamd(nlfg);
84  EXPECT(assert_equal(expected,actual));
85 
86  // Constrained ordering - put x2 at the end
87  const Ordering expectedConstrained{L(1), X(1), X(2)};
88  FastMap<Key, int> constraints;
89  constraints[X(2)] = 1;
90  Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints);
91  EXPECT(assert_equal(expectedConstrained, actualConstrained));
92 }
93 
94 /* ************************************************************************* */
96 {
98  Values cfg = createValues();
99 
100  // evaluate the probability of the factor graph
101  double actual = fg.probPrime(cfg);
102  double expected = 1.0;
103  DOUBLES_EQUAL(expected,actual,0);
104 }
105 
106 /* ************************************************************************* */
110  noiseModel::Isotropic::Sigma(1, 1.0));
111 
112  Values values;
113  values.insert(1, 1.0);
114 
115  // The prior factor squared error is: 0.5.
116  EXPECT_DOUBLES_EQUAL(0.5, fg.error(values), 1e-12);
117 
118  // The probability value is: exp^(-factor_error) / sqrt(2 * PI)
119  // Ignore the denominator and we get: exp^(-factor_error) = exp^(-0.5)
120  double expected = exp(-0.5);
122 }
123 
124 /* ************************************************************************* */
126 {
129  GaussianFactorGraph linearFG = *fg.linearize(initial);
131  CHECK(assert_equal(expected,linearFG)); // Needs correct linearizations
132 }
133 
134 /* ************************************************************************* */
136 {
138  NonlinearFactorGraph actClone = fg.clone();
139  EXPECT(assert_equal(fg, actClone));
140  for (size_t i=0; i<fg.size(); ++i)
141  EXPECT(fg[i] != actClone[i]);
142 }
143 
144 /* ************************************************************************* */
146 {
148  map<Key,Key> rekey_mapping;
149  rekey_mapping.insert(make_pair(L(1), L(4)));
150  NonlinearFactorGraph actRekey = init.rekey(rekey_mapping);
151 
152  // ensure deep clone
153  LONGS_EQUAL((long)init.size(), (long)actRekey.size());
154  for (size_t i=0; i<init.size(); ++i)
155  EXPECT(init[i] != actRekey[i]);
156 
157  NonlinearFactorGraph expRekey;
158  // original measurements
159  expRekey.push_back(init[0]);
160  expRekey.push_back(init[1]);
161 
162  // updated measurements
163  Point2 z3(0, -1), z4(-1.5, -1.);
164  SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2);
165  expRekey.emplace_shared<simulated2D::Measurement>(z3, sigma0_2, X(1), L(4));
166  expRekey.emplace_shared<simulated2D::Measurement>(z4, sigma0_2, X(2), L(4));
167 
168  EXPECT(assert_equal(expRekey, actRekey));
169 }
170 
171 /* ************************************************************************* */
173 {
175 
177  expected.push_factor(X(1));
178  expected.push_factor(X(1), X(2));
179  expected.push_factor(X(1), L(1));
180  expected.push_factor(X(2), L(1));
181 
182  SymbolicFactorGraph actual = *graph.symbolic();
183 
184  EXPECT(assert_equal(expected, actual));
185 }
186 
187 /* ************************************************************************* */
188 TEST(NonlinearFactorGraph, UpdateCholesky) {
191 
192  // solve conventionally
193  GaussianFactorGraph linearFG = *fg.linearize(initial);
194  auto delta = linearFG.optimizeDensely();
195  auto expected = initial.retract(delta);
196 
197  // solve with new method
199 
200  // solve with Ordering
201  const Ordering ordering{L(1), X(2), X(1)};
203 
204  // solve with new method, heavily damped
205  auto dampen = [](const HessianFactor::shared_ptr& hessianFactor) {
206  auto iterator = hessianFactor->begin();
207  for (; iterator != hessianFactor->end(); iterator++) {
208  const auto index = std::distance(hessianFactor->begin(), iterator);
209  auto block = hessianFactor->info().diagonalBlock(index);
210  for (int j = 0; j < block.rows(); j++) {
211  block(j, j) += 1e9;
212  }
213  }
214  };
215  EXPECT(assert_equal(initial, fg.updateCholesky(initial, dampen), 1e-6));
216 }
217 
218 /* ************************************************************************* */
219 // Example from issue #452 which threw an ILS error. The reason was a very
220 // weak prior on heading, which was tightened, and the ILS disappeared.
221 TEST(testNonlinearFactorGraph, eliminate) {
222  // Linearization point
223  Pose2 T11(0, 0, 0);
224  Pose2 T12(1, 0, 0);
225  Pose2 T21(0, 1, 0);
226  Pose2 T22(1, 1, 0);
227 
228  // Factor graph
229  auto graph = NonlinearFactorGraph();
230 
231  // Priors
232  auto prior = noiseModel::Isotropic::Sigma(3, 1);
233  graph.addPrior(11, T11, prior);
234  graph.addPrior(21, T21, prior);
235 
236  // Odometry
237  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.01, 0.01, 0.3));
238  graph.add(BetweenFactor<Pose2>(11, 12, T11.between(T12), model));
239  graph.add(BetweenFactor<Pose2>(21, 22, T21.between(T22), model));
240 
241  // Range factor
242  auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01);
243  graph.add(RangeFactor<Pose2>(12, 22, 1.0, model_rho));
244 
245  Values values;
246  values.insert(11, T11.retract(Vector3(0.1,0.2,0.3)));
247  values.insert(12, T12);
248  values.insert(21, T21);
249  values.insert(22, T22);
250  auto linearized = graph.linearize(values);
251 
252  // Eliminate
253  const Ordering ordering{11, 21, 12, 22};
254  auto bn = linearized->eliminateSequential(ordering);
255  EXPECT_LONGS_EQUAL(4, bn->size());
256 }
257 
258 /* ************************************************************************* */
259 TEST(testNonlinearFactorGraph, addPrior) {
260  Key k(0);
261 
262  // Factor graph.
263  auto graph = NonlinearFactorGraph();
264 
265  // Add a prior factor for key k.
266  auto model_double = noiseModel::Isotropic::Sigma(1, 1);
267  graph.addPrior<double>(k, 10, model_double);
268 
269  // Assert the graph has 0 error with the correct values.
270  Values values;
271  values.insert(k, 10.0);
273 
274  // Assert the graph has some error with incorrect values.
275  values.clear();
276  values.insert(k, 11.0);
277  EXPECT(0 != graph.error(values));
278 
279  // Clear the factor graph and values.
280  values.clear();
281  graph.erase(graph.begin(), graph.end());
282 
283  // Add a Pose3 prior to the factor graph. Use a gaussian noise model by
284  // providing the covariance matrix.
285  Eigen::DiagonalMatrix<double, 6, 6> covariance_pose3;
286  covariance_pose3.setIdentity();
287  Pose3 pose{Rot3(), Point3(0, 0, 0)};
288  graph.addPrior(k, pose, covariance_pose3);
289 
290  // Assert the graph has 0 error with the correct values.
291  values.insert(k, pose);
293 
294  // Assert the graph has some error with incorrect values.
295  values.clear();
296  Pose3 pose_incorrect{Rot3::RzRyRx(-M_PI, M_PI, -M_PI / 8), Point3(1, 2, 3)};
297  values.insert(k, pose_incorrect);
298  EXPECT(0 != graph.error(values));
299 }
300 
301 /* ************************************************************************* */
303 {
305  const Values c = createValues();
306 
307  // Test that it builds with default parameters.
308  // We cannot check the output since (at present) output is fixed to std::cout.
309  fg.printErrors(c);
310 
311  // Second round: using callback filter to check that we actually visit all factors:
312  std::vector<bool> visited;
313  visited.assign(fg.size(), false);
314  const auto testFilter =
315  [&](const gtsam::Factor *f, double error, size_t index) {
316  EXPECT(f!=nullptr);
317  EXPECT(error>=.0);
318  visited.at(index)=true;
319  return false; // do not print
320  };
321  fg.printErrors(c,"Test graph: ", gtsam::DefaultKeyFormatter,testFilter);
322 
323  for (bool visit : visited) EXPECT(visit==true);
324 }
325 
326 /* ************************************************************************* */
328  string expected =
329  "graph {\n"
330  " size=\"5,5\";\n"
331  "\n"
332  " var7782220156096217089[label=\"l1\"];\n"
333  " var8646911284551352321[label=\"x1\"];\n"
334  " var8646911284551352322[label=\"x2\"];\n"
335  "\n"
336  " factor0[label=\"\", shape=point];\n"
337  " var8646911284551352321--factor0;\n"
338  " factor1[label=\"\", shape=point];\n"
339  " var8646911284551352321--factor1;\n"
340  " var8646911284551352322--factor1;\n"
341  " factor2[label=\"\", shape=point];\n"
342  " var8646911284551352321--factor2;\n"
343  " var7782220156096217089--factor2;\n"
344  " factor3[label=\"\", shape=point];\n"
345  " var8646911284551352322--factor3;\n"
346  " var7782220156096217089--factor3;\n"
347  "}\n";
348 
350  string actual = fg.dot();
351  EXPECT(actual == expected);
352 }
353 
354 /* ************************************************************************* */
356  string expected =
357  "graph {\n"
358  " size=\"5,5\";\n"
359  "\n"
360  " var7782220156096217089[label=\"l1\", pos=\"0,0!\"];\n"
361  " var8646911284551352321[label=\"x1\", pos=\"1,0!\"];\n"
362  " var8646911284551352322[label=\"x2\", pos=\"1,1.5!\"];\n"
363  "\n"
364  " factor0[label=\"\", shape=point];\n"
365  " var8646911284551352321--factor0;\n"
366  " factor1[label=\"\", shape=point];\n"
367  " var8646911284551352321--factor1;\n"
368  " var8646911284551352322--factor1;\n"
369  " factor2[label=\"\", shape=point];\n"
370  " var8646911284551352321--factor2;\n"
371  " var7782220156096217089--factor2;\n"
372  " factor3[label=\"\", shape=point];\n"
373  " var8646911284551352322--factor3;\n"
374  " var7782220156096217089--factor3;\n"
375  "}\n";
376 
378  const Values c = createValues();
379 
380  stringstream ss;
381  fg.dot(ss, c);
382  EXPECT(ss.str() == expected);
383 }
384 
385 /* ************************************************************************* */
386 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
387 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
gtsam::example::createNoisyValues
Values createNoisyValues()
Definition: smallExample.h:243
Pose2.h
2D Pose
gtsam::NonlinearFactorGraph::equals
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
Definition: NonlinearFactorGraph.cpp:97
gtsam::RangeFactor
Definition: sam/RangeFactor.h:35
Eigen::DiagonalMatrix
Represents a diagonal matrix with its storage.
Definition: DiagonalMatrix.h:140
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::GaussianFactorGraph::optimizeDensely
VectorValues optimizeDensely() const
Definition: GaussianFactorGraph.cpp:323
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
TEST
TEST(NonlinearFactorGraph, equals)
Definition: testNonlinearFactorGraph.cpp:46
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Matrix.h
typedef and functions to augment Eigen's MatrixXd
RangeFactor.h
Serializable factor induced by a range measurement.
gtsam::FastMap
Definition: FastMap.h:39
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
gtsam::HessianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Definition: HessianFactor.h:109
X
#define X
Definition: icosphere.cpp:20
gtsam::Factor
Definition: Factor.h:70
gtsam::FastSet< Key >
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
iterator
Definition: pytypes.h:1460
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
gtsam::NonlinearFactorGraph::probPrime
double probPrime(const Values &values) const
Definition: NonlinearFactorGraph.cpp:49
gtsam::NonlinearFactorGraph::dot
void dot(std::ostream &os, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const
Output to graphviz format, stream version, with Values/extra options.
Definition: NonlinearFactorGraph.cpp:102
block
m m block(1, 0, 2, 2)<< 4
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::Measurement
This is the base class for all measurement types.
Definition: Measurement.h:11
gtsam::FactorGraph::erase
iterator erase(iterator item)
Definition: FactorGraph.h:377
dot
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Definition: level1_real_impl.h:49
ss
static std::stringstream ss
Definition: testBTree.cpp:31
c1
static double c1
Definition: airy.c:54
example
Definition: testOrdering.cpp:28
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam::example::createNonlinearFactorGraph
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
Definition: smallExample.h:206
z3
static const Unit3 z3
Definition: testRotateFactor.cpp:44
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
BetweenFactor.h
gtsam::example::createGaussianFactorGraph
GaussianFactorGraph createGaussianFactorGraph()
Definition: smallExample.h:270
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
DOUBLES_EQUAL
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::NonlinearFactorGraph::clone
NonlinearFactorGraph clone() const
Clone() performs a deep-copy of the graph, including all of the factors.
Definition: NonlinearFactorGraph.cpp:372
gtsam::SymbolicFactorGraph
Definition: SymbolicFactorGraph.h:61
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::FactorGraph::keys
KeySet keys() const
Definition: FactorGraph-inst.h:85
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
main
int main()
Definition: testNonlinearFactorGraph.cpp:386
L
MatrixXd L
Definition: LLT_example.cpp:6
Symbol.h
gtsam::HybridValues::insert
void insert(Key j, const Vector &value)
Definition: HybridValues.cpp:85
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
addPrior
graph addPrior(1, Pose2(0, 0, 0), priorNoise)
SymbolicFactorGraph.h
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
ordering
static enum @1096 ordering
gtsam::equals
Definition: Testable.h:112
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::NonlinearFactorGraph::printErrors
void printErrors(const Values &values, const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) {return true;}) const
Definition: NonlinearFactorGraph.cpp:71
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
FactorGraph.h
Factor Graph Base Class.
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
CHECK
#define CHECK(condition)
Definition: Test.h:108
std
Definition: BFloat16.h:88
gtsam::FactorGraph::end
const_iterator end() const
Definition: FactorGraph.h:342
c2
static double c2
Definition: airy.c:55
gtsam::NonlinearFactorGraph::updateCholesky
Values updateCholesky(const Values &values, const Dampen &dampen=nullptr) const
Definition: NonlinearFactorGraph.cpp:353
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::FactorGraph::begin
const_iterator begin() const
Definition: FactorGraph.h:339
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::example::createValues
Values createValues()
Definition: smallExample.h:212
initial
Definition: testScenarioRunner.cpp:148
gtsam::LieGroup::retract
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
different_sigmas::prior
const auto prior
Definition: testHybridBayesNet.cpp:238
gtsam::distance
Double_ distance(const OrientedPlane3_ &p)
Definition: slam/expressions.h:117
gtsam::NonlinearFactorGraph::symbolic
std::shared_ptr< SymbolicFactorGraph > symbolic() const
Definition: NonlinearFactorGraph.cpp:194
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
smallExample.h
Create small example with two poses and one landmark.
init
Definition: TutorialInplaceLU.cpp:2
gtsam::Ordering
Definition: inference/Ordering.h:33
Eigen::DiagonalMatrix::setIdentity
EIGEN_DEVICE_FUNC void setIdentity()
Definition: DiagonalMatrix.h:253
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Pose3.h
3D Pose
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Pose2
Definition: Pose2.h:39
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


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