GaussianMixtureFactor.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 
21 #pragma once
22 
29 
30 namespace gtsam {
31 
32 class HybridValues;
33 class DiscreteValues;
34 class VectorValues;
35 
47 class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
48  public:
49  using Base = HybridFactor;
51  using shared_ptr = std::shared_ptr<This>;
52 
53  using sharedFactor = std::shared_ptr<GaussianFactor>;
54 
57 
58  private:
61 
68  GaussianFactorGraphTree asGaussianFactorGraphTree() const;
69 
70  public:
73 
75  GaussianMixtureFactor() = default;
76 
86  GaussianMixtureFactor(const KeyVector &continuousKeys,
87  const DiscreteKeys &discreteKeys,
88  const Factors &factors);
89 
98  GaussianMixtureFactor(const KeyVector &continuousKeys,
99  const DiscreteKeys &discreteKeys,
100  const std::vector<sharedFactor> &factors)
101  : GaussianMixtureFactor(continuousKeys, discreteKeys,
102  Factors(discreteKeys, factors)) {}
103 
107 
108  bool equals(const HybridFactor &lf, double tol = 1e-9) const override;
109 
110  void print(
111  const std::string &s = "GaussianMixtureFactor\n",
112  const KeyFormatter &formatter = DefaultKeyFormatter) const override;
113 
117 
119  sharedFactor operator()(const DiscreteValues &assignment) const;
120 
130 
138  AlgebraicDecisionTree<Key> errorTree(const VectorValues &continuousValues) const;
139 
144  double error(const HybridValues &values) const override;
145 
147  const Factors &factors() const { return factors_; }
148 
151  GaussianFactorGraphTree &sum, const GaussianMixtureFactor &factor) {
152  sum = factor.add(sum);
153  return sum;
154  }
156 
157  private:
158 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
159 
160  friend class boost::serialization::access;
161  template <class ARCHIVE>
162  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
163  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
164  ar &BOOST_SERIALIZATION_NVP(factors_);
165  }
166 #endif
167 };
168 
169 // traits
170 template <>
171 struct traits<GaussianMixtureFactor> : public Testable<GaussianMixtureFactor> {
172 };
173 
174 } // namespace gtsam
VectorValues
gtsam::GaussianMixtureFactor
Implementation of a discrete conditional mixture factor. Implements a joint discrete-continuous facto...
Definition: GaussianMixtureFactor.h:47
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::HybridValues
Definition: HybridValues.h:38
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::HybridFactor
Definition: HybridFactor.h:53
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
HybridValues
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::GaussianMixtureFactor::sharedFactor
std::shared_ptr< GaussianFactor > sharedFactor
Definition: GaussianMixtureFactor.h:53
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::AlgebraicDecisionTree< Key >
AlgebraicDecisionTree.h
Algebraic Decision Trees.
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::GaussianMixtureFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: GaussianMixtureFactor.h:51
HybridFactor.h
gtsam::VectorValues
Definition: VectorValues.h:74
operator()
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
Definition: IndexedViewMethods.h:73
gtsam::KeyFormatter
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
DecisionTree.h
Decision Tree for use in DiscreteFactors.
add
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
gtsam::GaussianMixtureFactor::add
GaussianFactorGraphTree add(const GaussianFactorGraphTree &sum) const
Combine the Gaussian Factor Graphs in sum and this while maintaining the original tree structure.
Definition: GaussianMixtureFactor.cpp:85
DiscreteValues
gtsam::GaussianMixtureFactor::operator+=
friend GaussianFactorGraphTree & operator+=(GaussianFactorGraphTree &sum, const GaussianMixtureFactor &factor)
Add MixtureFactor to a Sum, syntactic sugar.
Definition: GaussianMixtureFactor.h:150
gtsam::equals
Definition: Testable.h:112
DiscreteKey.h
specialized key for discrete variables
gtsam::DecisionTree< Key, sharedFactor >
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
error
static double error
Definition: testRot3.cpp:37
gtsam::traits
Definition: Group.h:36
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
leaf::values
leaf::MyValues values
gtsam::GaussianMixtureFactor::factors_
Factors factors_
Decision tree of Gaussian factors indexed by discrete keys.
Definition: GaussianMixtureFactor.h:60
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::GaussianMixtureFactor::GaussianMixtureFactor
GaussianMixtureFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys, const std::vector< sharedFactor > &factors)
Construct a new GaussianMixtureFactor object using a vector of GaussianFactor shared pointers.
Definition: GaussianMixtureFactor.h:98
GaussianFactor.h
A factor with a quadratic error function - a Gaussian.
Base
Definition: test_virtual_functions.cpp:156
gtsam::GaussianMixtureFactor::factors
const Factors & factors() const
Getter for GaussianFactor decision tree.
Definition: GaussianMixtureFactor.h:147


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:54