DecisionTreeFactor.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 
22 #include <gtsam/base/FastSet.h>
23 
24 #include <boost/make_shared.hpp>
25 
26 using namespace std;
27 
28 namespace gtsam {
29 
30  /* ******************************************************************************** */
31  DecisionTreeFactor::DecisionTreeFactor() {
32  }
33 
34  /* ******************************************************************************** */
35  DecisionTreeFactor::DecisionTreeFactor(const DiscreteKeys& keys,
36  const ADT& potentials) :
37  DiscreteFactor(keys.indices()), Potentials(keys, potentials) {
38  }
39 
40  /* *************************************************************************/
42  DiscreteFactor(c.keys()), Potentials(c) {
43  }
44 
45  /* ************************************************************************* */
46  bool DecisionTreeFactor::equals(const DiscreteFactor& other, double tol) const {
47  if(!dynamic_cast<const DecisionTreeFactor*>(&other)) {
48  return false;
49  }
50  else {
51  const DecisionTreeFactor& f(static_cast<const DecisionTreeFactor&>(other));
52  return Potentials::equals(f, tol);
53  }
54  }
55 
56  /* ************************************************************************* */
57  void DecisionTreeFactor::print(const string& s,
58  const KeyFormatter& formatter) const {
59  cout << s;
60  Potentials::print("Potentials:",formatter);
61  }
62 
63  /* ************************************************************************* */
65  ADT::Binary op) const {
66  map<Key,size_t> cs; // new cardinalities
67  // make unique key-cardinality map
68  for(Key j: keys()) cs[j] = cardinality(j);
69  for(Key j: f.keys()) cs[j] = f.cardinality(j);
70  // Convert map into keys
72  for(const std::pair<const Key,size_t>& key: cs)
73  keys.push_back(key);
74  // apply operand
75  ADT result = ADT::apply(f, op);
76  // Make a new factor
77  return DecisionTreeFactor(keys, result);
78  }
79 
80  /* ************************************************************************* */
82  ADT::Binary op) const {
83 
84  if (nrFrontals > size()) throw invalid_argument(
85  (boost::format(
86  "DecisionTreeFactor::combine: invalid number of frontal keys %d, nr.keys=%d")
87  % nrFrontals % size()).str());
88 
89  // sum over nrFrontals keys
90  size_t i;
91  ADT result(*this);
92  for (i = 0; i < nrFrontals; i++) {
93  Key j = keys()[i];
94  result = result.combine(j, cardinality(j), op);
95  }
96 
97  // create new factor, note we start keys after nrFrontals
98  DiscreteKeys dkeys;
99  for (; i < keys().size(); i++) {
100  Key j = keys()[i];
101  dkeys.push_back(DiscreteKey(j,cardinality(j)));
102  }
103  return boost::make_shared<DecisionTreeFactor>(dkeys, result);
104  }
105 
106 
107  /* ************************************************************************* */
109  ADT::Binary op) const {
110 
111  if (frontalKeys.size() > size()) throw invalid_argument(
112  (boost::format(
113  "DecisionTreeFactor::combine: invalid number of frontal keys %d, nr.keys=%d")
114  % frontalKeys.size() % size()).str());
115 
116  // sum over nrFrontals keys
117  size_t i;
118  ADT result(*this);
119  for (i = 0; i < frontalKeys.size(); i++) {
120  Key j = frontalKeys[i];
121  result = result.combine(j, cardinality(j), op);
122  }
123 
124  // create new factor, note we collect keys that are not in frontalKeys
125  // TODO: why do we need this??? result should contain correct keys!!!
126  DiscreteKeys dkeys;
127  for (i = 0; i < keys().size(); i++) {
128  Key j = keys()[i];
129  // TODO: inefficient!
130  if (std::find(frontalKeys.begin(), frontalKeys.end(), j) != frontalKeys.end())
131  continue;
132  dkeys.push_back(DiscreteKey(j,cardinality(j)));
133  }
134  return boost::make_shared<DecisionTreeFactor>(dkeys, result);
135  }
136 
137 /* ************************************************************************* */
138 } // namespace gtsam
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
DecisionTree apply(const Unary &op) const
boost::function< double(const double &, const double &)> Binary
Definition: DecisionTree.h:42
Definition: Half.h:150
shared_ptr combine(size_t nrFrontals, ADT::Binary op) const
const KeyFormatter & formatter
DecisionTreeFactor apply(const DecisionTreeFactor &f, ADT::Binary op) const
DecisionTree combine(const L &label, size_t cardinality, const Binary &op) const
Values result
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:34
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 >)
GTSAM_EXPORT bool equals(const Potentials &other, double tol=1e-9) const
Definition: Potentials.cpp:52
size_t cardinality(Key j) const
Definition: Potentials.h:74
RealScalar s
traits
Definition: chartTesting.h:28
size_t size() const
Definition: Factor.h:135
const KeyVector & keys() const
Access the factor&#39;s involved variable keys.
Definition: Factor.h:124
boost::shared_ptr< DecisionTreeFactor > shared_ptr
GTSAM_EXPORT void print(const std::string &s="Potentials: ", const KeyFormatter &formatter=DefaultKeyFormatter) const
Definition: Potentials.cpp:57
bool equals(const DiscreteFactor &other, double tol=1e-9) const override
equality
const G double tol
Definition: Group.h:83
const KeyVector keys
void print(const std::string &s="DecisionTreeFactor:\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
A thin wrapper around std::set that uses boost&#39;s fast_pool_allocator.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:37


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:57