DecisionTreeFactor.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 
25 
26 #include <algorithm>
27 #include <memory>
28 #include <map>
29 #include <stdexcept>
30 #include <string>
31 #include <utility>
32 #include <vector>
33 
34 namespace gtsam {
35 
36  class DiscreteConditional;
37  class HybridValues;
38 
44  class GTSAM_EXPORT DecisionTreeFactor : public DiscreteFactor,
45  public AlgebraicDecisionTree<Key> {
46  public:
47  // typedefs needed to play nice with gtsam
49  typedef DiscreteFactor Base;
50  typedef std::shared_ptr<DecisionTreeFactor> shared_ptr;
52 
55 
58 
60  DecisionTreeFactor(const DiscreteKeys& keys, const ADT& potentials);
61 
82  const std::vector<double>& table);
83 
102  DecisionTreeFactor(const DiscreteKeys& keys, const std::string& table);
103 
105  template <class SOURCE>
108 
110  DecisionTreeFactor(const DiscreteKey& key, const std::vector<double>& row)
112 
114  explicit DecisionTreeFactor(const DiscreteConditional& c);
115 
119 
121  bool equals(const DiscreteFactor& other, double tol = 1e-9) const override;
122 
123  // print
124  void print(
125  const std::string& s = "DecisionTreeFactor:\n",
126  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
127 
131 
134  double evaluate(const DiscreteValues& values) const {
135  return ADT::operator()(values);
136  }
137 
139  double operator()(const DiscreteValues& values) const override {
140  return ADT::operator()(values);
141  }
142 
144  double error(const DiscreteValues& values) const;
145 
148  return apply(f, ADT::Ring::mul);
149  }
150 
151  static double safe_div(const double& a, const double& b);
152 
155  return apply(f, safe_div);
156  }
157 
159  DecisionTreeFactor toDecisionTreeFactor() const override { return *this; }
160 
162  shared_ptr sum(size_t nrFrontals) const {
163  return combine(nrFrontals, ADT::Ring::add);
164  }
165 
167  shared_ptr sum(const Ordering& keys) const {
168  return combine(keys, ADT::Ring::add);
169  }
170 
172  shared_ptr max(size_t nrFrontals) const {
173  return combine(nrFrontals, ADT::Ring::max);
174  }
175 
177  shared_ptr max(const Ordering& keys) const {
178  return combine(keys, ADT::Ring::max);
179  }
180 
184 
189  DecisionTreeFactor apply(ADT::Unary op) const;
190 
196  DecisionTreeFactor apply(ADT::UnaryAssignment op) const;
197 
203  DecisionTreeFactor apply(const DecisionTreeFactor& f, ADT::Binary op) const;
204 
211  shared_ptr combine(size_t nrFrontals, ADT::Binary op) const;
212 
219  shared_ptr combine(const Ordering& keys, ADT::Binary op) const;
220 
222  std::vector<std::pair<DiscreteValues, double>> enumerate() const;
223 
225  std::vector<double> probabilities() const;
226 
245  DecisionTreeFactor prune(size_t maxNrAssignments) const;
246 
250 
252  void dot(std::ostream& os,
253  const KeyFormatter& keyFormatter = DefaultKeyFormatter,
254  bool showZero = true) const;
255 
257  void dot(const std::string& name,
258  const KeyFormatter& keyFormatter = DefaultKeyFormatter,
259  bool showZero = true) const;
260 
262  std::string dot(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
263  bool showZero = true) const;
264 
272  std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
273  const Names& names = {}) const override;
274 
282  std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
283  const Names& names = {}) const override;
284 
288 
293  double error(const HybridValues& values) const override;
294 
296  AlgebraicDecisionTree<Key> errorTree() const override;
297 
299 
300  private:
301 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
302 
303  friend class boost::serialization::access;
304  template <class ARCHIVE>
305  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
306  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
307  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(ADT);
308  }
309 #endif
310  };
311 
312 // traits
313 template <>
314 struct traits<DecisionTreeFactor> : public Testable<DecisionTreeFactor> {};
315 } // namespace gtsam
gtsam::markdown
string markdown(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of markdown.
Definition: DiscreteValues.cpp:130
name
Annotation for function names.
Definition: attr.h:51
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:44
gtsam::DecisionTreeFactor::toDecisionTreeFactor
DecisionTreeFactor toDecisionTreeFactor() const override
Convert into a decisiontree.
Definition: DecisionTreeFactor.h:159
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
mul
double mul(const double &a, const double &b)
Definition: testAlgebraicDecisionTree.cpp:87
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
HybridValues
os
ofstream os("timeSchurFactors.csv")
gtsam::DecisionTreeFactor::shared_ptr
std::shared_ptr< DecisionTreeFactor > shared_ptr
Definition: DecisionTreeFactor.h:50
DiscreteFactor
Discrete values for.
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::AlgebraicDecisionTree
Definition: AlgebraicDecisionTree.h:39
gtsam::DecisionTreeFactor::evaluate
double evaluate(const DiscreteValues &values) const
Definition: DecisionTreeFactor.h:134
gtsam::DecisionTreeFactor::DecisionTreeFactor
DecisionTreeFactor(const DiscreteKey &key, const std::vector< double > &row)
Single-key specialization, with vector of doubles.
Definition: DecisionTreeFactor.h:110
AlgebraicDecisionTree.h
Algebraic Decision Trees.
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::DecisionTreeFactor::Base
DiscreteFactor Base
Typedef to base class.
Definition: DecisionTreeFactor.h:49
gtsam::DecisionTreeFactor::sum
shared_ptr sum(const Ordering &keys) const
Create new factor by summing all values with the same separator values.
Definition: DecisionTreeFactor.h:167
ADT
AlgebraicDecisionTree< Key > ADT
Definition: testAlgebraicDecisionTree.cpp:35
table
ArrayXXf table(10, 4)
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
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
gtsam::DecisionTreeFactor::operator()
double operator()(const DiscreteValues &values) const override
Evaluate probability distribution, sugar.
Definition: DecisionTreeFactor.h:139
DiscreteFactor.h
add
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
gtsam::DecisionTreeFactor::This
DecisionTreeFactor This
Definition: DecisionTreeFactor.h:48
gtsam::DecisionTreeFactor::operator*
DecisionTreeFactor operator*(const DecisionTreeFactor &f) const override
multiply two factors
Definition: DecisionTreeFactor.h:147
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
gtsam::DecisionTreeFactor::operator/
DecisionTreeFactor operator/(const DecisionTreeFactor &f) const
divide by factor f (safely)
Definition: DecisionTreeFactor.h:154
gtsam::DecisionTreeFactor::sum
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
Definition: DecisionTreeFactor.h:162
gtsam::DecisionTreeFactor::max
shared_ptr max(const Ordering &keys) const
Create new factor by maximizing over all values with the same separator.
Definition: DecisionTreeFactor.h:177
DiscreteKey.h
specialized key for discrete variables
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
process_shonan_timing_results.names
dictionary names
Definition: process_shonan_timing_results.py:175
gtsam::b
const G & b
Definition: Group.h:79
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
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::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
gtsam::DecisionTreeFactor::max
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
Definition: DecisionTreeFactor.h:172
gtsam::apply
DecisionTree< L, Y > apply(const DecisionTree< L, Y > &f, const typename DecisionTree< L, Y >::Unary &op)
Apply unary operator op to DecisionTree f.
Definition: DecisionTree.h:427
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::DecisionTreeFactor::ADT
AlgebraicDecisionTree< Key > ADT
Definition: DecisionTreeFactor.h:51
gtsam::html
string html(const DiscreteValues &values, const KeyFormatter &keyFormatter, const DiscreteValues::Names &names)
Free version of html.
Definition: DiscreteValues.cpp:135
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:39
Base
Definition: test_virtual_functions.cpp:156
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::Ordering
Definition: inference/Ordering.h:33
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::DecisionTreeFactor::DecisionTreeFactor
DecisionTreeFactor(const DiscreteKey &key, SOURCE table)
Single-key specialization.
Definition: DecisionTreeFactor.h:106


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