DiscreteFactor.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 
20 #include <gtsam/base/Vector.h>
23 
24 #include <cmath>
25 #include <sstream>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
31 /* ************************************************************************* */
32 bool DiscreteFactor::equals(const DiscreteFactor& lf, double tol) const {
33  return Base::equals(lf, tol) && cardinalities_ == lf.cardinalities_;
34 }
35 
36 /* ************************************************************************ */
37 DiscreteKeys DiscreteFactor::discreteKeys() const {
39  for (auto&& key : keys()) {
40  DiscreteKey dkey(key, cardinality(key));
41  if (std::find(result.begin(), result.end(), dkey) == result.end()) {
42  result.push_back(dkey);
43  }
44  }
45  return result;
46 }
47 
48 /* ************************************************************************* */
50  return -std::log((*this)(values));
51 }
52 
53 /* ************************************************************************* */
54 double DiscreteFactor::error(const HybridValues& c) const {
55  return this->error(c.discrete());
56 }
57 
58 /* ************************************************************************ */
59 AlgebraicDecisionTree<Key> DiscreteFactor::errorTree() const {
60  // Get all possible assignments
61  DiscreteKeys dkeys = discreteKeys();
62  // Reverse to make cartesian product output a more natural ordering.
63  DiscreteKeys rdkeys(dkeys.rbegin(), dkeys.rend());
64  const auto assignments = DiscreteValues::CartesianProduct(rdkeys);
65 
66  // Construct vector with error values
67  std::vector<double> errors;
68  for (const auto& assignment : assignments) {
69  errors.push_back(error(assignment));
70  }
71  return AlgebraicDecisionTree<Key>(dkeys, errors);
72 }
73 
74 /* ************************************************************************* */
75 std::vector<double> expNormalize(const std::vector<double>& logProbs) {
76  double maxLogProb = -std::numeric_limits<double>::infinity();
77  for (size_t i = 0; i < logProbs.size(); i++) {
78  double logProb = logProbs[i];
79  if ((logProb != std::numeric_limits<double>::infinity()) &&
80  logProb > maxLogProb) {
81  maxLogProb = logProb;
82  }
83  }
84 
85  // After computing the max = "Z" of the log probabilities L_i, we compute
86  // the log of the normalizing constant, log S, where S = sum_j exp(L_j - Z).
87  double total = 0.0;
88  for (size_t i = 0; i < logProbs.size(); i++) {
89  double probPrime = exp(logProbs[i] - maxLogProb);
90  total += probPrime;
91  }
92  double logTotal = log(total);
93 
94  // Now we compute the (normalized) probability (for each i):
95  // p_i = exp(L_i - Z - log S)
96  double checkNormalization = 0.0;
97  std::vector<double> probs;
98  for (size_t i = 0; i < logProbs.size(); i++) {
99  double prob = exp(logProbs[i] - maxLogProb - logTotal);
100  probs.push_back(prob);
101  checkNormalization += prob;
102  }
103 
104  // Numerical tolerance for floating point comparisons
105  double tol = 1e-9;
106 
107  if (!gtsam::fpEqual(checkNormalization, 1.0, tol)) {
108  std::string errMsg =
109  std::string("expNormalize failed to normalize probabilities. ") +
110  std::string("Expected normalization constant = 1.0. Got value: ") +
111  std::to_string(checkNormalization) +
112  std::string(
113  "\n This could have resulted from numerical overflow/underflow.");
114  throw std::logic_error(errMsg);
115  }
116  return probs;
117 }
118 
119 } // namespace gtsam
gtsam::HybridValues
Definition: HybridValues.h:37
Vector.h
typedef and functions to augment Eigen's VectorXd
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
gtsam::DiscreteFactor::cardinalities_
std::map< Key, size_t > cardinalities_
Map of Keys and their cardinalities.
Definition: DiscreteFactor.h:56
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::AlgebraicDecisionTree< Key >
DiscreteFactor.h
gtsam::fpEqual
bool fpEqual(double a, double b, double tol, bool check_relative_also)
Definition: Vector.cpp:42
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
gtsam::HybridValues::discrete
const DiscreteValues & discrete() const
Return the discrete values.
Definition: HybridValues.cpp:57
gtsam::expNormalize
std::vector< double > expNormalize(const std::vector< double > &logProbs)
Normalize a set of log probabilities.
Definition: DiscreteFactor.cpp:75
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::DiscreteFactor
Definition: DiscreteFactor.h:39
HybridValues.h
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:28