Merge pull request #1220 from borglab/hybrid/tests
commit
784f16fe75
|
@ -39,10 +39,10 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
using boost::assign::operator+=;
|
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
using boost::assign::operator+=;
|
||||||
|
|
||||||
/****************************************************************************/
|
/****************************************************************************/
|
||||||
// Node
|
// Node
|
||||||
/****************************************************************************/
|
/****************************************************************************/
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/base/utilities.h>
|
#include <gtsam/base/utilities.h>
|
||||||
#include <gtsam/discrete/DecisionTree-inl.h>
|
#include <gtsam/discrete/DiscreteValues.h>
|
||||||
#include <gtsam/hybrid/GaussianMixture.h>
|
#include <gtsam/hybrid/GaussianMixture.h>
|
||||||
#include <gtsam/inference/Conditional-inst.h>
|
#include <gtsam/inference/Conditional-inst.h>
|
||||||
#include <gtsam/linear/GaussianFactorGraph.h>
|
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||||
|
@ -36,8 +36,7 @@ GaussianMixture::GaussianMixture(
|
||||||
conditionals_(conditionals) {}
|
conditionals_(conditionals) {}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
const GaussianMixture::Conditionals &
|
const GaussianMixture::Conditionals &GaussianMixture::conditionals() {
|
||||||
GaussianMixture::conditionals() {
|
|
||||||
return conditionals_;
|
return conditionals_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -48,8 +47,8 @@ GaussianMixture GaussianMixture::FromConditionals(
|
||||||
const std::vector<GaussianConditional::shared_ptr> &conditionalsList) {
|
const std::vector<GaussianConditional::shared_ptr> &conditionalsList) {
|
||||||
Conditionals dt(discreteParents, conditionalsList);
|
Conditionals dt(discreteParents, conditionalsList);
|
||||||
|
|
||||||
return GaussianMixture(continuousFrontals, continuousParents,
|
return GaussianMixture(continuousFrontals, continuousParents, discreteParents,
|
||||||
discreteParents, dt);
|
dt);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
|
@ -66,8 +65,7 @@ GaussianMixture::Sum GaussianMixture::add(
|
||||||
}
|
}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
GaussianMixture::Sum
|
GaussianMixture::Sum GaussianMixture::asGaussianFactorGraphTree() const {
|
||||||
GaussianMixture::asGaussianFactorGraphTree() const {
|
|
||||||
auto lambda = [](const GaussianFactor::shared_ptr &factor) {
|
auto lambda = [](const GaussianFactor::shared_ptr &factor) {
|
||||||
GaussianFactorGraph result;
|
GaussianFactorGraph result;
|
||||||
result.push_back(factor);
|
result.push_back(factor);
|
||||||
|
@ -77,21 +75,42 @@ GaussianMixture::asGaussianFactorGraphTree() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
bool GaussianMixture::equals(const HybridFactor &lf,
|
size_t GaussianMixture::nrComponents() const {
|
||||||
double tol) const {
|
size_t total = 0;
|
||||||
|
conditionals_.visit([&total](const GaussianFactor::shared_ptr &node) {
|
||||||
|
if (node) total += 1;
|
||||||
|
});
|
||||||
|
return total;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* *******************************************************************************/
|
||||||
|
GaussianConditional::shared_ptr GaussianMixture::operator()(
|
||||||
|
const DiscreteValues &discreteVals) const {
|
||||||
|
auto &ptr = conditionals_(discreteVals);
|
||||||
|
if (!ptr) return nullptr;
|
||||||
|
auto conditional = boost::dynamic_pointer_cast<GaussianConditional>(ptr);
|
||||||
|
if (conditional)
|
||||||
|
return conditional;
|
||||||
|
else
|
||||||
|
throw std::logic_error(
|
||||||
|
"A GaussianMixture unexpectedly contained a non-conditional");
|
||||||
|
}
|
||||||
|
|
||||||
|
/* *******************************************************************************/
|
||||||
|
bool GaussianMixture::equals(const HybridFactor &lf, double tol) const {
|
||||||
const This *e = dynamic_cast<const This *>(&lf);
|
const This *e = dynamic_cast<const This *>(&lf);
|
||||||
return e != nullptr && BaseFactor::equals(*e, tol);
|
return e != nullptr && BaseFactor::equals(*e, tol);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
void GaussianMixture::print(const std::string &s,
|
void GaussianMixture::print(const std::string &s,
|
||||||
const KeyFormatter &formatter) const {
|
const KeyFormatter &formatter) const {
|
||||||
std::cout << s;
|
std::cout << s;
|
||||||
if (isContinuous()) std::cout << "Continuous ";
|
if (isContinuous()) std::cout << "Continuous ";
|
||||||
if (isDiscrete()) std::cout << "Discrete ";
|
if (isDiscrete()) std::cout << "Discrete ";
|
||||||
if (isHybrid()) std::cout << "Hybrid ";
|
if (isHybrid()) std::cout << "Hybrid ";
|
||||||
BaseConditional::print("", formatter);
|
BaseConditional::print("", formatter);
|
||||||
std::cout << "\nDiscrete Keys = ";
|
std::cout << " Discrete Keys = ";
|
||||||
for (auto &dk : discreteKeys()) {
|
for (auto &dk : discreteKeys()) {
|
||||||
std::cout << "(" << formatter(dk.first) << ", " << dk.second << "), ";
|
std::cout << "(" << formatter(dk.first) << ", " << dk.second << "), ";
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,7 +19,9 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <gtsam/discrete/DecisionTree-inl.h>
|
||||||
#include <gtsam/discrete/DecisionTree.h>
|
#include <gtsam/discrete/DecisionTree.h>
|
||||||
|
#include <gtsam/discrete/DiscreteKey.h>
|
||||||
#include <gtsam/hybrid/HybridFactor.h>
|
#include <gtsam/hybrid/HybridFactor.h>
|
||||||
#include <gtsam/inference/Conditional.h>
|
#include <gtsam/inference/Conditional.h>
|
||||||
#include <gtsam/linear/GaussianConditional.h>
|
#include <gtsam/linear/GaussianConditional.h>
|
||||||
|
@ -99,6 +101,16 @@ class GTSAM_EXPORT GaussianMixture
|
||||||
const DiscreteKeys &discreteParents,
|
const DiscreteKeys &discreteParents,
|
||||||
const std::vector<GaussianConditional::shared_ptr> &conditionals);
|
const std::vector<GaussianConditional::shared_ptr> &conditionals);
|
||||||
|
|
||||||
|
/// @}
|
||||||
|
/// @name Standard API
|
||||||
|
/// @{
|
||||||
|
|
||||||
|
GaussianConditional::shared_ptr operator()(
|
||||||
|
const DiscreteValues &discreteVals) const;
|
||||||
|
|
||||||
|
/// Returns the total number of continuous components
|
||||||
|
size_t nrComponents() const;
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
|
@ -51,16 +51,19 @@ GaussianMixtureFactor GaussianMixtureFactor::FromFactors(
|
||||||
void GaussianMixtureFactor::print(const std::string &s,
|
void GaussianMixtureFactor::print(const std::string &s,
|
||||||
const KeyFormatter &formatter) const {
|
const KeyFormatter &formatter) const {
|
||||||
HybridFactor::print(s, formatter);
|
HybridFactor::print(s, formatter);
|
||||||
|
std::cout << "]{\n";
|
||||||
factors_.print(
|
factors_.print(
|
||||||
"mixture = ", [&](Key k) { return formatter(k); },
|
"", [&](Key k) { return formatter(k); },
|
||||||
[&](const GaussianFactor::shared_ptr &gf) -> std::string {
|
[&](const GaussianFactor::shared_ptr &gf) -> std::string {
|
||||||
RedirectCout rd;
|
RedirectCout rd;
|
||||||
if (!gf->empty())
|
std::cout << ":\n";
|
||||||
|
if (gf)
|
||||||
gf->print("", formatter);
|
gf->print("", formatter);
|
||||||
else
|
else
|
||||||
return {"nullptr"};
|
return {"nullptr"};
|
||||||
return rd.str();
|
return rd.str();
|
||||||
});
|
});
|
||||||
|
std::cout << "}" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* *******************************************************************************/
|
/* *******************************************************************************/
|
||||||
|
|
|
@ -84,6 +84,19 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
|
||||||
const DiscreteKeys &discreteKeys,
|
const DiscreteKeys &discreteKeys,
|
||||||
const Factors &factors);
|
const Factors &factors);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Construct a new GaussianMixtureFactor object using a vector of
|
||||||
|
* GaussianFactor shared pointers.
|
||||||
|
*
|
||||||
|
* @param keys Vector of keys for continuous factors.
|
||||||
|
* @param discreteKeys Vector of discrete keys.
|
||||||
|
* @param factors Vector of gaussian factor shared pointers.
|
||||||
|
*/
|
||||||
|
GaussianMixtureFactor(const KeyVector &keys, const DiscreteKeys &discreteKeys,
|
||||||
|
const std::vector<GaussianFactor::shared_ptr> &factors)
|
||||||
|
: GaussianMixtureFactor(keys, discreteKeys,
|
||||||
|
Factors(discreteKeys, factors)) {}
|
||||||
|
|
||||||
static This FromFactors(
|
static This FromFactors(
|
||||||
const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys,
|
const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys,
|
||||||
const std::vector<GaussianFactor::shared_ptr> &factors);
|
const std::vector<GaussianFactor::shared_ptr> &factors);
|
||||||
|
@ -111,6 +124,12 @@ class GTSAM_EXPORT GaussianMixtureFactor : public HybridFactor {
|
||||||
* @return Sum
|
* @return Sum
|
||||||
*/
|
*/
|
||||||
Sum add(const Sum &sum) const;
|
Sum add(const Sum &sum) const;
|
||||||
|
|
||||||
|
/// Add MixtureFactor to a Sum, syntactic sugar.
|
||||||
|
friend Sum &operator+=(Sum &sum, const GaussianMixtureFactor &factor) {
|
||||||
|
sum = factor.add(sum);
|
||||||
|
return sum;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
// traits
|
// traits
|
||||||
|
|
|
@ -47,7 +47,7 @@ bool HybridDiscreteFactor::equals(const HybridFactor &lf, double tol) const {
|
||||||
void HybridDiscreteFactor::print(const std::string &s,
|
void HybridDiscreteFactor::print(const std::string &s,
|
||||||
const KeyFormatter &formatter) const {
|
const KeyFormatter &formatter) const {
|
||||||
HybridFactor::print(s, formatter);
|
HybridFactor::print(s, formatter);
|
||||||
inner_->print("inner: ", formatter);
|
inner_->print("\n", formatter);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -50,7 +50,10 @@ DiscreteKeys CollectDiscreteKeys(const DiscreteKeys &key1,
|
||||||
|
|
||||||
/* ************************************************************************ */
|
/* ************************************************************************ */
|
||||||
HybridFactor::HybridFactor(const KeyVector &keys)
|
HybridFactor::HybridFactor(const KeyVector &keys)
|
||||||
: Base(keys), isContinuous_(true), nrContinuous_(keys.size()) {}
|
: Base(keys),
|
||||||
|
isContinuous_(true),
|
||||||
|
nrContinuous_(keys.size()),
|
||||||
|
continuousKeys_(keys) {}
|
||||||
|
|
||||||
/* ************************************************************************ */
|
/* ************************************************************************ */
|
||||||
HybridFactor::HybridFactor(const KeyVector &continuousKeys,
|
HybridFactor::HybridFactor(const KeyVector &continuousKeys,
|
||||||
|
@ -60,13 +63,15 @@ HybridFactor::HybridFactor(const KeyVector &continuousKeys,
|
||||||
isContinuous_((continuousKeys.size() != 0) && (discreteKeys.size() == 0)),
|
isContinuous_((continuousKeys.size() != 0) && (discreteKeys.size() == 0)),
|
||||||
isHybrid_((continuousKeys.size() != 0) && (discreteKeys.size() != 0)),
|
isHybrid_((continuousKeys.size() != 0) && (discreteKeys.size() != 0)),
|
||||||
nrContinuous_(continuousKeys.size()),
|
nrContinuous_(continuousKeys.size()),
|
||||||
discreteKeys_(discreteKeys) {}
|
discreteKeys_(discreteKeys),
|
||||||
|
continuousKeys_(continuousKeys) {}
|
||||||
|
|
||||||
/* ************************************************************************ */
|
/* ************************************************************************ */
|
||||||
HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys)
|
HybridFactor::HybridFactor(const DiscreteKeys &discreteKeys)
|
||||||
: Base(CollectKeys({}, discreteKeys)),
|
: Base(CollectKeys({}, discreteKeys)),
|
||||||
isDiscrete_(true),
|
isDiscrete_(true),
|
||||||
discreteKeys_(discreteKeys) {}
|
discreteKeys_(discreteKeys),
|
||||||
|
continuousKeys_({}) {}
|
||||||
|
|
||||||
/* ************************************************************************ */
|
/* ************************************************************************ */
|
||||||
bool HybridFactor::equals(const HybridFactor &lf, double tol) const {
|
bool HybridFactor::equals(const HybridFactor &lf, double tol) const {
|
||||||
|
@ -83,7 +88,17 @@ void HybridFactor::print(const std::string &s,
|
||||||
if (isContinuous_) std::cout << "Continuous ";
|
if (isContinuous_) std::cout << "Continuous ";
|
||||||
if (isDiscrete_) std::cout << "Discrete ";
|
if (isDiscrete_) std::cout << "Discrete ";
|
||||||
if (isHybrid_) std::cout << "Hybrid ";
|
if (isHybrid_) std::cout << "Hybrid ";
|
||||||
this->printKeys("", formatter);
|
for (size_t c=0; c<continuousKeys_.size(); c++) {
|
||||||
|
std::cout << formatter(continuousKeys_.at(c));
|
||||||
|
if (c < continuousKeys_.size() - 1) {
|
||||||
|
std::cout << " ";
|
||||||
|
} else {
|
||||||
|
std::cout << "; ";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
for(auto && discreteKey: discreteKeys_) {
|
||||||
|
std::cout << formatter(discreteKey.first) << " ";
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -52,6 +52,9 @@ class GTSAM_EXPORT HybridFactor : public Factor {
|
||||||
protected:
|
protected:
|
||||||
DiscreteKeys discreteKeys_;
|
DiscreteKeys discreteKeys_;
|
||||||
|
|
||||||
|
/// Record continuous keys for book-keeping
|
||||||
|
KeyVector continuousKeys_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
// typedefs needed to play nice with gtsam
|
// typedefs needed to play nice with gtsam
|
||||||
typedef HybridFactor This; ///< This class
|
typedef HybridFactor This; ///< This class
|
||||||
|
|
|
@ -41,7 +41,7 @@ bool HybridGaussianFactor::equals(const HybridFactor &other, double tol) const {
|
||||||
void HybridGaussianFactor::print(const std::string &s,
|
void HybridGaussianFactor::print(const std::string &s,
|
||||||
const KeyFormatter &formatter) const {
|
const KeyFormatter &formatter) const {
|
||||||
HybridFactor::print(s, formatter);
|
HybridFactor::print(s, formatter);
|
||||||
inner_->print("inner: ", formatter);
|
inner_->print("\n", formatter);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -0,0 +1,95 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
|
* Atlanta, Georgia 30332-0415
|
||||||
|
* All Rights Reserved
|
||||||
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
|
* See LICENSE for the license information
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file testGaussianMixture.cpp
|
||||||
|
* @brief Unit tests for GaussianMixture class
|
||||||
|
* @author Varun Agrawal
|
||||||
|
* @author Fan Jiang
|
||||||
|
* @author Frank Dellaert
|
||||||
|
* @date December 2021
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <gtsam/discrete/DiscreteValues.h>
|
||||||
|
#include <gtsam/hybrid/GaussianMixture.h>
|
||||||
|
#include <gtsam/inference/Symbol.h>
|
||||||
|
#include <gtsam/linear/GaussianConditional.h>
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
// Include for test suite
|
||||||
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace gtsam;
|
||||||
|
using noiseModel::Isotropic;
|
||||||
|
using symbol_shorthand::M;
|
||||||
|
using symbol_shorthand::X;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
/* Check construction of GaussianMixture P(x1 | x2, m1) as well as accessing a
|
||||||
|
* specific mode i.e. P(x1 | x2, m1=1).
|
||||||
|
*/
|
||||||
|
TEST(GaussianMixture, Equals) {
|
||||||
|
// create a conditional gaussian node
|
||||||
|
Matrix S1(2, 2);
|
||||||
|
S1(0, 0) = 1;
|
||||||
|
S1(1, 0) = 2;
|
||||||
|
S1(0, 1) = 3;
|
||||||
|
S1(1, 1) = 4;
|
||||||
|
|
||||||
|
Matrix S2(2, 2);
|
||||||
|
S2(0, 0) = 6;
|
||||||
|
S2(1, 0) = 0.2;
|
||||||
|
S2(0, 1) = 8;
|
||||||
|
S2(1, 1) = 0.4;
|
||||||
|
|
||||||
|
Matrix R1(2, 2);
|
||||||
|
R1(0, 0) = 0.1;
|
||||||
|
R1(1, 0) = 0.3;
|
||||||
|
R1(0, 1) = 0.0;
|
||||||
|
R1(1, 1) = 0.34;
|
||||||
|
|
||||||
|
Matrix R2(2, 2);
|
||||||
|
R2(0, 0) = 0.1;
|
||||||
|
R2(1, 0) = 0.3;
|
||||||
|
R2(0, 1) = 0.0;
|
||||||
|
R2(1, 1) = 0.34;
|
||||||
|
|
||||||
|
SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector2(1.0, 0.34));
|
||||||
|
|
||||||
|
Vector2 d1(0.2, 0.5), d2(0.5, 0.2);
|
||||||
|
|
||||||
|
auto conditional0 = boost::make_shared<GaussianConditional>(X(1), d1, R1,
|
||||||
|
X(2), S1, model),
|
||||||
|
conditional1 = boost::make_shared<GaussianConditional>(X(1), d2, R2,
|
||||||
|
X(2), S2, model);
|
||||||
|
|
||||||
|
// Create decision tree
|
||||||
|
DiscreteKey m1(1, 2);
|
||||||
|
GaussianMixture::Conditionals conditionals(
|
||||||
|
{m1},
|
||||||
|
vector<GaussianConditional::shared_ptr>{conditional0, conditional1});
|
||||||
|
GaussianMixture mixtureFactor({X(1)}, {X(2)}, {m1}, conditionals);
|
||||||
|
|
||||||
|
// Let's check that this worked:
|
||||||
|
DiscreteValues mode;
|
||||||
|
mode[m1.first] = 1;
|
||||||
|
auto actual = mixtureFactor(mode);
|
||||||
|
EXPECT(actual == conditional1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
int main() {
|
||||||
|
TestResult tr;
|
||||||
|
return TestRegistry::runAllTests(tr);
|
||||||
|
}
|
||||||
|
/* ************************************************************************* */
|
|
@ -0,0 +1,159 @@
|
||||||
|
/* ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||||
|
* Atlanta, Georgia 30332-0415
|
||||||
|
* All Rights Reserved
|
||||||
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||||
|
|
||||||
|
* See LICENSE for the license information
|
||||||
|
|
||||||
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file GaussianMixtureFactor.cpp
|
||||||
|
* @brief Unit tests for GaussianMixtureFactor
|
||||||
|
* @author Varun Agrawal
|
||||||
|
* @author Fan Jiang
|
||||||
|
* @author Frank Dellaert
|
||||||
|
* @date December 2021
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <gtsam/base/TestableAssertions.h>
|
||||||
|
#include <gtsam/discrete/DiscreteValues.h>
|
||||||
|
#include <gtsam/hybrid/GaussianMixture.h>
|
||||||
|
#include <gtsam/hybrid/GaussianMixtureFactor.h>
|
||||||
|
#include <gtsam/inference/Symbol.h>
|
||||||
|
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||||
|
|
||||||
|
// Include for test suite
|
||||||
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace gtsam;
|
||||||
|
using noiseModel::Isotropic;
|
||||||
|
using symbol_shorthand::M;
|
||||||
|
using symbol_shorthand::X;
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// Check iterators of empty mixture.
|
||||||
|
TEST(GaussianMixtureFactor, Constructor) {
|
||||||
|
GaussianMixtureFactor factor;
|
||||||
|
GaussianMixtureFactor::const_iterator const_it = factor.begin();
|
||||||
|
CHECK(const_it == factor.end());
|
||||||
|
GaussianMixtureFactor::iterator it = factor.begin();
|
||||||
|
CHECK(it == factor.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
// "Add" two mixture factors together.
|
||||||
|
TEST(GaussianMixtureFactor, Sum) {
|
||||||
|
DiscreteKey m1(1, 2), m2(2, 3);
|
||||||
|
|
||||||
|
auto A1 = Matrix::Zero(2, 1);
|
||||||
|
auto A2 = Matrix::Zero(2, 2);
|
||||||
|
auto A3 = Matrix::Zero(2, 3);
|
||||||
|
auto b = Matrix::Zero(2, 1);
|
||||||
|
Vector2 sigmas;
|
||||||
|
sigmas << 1, 2;
|
||||||
|
auto model = noiseModel::Diagonal::Sigmas(sigmas, true);
|
||||||
|
|
||||||
|
auto f10 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
|
||||||
|
auto f11 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
|
||||||
|
auto f20 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
|
||||||
|
auto f21 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
|
||||||
|
auto f22 = boost::make_shared<JacobianFactor>(X(1), A1, X(3), A3, b);
|
||||||
|
std::vector<GaussianFactor::shared_ptr> factorsA{f10, f11};
|
||||||
|
std::vector<GaussianFactor::shared_ptr> factorsB{f20, f21, f22};
|
||||||
|
|
||||||
|
// TODO(Frank): why specify keys at all? And: keys in factor should be *all*
|
||||||
|
// keys, deviating from Kevin's scheme. Should we index DT on DiscreteKey?
|
||||||
|
// Design review!
|
||||||
|
GaussianMixtureFactor mixtureFactorA({X(1), X(2)}, {m1}, factorsA);
|
||||||
|
GaussianMixtureFactor mixtureFactorB({X(1), X(3)}, {m2}, factorsB);
|
||||||
|
|
||||||
|
// Check that number of keys is 3
|
||||||
|
EXPECT_LONGS_EQUAL(3, mixtureFactorA.keys().size());
|
||||||
|
|
||||||
|
// Check that number of discrete keys is 1 // TODO(Frank): should not exist?
|
||||||
|
EXPECT_LONGS_EQUAL(1, mixtureFactorA.discreteKeys().size());
|
||||||
|
|
||||||
|
// Create sum of two mixture factors: it will be a decision tree now on both
|
||||||
|
// discrete variables m1 and m2:
|
||||||
|
GaussianMixtureFactor::Sum sum;
|
||||||
|
sum += mixtureFactorA;
|
||||||
|
sum += mixtureFactorB;
|
||||||
|
|
||||||
|
// Let's check that this worked:
|
||||||
|
Assignment<Key> mode;
|
||||||
|
mode[m1.first] = 1;
|
||||||
|
mode[m2.first] = 2;
|
||||||
|
auto actual = sum(mode);
|
||||||
|
EXPECT(actual.at(0) == f11);
|
||||||
|
EXPECT(actual.at(1) == f22);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(GaussianMixtureFactor, Printing) {
|
||||||
|
DiscreteKey m1(1, 2);
|
||||||
|
auto A1 = Matrix::Zero(2, 1);
|
||||||
|
auto A2 = Matrix::Zero(2, 2);
|
||||||
|
auto b = Matrix::Zero(2, 1);
|
||||||
|
auto f10 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
|
||||||
|
auto f11 = boost::make_shared<JacobianFactor>(X(1), A1, X(2), A2, b);
|
||||||
|
std::vector<GaussianFactor::shared_ptr> factors{f10, f11};
|
||||||
|
|
||||||
|
GaussianMixtureFactor mixtureFactor({X(1), X(2)}, {m1}, factors);
|
||||||
|
|
||||||
|
std::string expected =
|
||||||
|
R"(Hybrid x1 x2; 1 ]{
|
||||||
|
Choice(1)
|
||||||
|
0 Leaf :
|
||||||
|
A[x1] = [
|
||||||
|
0;
|
||||||
|
0
|
||||||
|
]
|
||||||
|
A[x2] = [
|
||||||
|
0, 0;
|
||||||
|
0, 0
|
||||||
|
]
|
||||||
|
b = [ 0 0 ]
|
||||||
|
No noise model
|
||||||
|
|
||||||
|
1 Leaf :
|
||||||
|
A[x1] = [
|
||||||
|
0;
|
||||||
|
0
|
||||||
|
]
|
||||||
|
A[x2] = [
|
||||||
|
0, 0;
|
||||||
|
0, 0
|
||||||
|
]
|
||||||
|
b = [ 0 0 ]
|
||||||
|
No noise model
|
||||||
|
|
||||||
|
}
|
||||||
|
)";
|
||||||
|
EXPECT(assert_print_equal(expected, mixtureFactor));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_UNSAFE(GaussianMixtureFactor, GaussianMixture) {
|
||||||
|
KeyVector keys;
|
||||||
|
keys.push_back(X(0));
|
||||||
|
keys.push_back(X(1));
|
||||||
|
|
||||||
|
DiscreteKeys dKeys;
|
||||||
|
dKeys.emplace_back(M(0), 2);
|
||||||
|
dKeys.emplace_back(M(1), 2);
|
||||||
|
|
||||||
|
auto gaussians = boost::make_shared<GaussianConditional>();
|
||||||
|
GaussianMixture::Conditionals conditionals(gaussians);
|
||||||
|
GaussianMixture gm({}, keys, dKeys, conditionals);
|
||||||
|
|
||||||
|
EXPECT_LONGS_EQUAL(2, gm.discreteKeys().size());
|
||||||
|
}
|
||||||
|
|
||||||
|
/* ************************************************************************* */
|
||||||
|
int main() {
|
||||||
|
TestResult tr;
|
||||||
|
return TestRegistry::runAllTests(tr);
|
||||||
|
}
|
||||||
|
/* ************************************************************************* */
|
Loading…
Reference in New Issue