GaussianFactorGraph.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 #pragma once
23 
29 #include <gtsam/linear/Errors.h> // Included here instead of fw-declared so we can use Errors::iterator
30 
31 namespace gtsam {
32 
33  // Forward declarations
34  class GaussianFactorGraph;
35  class GaussianFactor;
36  class GaussianConditional;
37  class GaussianBayesNet;
38  class GaussianEliminationTree;
39  class GaussianBayesTree;
40  class GaussianJunctionTree;
41 
42  /* ************************************************************************* */
44  {
52  static std::pair<boost::shared_ptr<ConditionalType>, boost::shared_ptr<FactorType> >
54  DefaultEliminate(const FactorGraphType& factors, const Ordering& keys) {
55  return EliminatePreferCholesky(factors, keys); }
56  };
57 
58  /* ************************************************************************* */
65  class GTSAM_EXPORT GaussianFactorGraph :
66  public FactorGraph<GaussianFactor>,
67  public EliminateableFactorGraph<GaussianFactorGraph>
68  {
69  public:
70 
74  typedef boost::shared_ptr<This> shared_ptr;
75 
78 
80  template<typename ITERATOR>
81  GaussianFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor) : Base(firstFactor, lastFactor) {}
82 
84  template<class CONTAINER>
85  explicit GaussianFactorGraph(const CONTAINER& factors) : Base(factors) {}
86 
88  template<class DERIVEDFACTOR>
90 
92  virtual ~GaussianFactorGraph() {}
93 
96 
97  bool equals(const This& fg, double tol = 1e-9) const;
98 
100 
102  void add(const GaussianFactor& factor) { push_back(factor.clone()); }
103 
105  void add(const sharedFactor& factor) { push_back(factor); }
106 
108  void add(const Vector& b) {
109  add(JacobianFactor(b)); }
110 
112  void add(Key key1, const Matrix& A1,
113  const Vector& b, const SharedDiagonal& model = SharedDiagonal()) {
114  add(JacobianFactor(key1,A1,b,model)); }
115 
117  void add(Key key1, const Matrix& A1,
118  Key key2, const Matrix& A2,
119  const Vector& b, const SharedDiagonal& model = SharedDiagonal()) {
120  add(JacobianFactor(key1,A1,key2,A2,b,model)); }
121 
123  void add(Key key1, const Matrix& A1,
124  Key key2, const Matrix& A2,
125  Key key3, const Matrix& A3,
126  const Vector& b, const SharedDiagonal& model = SharedDiagonal()) {
127  add(JacobianFactor(key1,A1,key2,A2,key3,A3,b,model)); }
128 
130  template<class TERMS>
131  void add(const TERMS& terms, const Vector &b, const SharedDiagonal& model = SharedDiagonal()) {
132  add(JacobianFactor(terms,b,model)); }
133 
138  typedef KeySet Keys;
139  Keys keys() const;
140 
141  /* return a map of (Key, dimension) */
142  std::map<Key, size_t> getKeyDimMap() const;
143 
145  double error(const VectorValues& x) const {
146  double total_error = 0.;
147  for(const sharedFactor& factor: *this){
148  if(factor)
149  total_error += factor->error(x);
150  }
151  return total_error;
152  }
153 
155  double probPrime(const VectorValues& c) const {
156  return exp(-0.5 * error(c));
157  }
158 
164  virtual GaussianFactorGraph clone() const;
165 
170  virtual GaussianFactorGraph::shared_ptr cloneToPtr() const;
171 
178  GaussianFactorGraph negate() const;
179 
182 
193  std::vector<std::tuple<int, int, double> > sparseJacobian(
194  const Ordering& ordering, size_t& nrows, size_t& ncols) const;
195 
197  std::vector<std::tuple<int, int, double> > sparseJacobian() const;
198 
205  Matrix sparseJacobian_() const;
206 
214  Matrix augmentedJacobian(const Ordering& ordering) const;
215 
223  Matrix augmentedJacobian() const;
224 
232  std::pair<Matrix,Vector> jacobian(const Ordering& ordering) const;
233 
241  std::pair<Matrix,Vector> jacobian() const;
242 
254  Matrix augmentedHessian(const Ordering& ordering) const;
255 
267  Matrix augmentedHessian() const;
268 
275  std::pair<Matrix,Vector> hessian(const Ordering& ordering) const;
276 
283  std::pair<Matrix,Vector> hessian() const;
284 
286  virtual VectorValues hessianDiagonal() const;
287 
289  virtual std::map<Key,Matrix> hessianBlockDiagonal() const;
290 
296  const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
297 
303  const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
304 
308  VectorValues optimizeDensely() const;
309 
319  VectorValues gradient(const VectorValues& x0) const;
320 
328  virtual VectorValues gradientAtZero() const;
329 
354  VectorValues optimizeGradientSearch() const;
355 
357  VectorValues transposeMultiply(const Errors& e) const;
358 
360  void transposeMultiplyAdd(double alpha, const Errors& e, VectorValues& x) const;
361 
363  Errors gaussianErrors(const VectorValues& x) const;
364 
366  Errors operator*(const VectorValues& x) const;
367 
369  void multiplyHessianAdd(double alpha, const VectorValues& x,
370  VectorValues& y) const;
371 
373  void multiplyInPlace(const VectorValues& x, Errors& e) const;
374 
376  void multiplyInPlace(const VectorValues& x, const Errors::iterator& e) const;
377 
379 
380  private:
382  friend class boost::serialization::access;
383  template<class ARCHIVE>
384  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
385  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
386  }
387 
388  public:
389 
391  VectorValues optimize(boost::none_t,
392  const Eliminate& function = EliminationTraitsType::DefaultEliminate) const;
393 
394  };
395 
400  GTSAM_EXPORT bool hasConstraints(const GaussianFactorGraph& factors);
401 
402  /****** Linear Algebra Opeations ******/
403 
405  //GTSAM_EXPORT void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
406  //GTSAM_EXPORT void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
407 
409 template<>
410 struct traits<GaussianFactorGraph> : public Testable<GaussianFactorGraph> {
411 };
412 
413 } // \ namespace gtsam
GaussianFactorGraph FactorGraphType
Type of the factor graph (e.g. GaussianFactorGraph)
vector of errors
Scalar * y
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
Variable elimination algorithms for factor graphs.
noiseModel::Diagonal::shared_ptr model
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
GaussianEliminationTree EliminationTreeType
Type of elimination tree.
static std::pair< boost::shared_ptr< ConditionalType >, boost::shared_ptr< FactorType > > DefaultEliminate(const FactorGraphType &factors, const Ordering &keys)
The default dense elimination function.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
A factor with a quadratic error function - a Gaussian.
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
GaussianFactorGraph(const FactorGraph< DERIVEDFACTOR > &graph)
virtual GaussianFactor::shared_ptr clone() const =0
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:45
NonlinearFactorGraph graph
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
graph add(boost::make_shared< UnaryFactor >(1, 0.0, 0.0, unaryNoise))
double error(const VectorValues &x) const
const Symbol key1('v', 1)
T negate(const T &x)
Definition: packetmath.cpp:27
void add(const GaussianFactor &factor)
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
GaussianFactorGraph(ITERATOR firstFactor, ITERATOR lastFactor)
Eigen::VectorXd Vector
Definition: Vector.h:38
EliminateableFactorGraph< This > BaseEliminateable
Typedef to base elimination class.
void serialize(ARCHIVE &ar, const unsigned int)
void add(Key key1, const Matrix &A1, Key key2, const Matrix &A2, Key key3, const Matrix &A3, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
boost::shared_ptr< GaussianFactor > sharedFactor
Shared pointer to a factor.
Definition: FactorGraph.h:98
RealScalar alpha
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const G & b
Definition: Group.h:83
static Symbol x0('x', 0)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
GaussianFactorGraph(const CONTAINER &factors)
traits
Definition: chartTesting.h:28
GaussianConditional ConditionalType
Type of conditionals from elimination.
bool hasConstraints(const GaussianFactorGraph &factors)
GaussianBayesTree BayesTreeType
Type of Bayes tree.
void add(Key key1, const Matrix &A1, Key key2, const Matrix &A2, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
const Symbol key3('v', 3)
const Symbol key2('v', 2)
Factor Graph Base Class.
void add(Key key1, const Matrix &A1, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
GaussianBayesNet BayesNetType
Type of Bayes net from sequential elimination.
boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
GaussianFactor FactorType
Type of factors in factor graph.
GaussianFactorGraph This
Typedef to this class.
static double error
Definition: testRot3.cpp:39
FactorGraph< GaussianFactor > Base
Typedef to base factor graph type.
void add(const sharedFactor &factor)
const G double tol
Definition: Group.h:83
double probPrime(const VectorValues &c) const
void add(const TERMS &terms, const Vector &b, const SharedDiagonal &model=SharedDiagonal())
const KeyVector keys
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:05