Skip to content

Commit

Permalink
rename error to errorTree when it returns an AlgebraicDecisionTree
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal committed Jan 5, 2024
1 parent 7d4dcf8 commit bc3b96a
Show file tree
Hide file tree
Showing 21 changed files with 33 additions and 31 deletions.
2 changes: 1 addition & 1 deletion gtsam/discrete/DecisionTreeFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace gtsam {
}

/* ************************************************************************ */
AlgebraicDecisionTree<Key> DecisionTreeFactor::error() const {
AlgebraicDecisionTree<Key> DecisionTreeFactor::errorTree() const {
// Get all possible assignments
DiscreteKeys dkeys = discreteKeys();
// Reverse to make cartesian product output a more natural ordering.
Expand Down
2 changes: 1 addition & 1 deletion gtsam/discrete/DecisionTreeFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ namespace gtsam {
double error(const HybridValues& values) const override;

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override;
AlgebraicDecisionTree<Key> errorTree() const override;

/// @}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/discrete/DiscreteFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class GTSAM_EXPORT DiscreteFactor : public Factor {
double error(const HybridValues& c) const override;

/// Compute error for each assignment and return as a tree
virtual AlgebraicDecisionTree<Key> error() const = 0;
virtual AlgebraicDecisionTree<Key> errorTree() const = 0;

/// Multiply in a DecisionTreeFactor and return the result as
/// DecisionTreeFactor
Expand Down
4 changes: 2 additions & 2 deletions gtsam/discrete/TableFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,8 @@ double TableFactor::error(const HybridValues& values) const {
}

/* ************************************************************************ */
AlgebraicDecisionTree<Key> TableFactor::error() const {
return toDecisionTreeFactor().error();
AlgebraicDecisionTree<Key> TableFactor::errorTree() const {
return toDecisionTreeFactor().errorTree();
}

/* ************************************************************************ */
Expand Down
2 changes: 1 addition & 1 deletion gtsam/discrete/TableFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ class GTSAM_EXPORT TableFactor : public DiscreteFactor {
double error(const HybridValues& values) const override;

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override;
AlgebraicDecisionTree<Key> errorTree() const override;

/// @}
};
Expand Down
2 changes: 1 addition & 1 deletion gtsam/discrete/tests/testDecisionTreeFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ TEST(DecisionTreeFactor, Error) {
// Create factors
DecisionTreeFactor f(X & Y & Z, "2 5 3 6 4 7 25 55 35 65 45 75");

auto errors = f.error();
auto errors = f.errorTree();
// regression
AlgebraicDecisionTree<Key> expected(
{X, Y, Z},
Expand Down
6 changes: 3 additions & 3 deletions gtsam/hybrid/GaussianMixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,14 +313,14 @@ AlgebraicDecisionTree<Key> GaussianMixture::logProbability(
}

/* *******************************************************************************/
AlgebraicDecisionTree<Key> GaussianMixture::error(
AlgebraicDecisionTree<Key> GaussianMixture::errorTree(
const VectorValues &continuousValues) const {
auto errorFunc = [&](const GaussianConditional::shared_ptr &conditional) {
return conditional->error(continuousValues) + //
logConstant_ - conditional->logNormalizationConstant();
};
DecisionTree<Key, double> errorTree(conditionals_, errorFunc);
return errorTree;
DecisionTree<Key, double> error_tree(conditionals_, errorFunc);
return error_tree;
}

/* *******************************************************************************/
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/GaussianMixture.h
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,7 @@ class GTSAM_EXPORT GaussianMixture
* @return AlgebraicDecisionTree<Key> A decision tree on the discrete keys
* only, with the leaf values as the error for each assignment.
*/
AlgebraicDecisionTree<Key> error(const VectorValues &continuousValues) const;
AlgebraicDecisionTree<Key> errorTree(const VectorValues &continuousValues) const;

/**
* @brief Compute the logProbability of this Gaussian Mixture.
Expand Down
6 changes: 3 additions & 3 deletions gtsam/hybrid/GaussianMixtureFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,14 +102,14 @@ GaussianFactorGraphTree GaussianMixtureFactor::asGaussianFactorGraphTree()
}

/* *******************************************************************************/
AlgebraicDecisionTree<Key> GaussianMixtureFactor::error(
AlgebraicDecisionTree<Key> GaussianMixtureFactor::errorTree(
const VectorValues &continuousValues) const {
// functor to convert from sharedFactor to double error value.
auto errorFunc = [&continuousValues](const sharedFactor &gf) {
return gf->error(continuousValues);
};
DecisionTree<Key, double> errorTree(factors_, errorFunc);
return errorTree;
DecisionTree<Key, double> error_tree(factors_, errorFunc);
return error_tree;
}

/* *******************************************************************************/
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/GaussianMixtureFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
* @return AlgebraicDecisionTree<Key> A decision tree with the same keys
* as the factors involved, and leaf values as the error.
*/
AlgebraicDecisionTree<Key> error(const VectorValues &continuousValues) const;
AlgebraicDecisionTree<Key> errorTree(const VectorValues &continuousValues) const;

/**
* @brief Compute the log-likelihood, including the log-normalizing constant.
Expand Down
6 changes: 3 additions & 3 deletions gtsam/hybrid/HybridGaussianFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ EliminateHybrid(const HybridGaussianFactorGraph &factors,
}

/* ************************************************************************ */
AlgebraicDecisionTree<Key> HybridGaussianFactorGraph::error(
AlgebraicDecisionTree<Key> HybridGaussianFactorGraph::errorTree(
const VectorValues &continuousValues) const {
AlgebraicDecisionTree<Key> error_tree(0.0);

Expand All @@ -431,7 +431,7 @@ AlgebraicDecisionTree<Key> HybridGaussianFactorGraph::error(

if (auto gaussianMixture = dynamic_pointer_cast<GaussianMixtureFactor>(f)) {
// Compute factor error and add it.
error_tree = error_tree + gaussianMixture->error(continuousValues);
error_tree = error_tree + gaussianMixture->errorTree(continuousValues);
} else if (auto gaussian = dynamic_pointer_cast<GaussianFactor>(f)) {
// If continuous only, get the (double) error
// and add it to the error_tree
Expand Down Expand Up @@ -460,7 +460,7 @@ double HybridGaussianFactorGraph::probPrime(const HybridValues &values) const {
/* ************************************************************************ */
AlgebraicDecisionTree<Key> HybridGaussianFactorGraph::probPrime(
const VectorValues &continuousValues) const {
AlgebraicDecisionTree<Key> error_tree = this->error(continuousValues);
AlgebraicDecisionTree<Key> error_tree = this->errorTree(continuousValues);
AlgebraicDecisionTree<Key> prob_tree = error_tree.apply([](double error) {
// NOTE: The 0.5 term is handled by each factor
return exp(-error);
Expand Down
3 changes: 2 additions & 1 deletion gtsam/hybrid/HybridGaussianFactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,8 @@ class GTSAM_EXPORT HybridGaussianFactorGraph
* @param continuousValues Continuous values at which to compute the error.
* @return AlgebraicDecisionTree<Key>
*/
AlgebraicDecisionTree<Key> error(const VectorValues& continuousValues) const;
AlgebraicDecisionTree<Key> errorTree(
const VectorValues& continuousValues) const;

/**
* @brief Compute unnormalized probability \f$ P(X | M, Z) \f$
Expand Down
6 changes: 3 additions & 3 deletions gtsam/hybrid/MixtureFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -131,13 +131,13 @@ class MixtureFactor : public HybridFactor {
* @return AlgebraicDecisionTree<Key> A decision tree with the same keys
* as the factor, and leaf values as the error.
*/
AlgebraicDecisionTree<Key> error(const Values& continuousValues) const {
AlgebraicDecisionTree<Key> errorTree(const Values& continuousValues) const {
// functor to convert from sharedFactor to double error value.
auto errorFunc = [continuousValues](const sharedFactor& factor) {
return factor->error(continuousValues);
};
DecisionTree<Key, double> errorTree(factors_, errorFunc);
return errorTree;
DecisionTree<Key, double> result(factors_, errorFunc);
return result;
}

/**
Expand Down
4 changes: 2 additions & 2 deletions gtsam/hybrid/tests/testGaussianMixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ TEST(GaussianMixture, LogProbability) {
/// Check error.
TEST(GaussianMixture, Error) {
using namespace equal_constants;
auto actual = mixture.error(vv);
auto actual = mixture.errorTree(vv);

// Check result.
std::vector<DiscreteKey> discrete_keys = {mode};
Expand Down Expand Up @@ -134,7 +134,7 @@ TEST(GaussianMixture, Likelihood) {
std::vector<double> leaves = {conditionals[0]->likelihood(vv)->error(vv),
conditionals[1]->likelihood(vv)->error(vv)};
AlgebraicDecisionTree<Key> expected(discrete_keys, leaves);
EXPECT(assert_equal(expected, likelihood->error(vv), 1e-6));
EXPECT(assert_equal(expected, likelihood->errorTree(vv), 1e-6));

// Check that the ratio of probPrime to evaluate is the same for all modes.
std::vector<double> ratio(2);
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/tests/testGaussianMixtureFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ TEST(GaussianMixtureFactor, Error) {
continuousValues.insert(X(2), Vector2(1, 1));

// error should return a tree of errors, with nodes for each discrete value.
AlgebraicDecisionTree<Key> error_tree = mixtureFactor.error(continuousValues);
AlgebraicDecisionTree<Key> error_tree = mixtureFactor.errorTree(continuousValues);

std::vector<DiscreteKey> discrete_keys = {m1};
// Error values for regression test
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/tests/testHybridGaussianFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -580,7 +580,7 @@ TEST(HybridGaussianFactorGraph, ErrorAndProbPrimeTree) {
HybridBayesNet::shared_ptr hybridBayesNet = graph.eliminateSequential();

HybridValues delta = hybridBayesNet->optimize();
auto error_tree = graph.error(delta.continuous());
auto error_tree = graph.errorTree(delta.continuous());

std::vector<DiscreteKey> discrete_keys = {{M(0), 2}, {M(1), 2}};
std::vector<double> leaves = {0.9998558, 0.4902432, 0.5193694, 0.0097568};
Expand Down
3 changes: 2 additions & 1 deletion gtsam/hybrid/tests/testMixtureFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,8 @@ TEST(MixtureFactor, Error) {
continuousValues.insert<double>(X(1), 0);
continuousValues.insert<double>(X(2), 1);

AlgebraicDecisionTree<Key> error_tree = mixtureFactor.error(continuousValues);
AlgebraicDecisionTree<Key> error_tree =
mixtureFactor.errorTree(continuousValues);

DiscreteKey m1(1, 2);
std::vector<DiscreteKey> discrete_keys = {m1};
Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/discrete/AllDiff.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class GTSAM_UNSTABLE_EXPORT AllDiff : public Constraint {
DecisionTreeFactor operator*(const DecisionTreeFactor& f) const override;

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override {
AlgebraicDecisionTree<Key> errorTree() const override {
throw std::runtime_error("AllDiff::error not implemented");
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/discrete/BinaryAllDiff.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class BinaryAllDiff : public Constraint {
}

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override {
AlgebraicDecisionTree<Key> errorTree() const override {
throw std::runtime_error("BinaryAllDiff::error not implemented");
}
};
Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/discrete/Domain.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class GTSAM_UNSTABLE_EXPORT Domain : public Constraint {
}

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override {
AlgebraicDecisionTree<Key> errorTree() const override {
throw std::runtime_error("Domain::error not implemented");
}

Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/discrete/SingleValue.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class GTSAM_UNSTABLE_EXPORT SingleValue : public Constraint {
}

/// Compute error for each assignment and return as a tree
AlgebraicDecisionTree<Key> error() const override {
AlgebraicDecisionTree<Key> errorTree() const override {
throw std::runtime_error("SingleValue::error not implemented");
}

Expand Down

0 comments on commit bc3b96a

Please sign in to comment.