HybridGaussianProductFactor.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 
19 #pragma once
20 
22 #include <gtsam/inference/Key.h>
24 
25 #include <iostream>
26 
27 namespace gtsam {
28 
29 class HybridGaussianFactor;
30 
31 using GaussianFactorGraphValuePair = std::pair<GaussianFactorGraph, double>;
32 
34 class GTSAM_EXPORT HybridGaussianProductFactor
35  : public DecisionTree<Key, GaussianFactorGraphValuePair> {
36  public:
38 
41 
43  HybridGaussianProductFactor() = default;
44 
50  template <class FACTOR>
51  HybridGaussianProductFactor(const std::shared_ptr<FACTOR>& factor)
53 
59 
61 
64 
67  const GaussianFactor::shared_ptr& factor) const;
68 
71  const HybridGaussianFactor& factor) const;
72 
75  const GaussianFactor::shared_ptr& factor);
76 
79 
81 
84 
90  void print(const std::string& s = "",
92 
100  double tol = 1e-9) const;
101 
103 
106 
117  HybridGaussianProductFactor removeEmpty() const;
118 
120 
121  private:
122 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
123 
124  friend class boost::serialization::access;
125  template <class Archive>
126  void serialize(Archive& ar, const unsigned int /*version*/) {
127  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
128  }
129 #endif
130 };
131 
132 // Testable traits
133 template <>
135  : public Testable<HybridGaussianProductFactor> {};
136 
145 std::istream& operator>>(std::istream& is, GaussianFactorGraphValuePair& pair);
146 
147 } // namespace gtsam
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::operator>>
istream & operator>>(istream &inputStream, Matrix &destinationMatrix)
Definition: Matrix.cpp:173
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::GaussianFactorGraphValuePair
std::pair< GaussianFactorGraph, double > GaussianFactorGraphValuePair
Definition: HybridGaussianProductFactor.h:31
tree
Definition: testExpression.cpp:212
gtsam::HybridGaussianProductFactor::HybridGaussianProductFactor
HybridGaussianProductFactor(const std::shared_ptr< FACTOR > &factor)
Construct from a single factor.
Definition: HybridGaussianProductFactor.h:51
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::HybridGaussianProductFactor
Alias for DecisionTree of GaussianFactorGraphs and their scalar sums.
Definition: HybridGaussianProductFactor.h:34
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
Key.h
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
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.
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::equals
Definition: Testable.h:112
gtsam::operator+
HybridGaussianProductFactor operator+(const HybridGaussianProductFactor &a, const HybridGaussianProductFactor &b)
Definition: HybridGaussianProductFactor.cpp:39
gtsam::DecisionTree
a decision tree is a function from assignments to values.
Definition: DecisionTree.h:62
move
detail::enable_if_t<!detail::move_never< T >::value, T > move(object &&obj)
Definition: cast.h:1243
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
std
Definition: BFloat16.h:88
gtsam::HybridGaussianFactor
Implementation of a discrete-conditioned hybrid factor. Implements a joint discrete-continuous factor...
Definition: HybridGaussianFactor.h:60
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::HybridGaussianProductFactor::HybridGaussianProductFactor
HybridGaussianProductFactor(Base &&tree)
Construct from DecisionTree.
Definition: HybridGaussianProductFactor.h:58
Base
Definition: test_virtual_functions.cpp:156
Eigen::bfloat16_impl::operator+=
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 & operator+=(bfloat16 &a, const bfloat16 &b)
Definition: BFloat16.h:184
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sat Oct 19 2024 03:01:44