NonlinearFactorGraph.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/geometry/Pose2.h>
21 #include <gtsam/geometry/Pose3.h>
23 #include <gtsam/nonlinear/Values.h>
30 #include <gtsam/config.h> // for GTSAM_USE_TBB
31 
32 #ifdef GTSAM_USE_TBB
33 # include <tbb/parallel_for.h>
34 #endif
35 
36 #include <cmath>
37 #include <fstream>
38 #include <limits>
39 
40 using namespace std;
41 
42 namespace gtsam {
43 
44 // Instantiate base classes
45 template class FactorGraph<NonlinearFactor>;
46 
47 /* ************************************************************************* */
48 double NonlinearFactorGraph::probPrime(const Values& values) const {
49  return exp(-0.5 * error(values));
50 }
51 
52 /* ************************************************************************* */
53 void NonlinearFactorGraph::print(const std::string& str, const KeyFormatter& keyFormatter) const {
54  cout << str << "size: " << size() << endl << endl;
55  for (size_t i = 0; i < factors_.size(); i++) {
56  stringstream ss;
57  ss << "Factor " << i << ": ";
58  if (factors_[i] != nullptr) factors_[i]->print(ss.str(), keyFormatter);
59  cout << endl;
60  }
61 }
62 
63 /* ************************************************************************* */
64 void NonlinearFactorGraph::printErrors(const Values& values, const std::string& str,
65  const KeyFormatter& keyFormatter,
66  const std::function<bool(const Factor* /*factor*/, double /*whitenedError*/, size_t /*index*/)>& printCondition) const
67 {
68  cout << str << "size: " << size() << endl
69  << endl;
70  for (size_t i = 0; i < factors_.size(); i++) {
71  const sharedFactor& factor = factors_[i];
72  const double errorValue = (factor != nullptr ? factors_[i]->error(values) : .0);
73  if (!printCondition(factor.get(),errorValue,i))
74  continue; // User-provided filter did not pass
75 
76  stringstream ss;
77  ss << "Factor " << i << ": ";
78  if (factor == nullptr) {
79  cout << "nullptr" << "\n";
80  } else {
81  factor->print(ss.str(), keyFormatter);
82  cout << "error = " << errorValue << "\n";
83  }
84  cout << endl; // only one "endl" at end might be faster, \n for each factor
85  }
86 }
87 
88 /* ************************************************************************* */
89 bool NonlinearFactorGraph::equals(const NonlinearFactorGraph& other, double tol) const {
90  return Base::equals(other, tol);
91 }
92 
93 /* ************************************************************************* */
94 void NonlinearFactorGraph::saveGraph(std::ostream &stm, const Values& values,
95  const GraphvizFormatting& formatting,
96  const KeyFormatter& keyFormatter) const
97 {
98  stm << "graph {\n";
99  stm << " size=\"" << formatting.figureWidthInches << "," <<
100  formatting.figureHeightInches << "\";\n\n";
101 
102  KeySet keys = this->keys();
103 
104  // Local utility function to extract x and y coordinates
105  struct { boost::optional<Point2> operator()(
106  const Value& value, const GraphvizFormatting& graphvizFormatting)
107  {
108  Vector3 t;
109  if (const GenericValue<Pose2>* p = dynamic_cast<const GenericValue<Pose2>*>(&value)) {
110  t << p->value().x(), p->value().y(), 0;
111  } else if (const GenericValue<Point2>* p = dynamic_cast<const GenericValue<Point2>*>(&value)) {
112  t << p->value().x(), p->value().y(), 0;
113  } else if (const GenericValue<Pose3>* p = dynamic_cast<const GenericValue<Pose3>*>(&value)) {
114  t = p->value().translation();
115  } else if (const GenericValue<Point3>* p = dynamic_cast<const GenericValue<Point3>*>(&value)) {
116  t = p->value();
117  } else {
118  return boost::none;
119  }
120  double x, y;
121  switch (graphvizFormatting.paperHorizontalAxis) {
122  case GraphvizFormatting::X: x = t.x(); break;
123  case GraphvizFormatting::Y: x = t.y(); break;
124  case GraphvizFormatting::Z: x = t.z(); break;
125  case GraphvizFormatting::NEGX: x = -t.x(); break;
126  case GraphvizFormatting::NEGY: x = -t.y(); break;
127  case GraphvizFormatting::NEGZ: x = -t.z(); break;
128  default: throw std::runtime_error("Invalid enum value");
129  }
130  switch (graphvizFormatting.paperVerticalAxis) {
131  case GraphvizFormatting::X: y = t.x(); break;
132  case GraphvizFormatting::Y: y = t.y(); break;
133  case GraphvizFormatting::Z: y = t.z(); break;
134  case GraphvizFormatting::NEGX: y = -t.x(); break;
135  case GraphvizFormatting::NEGY: y = -t.y(); break;
136  case GraphvizFormatting::NEGZ: y = -t.z(); break;
137  default: throw std::runtime_error("Invalid enum value");
138  }
139  return Point2(x,y);
140  }} getXY;
141 
142  // Find bounds
143  double minX = numeric_limits<double>::infinity(), maxX = -numeric_limits<double>::infinity();
144  double minY = numeric_limits<double>::infinity(), maxY = -numeric_limits<double>::infinity();
145  for (const Key& key : keys) {
146  if (values.exists(key)) {
147  boost::optional<Point2> xy = getXY(values.at(key), formatting);
148  if(xy) {
149  if(xy->x() < minX)
150  minX = xy->x();
151  if(xy->x() > maxX)
152  maxX = xy->x();
153  if(xy->y() < minY)
154  minY = xy->y();
155  if(xy->y() > maxY)
156  maxY = xy->y();
157  }
158  }
159  }
160 
161  // Create nodes for each variable in the graph
162  for(Key key: keys){
163  // Label the node with the label from the KeyFormatter
164  stm << " var" << key << "[label=\"" << keyFormatter(key) << "\"";
165  if(values.exists(key)) {
166  boost::optional<Point2> xy = getXY(values.at(key), formatting);
167  if(xy)
168  stm << ", pos=\"" << formatting.scale*(xy->x() - minX) << "," << formatting.scale*(xy->y() - minY) << "!\"";
169  }
170  stm << "];\n";
171  }
172  stm << "\n";
173 
174  if (formatting.mergeSimilarFactors) {
175  // Remove duplicate factors
176  std::set<KeyVector > structure;
177  for (const sharedFactor& factor : factors_) {
178  if (factor) {
179  KeyVector factorKeys = factor->keys();
180  std::sort(factorKeys.begin(), factorKeys.end());
181  structure.insert(factorKeys);
182  }
183  }
184 
185  // Create factors and variable connections
186  size_t i = 0;
187  for(const KeyVector& factorKeys: structure){
188  // Make each factor a dot
189  stm << " factor" << i << "[label=\"\", shape=point";
190  {
191  map<size_t, Point2>::const_iterator pos = formatting.factorPositions.find(i);
192  if(pos != formatting.factorPositions.end())
193  stm << ", pos=\"" << formatting.scale*(pos->second.x() - minX) << ","
194  << formatting.scale*(pos->second.y() - minY) << "!\"";
195  }
196  stm << "];\n";
197 
198  // Make factor-variable connections
199  for(Key key: factorKeys) {
200  stm << " var" << key << "--" << "factor" << i << ";\n";
201  }
202 
203  ++ i;
204  }
205  } else {
206  // Create factors and variable connections
207  for(size_t i = 0; i < size(); ++i) {
208  const NonlinearFactor::shared_ptr& factor = at(i);
209  // If null pointer, move on to the next
210  if (!factor) {
211  continue;
212  }
213 
214  if (formatting.plotFactorPoints) {
215  const KeyVector& keys = factor->keys();
216  if (formatting.binaryEdges && keys.size() == 2) {
217  stm << " var" << keys[0] << "--"
218  << "var" << keys[1] << ";\n";
219  } else {
220  // Make each factor a dot
221  stm << " factor" << i << "[label=\"\", shape=point";
222  {
223  map<size_t, Point2>::const_iterator pos =
224  formatting.factorPositions.find(i);
225  if (pos != formatting.factorPositions.end())
226  stm << ", pos=\"" << formatting.scale * (pos->second.x() - minX)
227  << "," << formatting.scale * (pos->second.y() - minY)
228  << "!\"";
229  }
230  stm << "];\n";
231 
232  // Make factor-variable connections
233  if (formatting.connectKeysToFactor && factor) {
234  for (Key key : *factor) {
235  stm << " var" << key << "--"
236  << "factor" << i << ";\n";
237  }
238  }
239  }
240  } else {
241  Key k;
242  bool firstTime = true;
243  for (Key key : *this->at(i)) {
244  if (firstTime) {
245  k = key;
246  firstTime = false;
247  continue;
248  }
249  stm << " var" << key << "--"
250  << "var" << k << ";\n";
251  k = key;
252  }
253  }
254  }
255  }
256 
257  stm << "}\n";
258 }
259 
260 /* ************************************************************************* */
261 void NonlinearFactorGraph::saveGraph(
262  const std::string& file, const Values& values,
263  const GraphvizFormatting& graphvizFormatting,
264  const KeyFormatter& keyFormatter) const {
265  std::ofstream of(file);
266  saveGraph(of, values, graphvizFormatting, keyFormatter);
267  of.close();
268 }
269 
270 /* ************************************************************************* */
271 double NonlinearFactorGraph::error(const Values& values) const {
272  gttic(NonlinearFactorGraph_error);
273  double total_error = 0.;
274  // iterate over all the factors_ to accumulate the log probabilities
275  for(const sharedFactor& factor: factors_) {
276  if(factor)
277  total_error += factor->error(values);
278  }
279  return total_error;
280 }
281 
282 /* ************************************************************************* */
283 Ordering NonlinearFactorGraph::orderingCOLAMD() const
284 {
285  return Ordering::Colamd(*this);
286 }
287 
288 /* ************************************************************************* */
289 Ordering NonlinearFactorGraph::orderingCOLAMDConstrained(const FastMap<Key, int>& constraints) const
290 {
291  return Ordering::ColamdConstrained(*this, constraints);
292 }
293 
294 /* ************************************************************************* */
295 SymbolicFactorGraph::shared_ptr NonlinearFactorGraph::symbolic() const
296 {
297  // Generate the symbolic factor graph
298  SymbolicFactorGraph::shared_ptr symbolic = boost::make_shared<SymbolicFactorGraph>();
299  symbolic->reserve(size());
300 
301  for (const sharedFactor& factor: factors_) {
302  if(factor)
303  *symbolic += SymbolicFactor(*factor);
304  else
305  *symbolic += SymbolicFactorGraph::sharedFactor();
306  }
307 
308  return symbolic;
309 }
310 
311 /* ************************************************************************* */
312 namespace {
313 
314 #ifdef GTSAM_USE_TBB
315 class _LinearizeOneFactor {
316  const NonlinearFactorGraph& nonlinearGraph_;
317  const Values& linearizationPoint_;
318  GaussianFactorGraph& result_;
319 public:
320  // Create functor with constant parameters
321  _LinearizeOneFactor(const NonlinearFactorGraph& graph,
322  const Values& linearizationPoint, GaussianFactorGraph& result) :
323  nonlinearGraph_(graph), linearizationPoint_(linearizationPoint), result_(result) {
324  }
325  // Operator that linearizes a given range of the factors
326  void operator()(const tbb::blocked_range<size_t>& blocked_range) const {
327  for (size_t i = blocked_range.begin(); i != blocked_range.end(); ++i) {
328  if (nonlinearGraph_[i])
329  result_[i] = nonlinearGraph_[i]->linearize(linearizationPoint_);
330  else
331  result_[i] = GaussianFactor::shared_ptr();
332  }
333  }
334 };
335 #endif
336 
337 }
338 
339 /* ************************************************************************* */
340 GaussianFactorGraph::shared_ptr NonlinearFactorGraph::linearize(const Values& linearizationPoint) const
341 {
342  gttic(NonlinearFactorGraph_linearize);
343 
344  // create an empty linear FG
345  GaussianFactorGraph::shared_ptr linearFG = boost::make_shared<GaussianFactorGraph>();
346 
347 #ifdef GTSAM_USE_TBB
348 
349  linearFG->resize(size());
350  TbbOpenMPMixedScope threadLimiter; // Limits OpenMP threads since we're mixing TBB and OpenMP
351  tbb::parallel_for(tbb::blocked_range<size_t>(0, size()),
352  _LinearizeOneFactor(*this, linearizationPoint, *linearFG));
353 
354 #else
355 
356  linearFG->reserve(size());
357 
358  // linearize all factors
359  for(const sharedFactor& factor: factors_) {
360  if(factor) {
361  (*linearFG) += factor->linearize(linearizationPoint);
362  } else
363  (*linearFG) += GaussianFactor::shared_ptr();
364  }
365 
366 #endif
367 
368  return linearFG;
369 }
370 
371 /* ************************************************************************* */
372 static Scatter scatterFromValues(const Values& values) {
374 
375  Scatter scatter;
376  scatter.reserve(values.size());
377 
378  // use "natural" ordering with keys taken from the initial values
379  for (const auto key_value : values) {
380  scatter.add(key_value.key, key_value.value.dim());
381  }
382 
383  return scatter;
384 }
385 
386 /* ************************************************************************* */
387 static Scatter scatterFromValues(const Values& values, const Ordering& ordering) {
389 
390  Scatter scatter;
391  scatter.reserve(values.size());
392 
393  // copy ordering into keys and lookup dimension in values, is O(n*log n)
394  for (Key key : ordering) {
395  const Value& value = values.at(key);
396  scatter.add(key, value.dim());
397  }
398 
399  return scatter;
400 }
401 
402 /* ************************************************************************* */
403 HessianFactor::shared_ptr NonlinearFactorGraph::linearizeToHessianFactor(
404  const Values& values, const Scatter& scatter, const Dampen& dampen) const {
405  // NOTE(frank): we are heavily leaning on friendship below
406  HessianFactor::shared_ptr hessianFactor(new HessianFactor(scatter));
407 
408  // Initialize so we can rank-update below
409  hessianFactor->info_.setZero();
410 
411  // linearize all factors straight into the Hessian
412  // TODO(frank): this saves on creating the graph, but still mallocs a gaussianFactor!
413  for (const sharedFactor& nonlinearFactor : factors_) {
414  if (nonlinearFactor) {
415  const auto& gaussianFactor = nonlinearFactor->linearize(values);
416  gaussianFactor->updateHessian(hessianFactor->keys_, &hessianFactor->info_);
417  }
418  }
419 
420  if (dampen) dampen(hessianFactor);
421 
422  return hessianFactor;
423 }
424 
425 /* ************************************************************************* */
426 HessianFactor::shared_ptr NonlinearFactorGraph::linearizeToHessianFactor(
427  const Values& values, const Ordering& order, const Dampen& dampen) const {
428  gttic(NonlinearFactorGraph_linearizeToHessianFactor);
429 
430  Scatter scatter = scatterFromValues(values, order);
431  return linearizeToHessianFactor(values, scatter, dampen);
432 }
433 
434 /* ************************************************************************* */
435 HessianFactor::shared_ptr NonlinearFactorGraph::linearizeToHessianFactor(
436  const Values& values, const Dampen& dampen) const {
437  gttic(NonlinearFactorGraph_linearizeToHessianFactor);
438 
439  Scatter scatter = scatterFromValues(values);
440  return linearizeToHessianFactor(values, scatter, dampen);
441 }
442 
443 /* ************************************************************************* */
444 Values NonlinearFactorGraph::updateCholesky(const Values& values,
445  const Dampen& dampen) const {
446  gttic(NonlinearFactorGraph_updateCholesky);
447  auto hessianFactor = linearizeToHessianFactor(values, dampen);
448  VectorValues delta = hessianFactor->solve();
449  return values.retract(delta);
450 }
451 
452 /* ************************************************************************* */
453 Values NonlinearFactorGraph::updateCholesky(const Values& values,
454  const Ordering& ordering,
455  const Dampen& dampen) const {
456  gttic(NonlinearFactorGraph_updateCholesky);
457  auto hessianFactor = linearizeToHessianFactor(values, ordering, dampen);
458  VectorValues delta = hessianFactor->solve();
459  return values.retract(delta);
460 }
461 
462 /* ************************************************************************* */
463 NonlinearFactorGraph NonlinearFactorGraph::clone() const {
465  for (const sharedFactor& f : factors_) {
466  if (f)
467  result.push_back(f->clone());
468  else
469  result.push_back(sharedFactor()); // Passes on null factors so indices remain valid
470  }
471  return result;
472 }
473 
474 /* ************************************************************************* */
475 NonlinearFactorGraph NonlinearFactorGraph::rekey(const std::map<Key,Key>& rekey_mapping) const {
477  for (const sharedFactor& f : factors_) {
478  if (f)
479  result.push_back(f->rekey(rekey_mapping));
480  else
481  result.push_back(sharedFactor());
482  }
483  return result;
484 }
485 
486 /* ************************************************************************* */
487 
488 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
bool mergeSimilarFactors
Merge multiple factors that have the same connectivity.
bool exists(Key j) const
Definition: Values.cpp:104
double scale
Scale all positions to reduce / increase density.
GTSAM_EXPORT void add(Key key, size_t dim)
Add a key/dim pair.
Definition: Scatter.cpp:76
Scalar * y
std::map< size_t, Point2 > factorPositions
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
bool connectKeysToFactor
Draw a line from each key within a factor to the dot of the factor.
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Vector2 Point2
Definition: Point2.h:27
leaf::MyValues values
Definition: Half.h:150
Matrix< float, 2, 1 > xy
Definition: LLT_solve.cpp:7
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
NonlinearFactorGraph graph
bool plotFactorPoints
Plots each factor as a dot between the variables.
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
#define Z
Definition: icosphere.cpp:21
#define gttic(label)
Definition: timing.h:280
Factor Graph Values.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
size_t size() const
Definition: Values.h:236
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
std::function< void(const boost::shared_ptr< HessianFactor > &hessianFactor)> Dampen
typdef for dampen functions used below
Definition: pytypes.h:928
boost::shared_ptr< This > shared_ptr
boost::shared_ptr< NonlinearFactor > sharedFactor
Shared pointer to a factor.
Definition: FactorGraph.h:98
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Axis paperHorizontalAxis
The world axis assigned to the horizontal paper axis.
Axis paperVerticalAxis
The world axis assigned to the vertical paper axis.
Linear Factor Graph where all factors are Gaussians.
bool binaryEdges
just use non-dotted edges for binary factors
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
virtual size_t dim() const =0
Exceptions that may be thrown by linear solver components.
static std::stringstream ss
Definition: testBTree.cpp:33
static Scatter scatterFromValues(const Values &values, const Ordering &ordering)
traits
Definition: chartTesting.h:28
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
float * p
A Gaussian factor using the canonical parameters (information form)
double figureHeightInches
The figure height on paper in inches.
static double error
Definition: testRot3.cpp:39
const G double tol
Definition: Group.h:83
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
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
double figureWidthInches
The figure width on paper in inches.
Point2 t(10, 10)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:03