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 
20 #include <gtsam/base/Testable.h>
21 #include <gtsam/base/Matrix.h>
22 #include <tests/smallExample.h>
24 #include <gtsam/inference/Symbol.h>
27 #include <gtsam/geometry/Pose2.h>
28 #include <gtsam/geometry/Pose3.h>
29 #include <gtsam/sam/RangeFactor.h>
31 
33 
34 #include <boost/assign/std/list.hpp>
35 #include <boost/assign/std/set.hpp>
36 using namespace boost::assign;
37 
38 /*STL/C++*/
39 #include <iostream>
40 
41 using namespace std;
42 using namespace gtsam;
43 using namespace example;
44 
47 
48 /* ************************************************************************* */
50 {
53  CHECK( fg.equals(fg2) );
54 }
55 
56 /* ************************************************************************* */
58 {
61  double actual1 = fg.error(c1);
62  DOUBLES_EQUAL( 0.0, actual1, 1e-9 );
63 
65  double actual2 = fg.error(c2);
66  DOUBLES_EQUAL( 5.625, actual2, 1e-9 );
67 }
68 
69 /* ************************************************************************* */
71 {
73  KeySet actual = fg.keys();
74  LONGS_EQUAL(3, (long)actual.size());
75  KeySet::const_iterator it = actual.begin();
76  LONGS_EQUAL((long)L(1), (long)*(it++));
77  LONGS_EQUAL((long)X(1), (long)*(it++));
78  LONGS_EQUAL((long)X(2), (long)*(it++));
79 }
80 
81 /* ************************************************************************* */
82 TEST( NonlinearFactorGraph, GET_ORDERING)
83 {
84  Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2
86  Ordering actual = Ordering::Colamd(nlfg);
87  EXPECT(assert_equal(expected,actual));
88 
89  // Constrained ordering - put x2 at the end
90  Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2);
91  FastMap<Key, int> constraints;
92  constraints[X(2)] = 1;
93  Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints);
94  EXPECT(assert_equal(expectedConstrained, actualConstrained));
95 }
96 
97 /* ************************************************************************* */
99 {
101  Values cfg = createValues();
102 
103  // evaluate the probability of the factor graph
104  double actual = fg.probPrime(cfg);
105  double expected = 1.0;
106  DOUBLES_EQUAL(expected,actual,0);
107 }
108 
109 /* ************************************************************************* */
111 {
114  GaussianFactorGraph linearFG = *fg.linearize(initial);
116  CHECK(assert_equal(expected,linearFG)); // Needs correct linearizations
117 }
118 
119 /* ************************************************************************* */
121 {
123  NonlinearFactorGraph actClone = fg.clone();
124  EXPECT(assert_equal(fg, actClone));
125  for (size_t i=0; i<fg.size(); ++i)
126  EXPECT(fg[i] != actClone[i]);
127 }
128 
129 /* ************************************************************************* */
131 {
133  map<Key,Key> rekey_mapping;
134  rekey_mapping.insert(make_pair(L(1), L(4)));
135  NonlinearFactorGraph actRekey = init.rekey(rekey_mapping);
136 
137  // ensure deep clone
138  LONGS_EQUAL((long)init.size(), (long)actRekey.size());
139  for (size_t i=0; i<init.size(); ++i)
140  EXPECT(init[i] != actRekey[i]);
141 
142  NonlinearFactorGraph expRekey;
143  // original measurements
144  expRekey.push_back(init[0]);
145  expRekey.push_back(init[1]);
146 
147  // updated measurements
148  Point2 z3(0, -1), z4(-1.5, -1.);
149  SharedDiagonal sigma0_2 = noiseModel::Isotropic::Sigma(2,0.2);
150  expRekey += simulated2D::Measurement(z3, sigma0_2, X(1), L(4));
151  expRekey += simulated2D::Measurement(z4, sigma0_2, X(2), L(4));
152 
153  EXPECT(assert_equal(expRekey, actRekey));
154 }
155 
156 /* ************************************************************************* */
158 {
160 
162  expected.push_factor(X(1));
163  expected.push_factor(X(1), X(2));
164  expected.push_factor(X(1), L(1));
165  expected.push_factor(X(2), L(1));
166 
167  SymbolicFactorGraph actual = *graph.symbolic();
168 
169  EXPECT(assert_equal(expected, actual));
170 }
171 
172 /* ************************************************************************* */
173 TEST(NonlinearFactorGraph, UpdateCholesky) {
176 
177  // solve conventionally
178  GaussianFactorGraph linearFG = *fg.linearize(initial);
179  auto delta = linearFG.optimizeDensely();
180  auto expected = initial.retract(delta);
181 
182  // solve with new method
184 
185  // solve with Ordering
187  ordering += L(1), X(2), X(1);
188  EXPECT(assert_equal(expected, fg.updateCholesky(initial, ordering)));
189 
190  // solve with new method, heavily damped
191  auto dampen = [](const HessianFactor::shared_ptr& hessianFactor) {
192  auto iterator = hessianFactor->begin();
193  for (; iterator != hessianFactor->end(); iterator++) {
194  const auto index = std::distance(hessianFactor->begin(), iterator);
195  auto block = hessianFactor->info().diagonalBlock(index);
196  for (int j = 0; j < block.rows(); j++) {
197  block(j, j) += 1e9;
198  }
199  }
200  };
201  EXPECT(assert_equal(initial, fg.updateCholesky(initial, dampen), 1e-6));
202 }
203 
204 /* ************************************************************************* */
205 // Example from issue #452 which threw an ILS error. The reason was a very
206 // weak prior on heading, which was tightened, and the ILS disappeared.
207 TEST(testNonlinearFactorGraph, eliminate) {
208  // Linearization point
209  Pose2 T11(0, 0, 0);
210  Pose2 T12(1, 0, 0);
211  Pose2 T21(0, 1, 0);
212  Pose2 T22(1, 1, 0);
213 
214  // Factor graph
215  auto graph = NonlinearFactorGraph();
216 
217  // Priors
218  auto prior = noiseModel::Isotropic::Sigma(3, 1);
219  graph.addPrior(11, T11, prior);
220  graph.addPrior(21, T21, prior);
221 
222  // Odometry
223  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.01, 0.01, 0.3));
224  graph.add(BetweenFactor<Pose2>(11, 12, T11.between(T12), model));
225  graph.add(BetweenFactor<Pose2>(21, 22, T21.between(T22), model));
226 
227  // Range factor
228  auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01);
229  graph.add(RangeFactor<Pose2>(12, 22, 1.0, model_rho));
230 
231  Values values;
232  values.insert(11, T11.retract(Vector3(0.1,0.2,0.3)));
233  values.insert(12, T12);
234  values.insert(21, T21);
235  values.insert(22, T22);
236  auto linearized = graph.linearize(values);
237 
238  // Eliminate
240  ordering += 11, 21, 12, 22;
241  auto bn = linearized->eliminateSequential(ordering);
242  EXPECT_LONGS_EQUAL(4, bn->size());
243 }
244 
245 /* ************************************************************************* */
246 TEST(testNonlinearFactorGraph, addPrior) {
247  Key k(0);
248 
249  // Factor graph.
250  auto graph = NonlinearFactorGraph();
251 
252  // Add a prior factor for key k.
253  auto model_double = noiseModel::Isotropic::Sigma(1, 1);
254  graph.addPrior<double>(k, 10, model_double);
255 
256  // Assert the graph has 0 error with the correct values.
257  Values values;
258  values.insert(k, 10.0);
259  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-16);
260 
261  // Assert the graph has some error with incorrect values.
262  values.clear();
263  values.insert(k, 11.0);
264  EXPECT(0 != graph.error(values));
265 
266  // Clear the factor graph and values.
267  values.clear();
268  graph.erase(graph.begin(), graph.end());
269 
270  // Add a Pose3 prior to the factor graph. Use a gaussian noise model by
271  // providing the covariance matrix.
272  Eigen::DiagonalMatrix<double, 6, 6> covariance_pose3;
273  covariance_pose3.setIdentity();
274  Pose3 pose{Rot3(), Point3(0, 0, 0)};
275  graph.addPrior(k, pose, covariance_pose3);
276 
277  // Assert the graph has 0 error with the correct values.
278  values.insert(k, pose);
279  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-16);
280 
281  // Assert the graph has some error with incorrect values.
282  values.clear();
283  Pose3 pose_incorrect{Rot3::RzRyRx(-M_PI, M_PI, -M_PI / 8), Point3(1, 2, 3)};
284  values.insert(k, pose_incorrect);
285  EXPECT(0 != graph.error(values));
286 }
287 
289 {
291  const Values c = createValues();
292 
293  // Test that it builds with default parameters.
294  // We cannot check the output since (at present) output is fixed to std::cout.
295  fg.printErrors(c);
296 
297  // Second round: using callback filter to check that we actually visit all factors:
298  std::vector<bool> visited;
299  visited.assign(fg.size(), false);
300  const auto testFilter =
301  [&](const gtsam::Factor *f, double error, size_t index) {
302  EXPECT(f!=nullptr);
303  EXPECT(error>=.0);
304  visited.at(index)=true;
305  return false; // do not print
306  };
307  fg.printErrors(c,"Test graph: ", gtsam::DefaultKeyFormatter,testFilter);
308 
309  for (bool visit : visited) EXPECT(visit==true);
310 }
311 
312 /* ************************************************************************* */
313 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
314 /* ************************************************************************* */
size_t size() const
Definition: FactorGraph.h:306
#define CHECK(condition)
Definition: Test.h:109
static const Key c2
Values createNoisyValues()
Definition: smallExample.h:245
NonlinearFactorGraph clone() const
Clone() performs a deep-copy of the graph, including all of the factors.
m m block(1, 0, 2, 2)<< 4
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Factor Graph consisting of non-linear factors.
GaussianFactorGraph createGaussianFactorGraph()
Definition: smallExample.h:272
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static enum @843 ordering
Matrix expected
Definition: testMatrix.cpp:974
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
Vector2 Point2
Definition: Point2.h:27
KeySet keys() const
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
#define M_PI
Definition: main.h:78
leaf::MyValues values
Represents a diagonal matrix with its storage.
Values updateCholesky(const Values &values, const Dampen &dampen=nullptr) const
MatrixXd L
Definition: LLT_example.cpp:6
Definition: Half.h:150
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
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
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:190
const_iterator begin() const
Definition: FactorGraph.h:333
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
static const Unit3 z3
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:263
#define EXPECT(condition)
Definition: Test.h:151
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
Definition: smallExample.h:207
const_iterator end() const
Definition: FactorGraph.h:336
NonlinearFactorGraph rekey(const std::map< Key, Key > &rekey_mapping) const
double probPrime(const Values &values) const
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
boost::shared_ptr< SymbolicFactorGraph > symbolic() const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
graph addPrior(1, priorMean, priorNoise)
TEST(NonlinearFactorGraph, equals)
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
VectorValues optimizeDensely() const
Factor Graph Base Class.
Class between(const Class &g) const
Definition: Lie.h:51
Create small example with two poses and one landmark.
static double error
Definition: testRot3.cpp:39
Vector3 Point3
Definition: Point3.h:35
Values createValues()
Definition: smallExample.h:213
EIGEN_DEVICE_FUNC void setIdentity()
double error(const Values &values) const
const KeyVector keys
2D Pose
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
#define X
Definition: icosphere.cpp:20
3D Pose
iterator erase(iterator item)
Definition: FactorGraph.h:368
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
static const Key c1


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:21