Removed old code from current release branch
parent
2c9981a970
commit
67cb0806fe
|
|
@ -1,20 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 RefCounted.cpp
|
||||
* @brief Simple reference-counted base class
|
||||
* @author Frank Dellaert
|
||||
* @date Mar 29, 2011
|
||||
*/
|
||||
|
||||
#include <gtsam/discrete/RefCounted.h>
|
||||
|
||||
|
|
@ -1,97 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 RefCounted.h
|
||||
* @brief Simple reference-counted base class
|
||||
* @author Frank Dellaert
|
||||
* @date Mar 29, 2011
|
||||
*/
|
||||
|
||||
#include <boost/intrusive_ptr.hpp>
|
||||
|
||||
// Forward Declarations
|
||||
namespace gtsam {
|
||||
struct RefCounted;
|
||||
}
|
||||
|
||||
namespace boost {
|
||||
void intrusive_ptr_add_ref(const gtsam::RefCounted * p);
|
||||
void intrusive_ptr_release(const gtsam::RefCounted * p);
|
||||
}
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* Simple reference counted class inspired by
|
||||
* http://www.codeproject.com/KB/stl/boostsmartptr.aspx
|
||||
*/
|
||||
struct RefCounted {
|
||||
private:
|
||||
mutable long references_;
|
||||
friend void ::boost::intrusive_ptr_add_ref(const RefCounted * p);
|
||||
friend void ::boost::intrusive_ptr_release(const RefCounted * p);
|
||||
public:
|
||||
RefCounted() :
|
||||
references_(0) {
|
||||
}
|
||||
virtual ~RefCounted() {
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace gtsam
|
||||
|
||||
// Intrusive Pointer free functions
|
||||
#ifndef DEBUG_REFCOUNT
|
||||
|
||||
namespace boost {
|
||||
|
||||
// increment reference count of object *p
|
||||
inline void intrusive_ptr_add_ref(const gtsam::RefCounted * p) {
|
||||
++(p->references_);
|
||||
}
|
||||
|
||||
// decrement reference count, and delete object when reference count reaches 0
|
||||
inline void intrusive_ptr_release(const gtsam::RefCounted * p) {
|
||||
if (--(p->references_) == 0)
|
||||
delete p;
|
||||
}
|
||||
|
||||
} // namespace boost
|
||||
|
||||
#else
|
||||
|
||||
#include <iostream>
|
||||
|
||||
namespace gtsam {
|
||||
static long GlobalRefCount = 0;
|
||||
}
|
||||
|
||||
namespace boost {
|
||||
inline void intrusive_ptr_add_ref(const gtsam::RefCounted * p) {
|
||||
++(p->references_);
|
||||
gtsam::GlobalRefCount++;
|
||||
std::cout << "add_ref " << p << " " << p->references_ << //
|
||||
" " << gtsam::GlobalRefCount << std::endl;
|
||||
}
|
||||
|
||||
inline void intrusive_ptr_release(const gtsam::RefCounted * p) {
|
||||
gtsam::GlobalRefCount--;
|
||||
std::cout << "release " << p << " " << (p->references_ - 1) << //
|
||||
" " << gtsam::GlobalRefCount << std::endl;
|
||||
if (--(p->references_) == 0)
|
||||
delete p;
|
||||
}
|
||||
|
||||
} // namespace boost
|
||||
|
||||
#endif
|
||||
|
||||
|
|
@ -1,173 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* Potentials.cpp
|
||||
*
|
||||
* @date Feb 21, 2011
|
||||
* @author Duy-Nguyen Ta
|
||||
*/
|
||||
|
||||
#include <math.h>
|
||||
#include <sstream>
|
||||
#include <iostream>
|
||||
#include <algorithm>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/foreach.hpp>
|
||||
#include <gtsam/discrete/PotentialTable.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::Iterator::operator++() {
|
||||
// note size_t is unsigned and i>=0 is always true, so strange-looking loop:
|
||||
for (size_t i = size(); i--; ) {
|
||||
if (++at(i) < cardinalities_[i])
|
||||
return;
|
||||
else
|
||||
at(i) = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
size_t PotentialTable::computeTableSize(
|
||||
const std::vector<size_t>& cardinalities) {
|
||||
size_t tableSize = 1;
|
||||
BOOST_FOREACH(const size_t c, cardinalities)
|
||||
tableSize *= c;
|
||||
return tableSize;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
PotentialTable::PotentialTable(const std::vector<size_t>& cs) :
|
||||
cardinalities_(cs), table_(computeTableSize(cs)) {
|
||||
generateKeyFactors();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
PotentialTable::PotentialTable(const std::vector<size_t>& cardinalities,
|
||||
const Table& table) : cardinalities_(cardinalities),table_(table) {
|
||||
generateKeyFactors();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
PotentialTable::PotentialTable(const std::vector<size_t>& cardinalities,
|
||||
const std::string& tableString) : cardinalities_(cardinalities) {
|
||||
parse(tableString);
|
||||
generateKeyFactors();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool PotentialTable::equals(const PotentialTable& other, double tol) const {
|
||||
//TODO: compare potentials in a more general sense with arbitrary order of keys???
|
||||
if ((cardinalities_ == other.cardinalities_) && (table_.size()
|
||||
== other.table_.size()) && (keyFactors_ == other.keyFactors_)) {
|
||||
for (size_t i = 0; i < table_.size(); i++) {
|
||||
if (fabs(table_[i] - other.table_[i]) > tol) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::print(const std::string& s) const {
|
||||
cout << s << endl;
|
||||
for (size_t i = 0; i < cardinalities_.size(); i++)
|
||||
cout << boost::format("[%d,%d]") % cardinalities_[i] % keyFactors_[i] << " ";
|
||||
cout << endl;
|
||||
Iterator assignment(cardinalities_);
|
||||
for (size_t idx = 0; idx < table_.size(); ++idx, ++assignment) {
|
||||
for (size_t k = 0; k < assignment.size(); k++)
|
||||
cout << assignment[k] << "\t\t";
|
||||
cout << table_[idx] << endl;
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
const double& PotentialTable::operator()(const Assignment& var) const {
|
||||
return table_[tableIndexFromAssignment(var)];
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
const double& PotentialTable::operator[](const size_t index) const {
|
||||
return table_.at(index);
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::setPotential(const PotentialTable::Assignment& asg, const double potential) {
|
||||
size_t idx = tableIndexFromAssignment(asg);
|
||||
assert(idx<table_.size());
|
||||
table_[idx] = potential;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::setPotential(const size_t tableIndex, const double potential) {
|
||||
assert(tableIndex<table_.size());
|
||||
table_[tableIndex] = potential;
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
size_t PotentialTable::tableIndexFromAssignment(
|
||||
const PotentialTable::Assignment& values) const {
|
||||
size_t index = 0;
|
||||
for (size_t i = 0; i < keyFactors_.size(); i++) {
|
||||
index += keyFactors_[i] * values[i];
|
||||
}
|
||||
return index;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
PotentialTable::Assignment PotentialTable::assignmentFromTableIndex(
|
||||
const size_t idx) const {
|
||||
assert(idx < table_.size());
|
||||
Assignment values(cardinalities_);
|
||||
Index processedIndex = idx;
|
||||
for (size_t i = 0; i < keyFactors_.size(); i++) {
|
||||
values[i] = processedIndex / keyFactors_[i];
|
||||
processedIndex %= keyFactors_[i];
|
||||
}
|
||||
return values;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::generateKeyFactors() {
|
||||
size_t accumIndex = table_.size();
|
||||
BOOST_FOREACH(size_t card, cardinalities_) {
|
||||
accumIndex /= card;
|
||||
keyFactors_.push_back(accumIndex);
|
||||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void PotentialTable::parse(const std::string& tableString) {
|
||||
// parse doubles
|
||||
istringstream iss(tableString);
|
||||
copy(istream_iterator<double> (iss), istream_iterator<double> (),
|
||||
back_inserter(table_));
|
||||
|
||||
#ifndef NDEBUG
|
||||
size_t expectedSize = computeTableSize(cardinalities_);
|
||||
if (table_.size() != expectedSize) throw invalid_argument(
|
||||
boost::str(
|
||||
boost::format(
|
||||
"String specification \"%s\" for table only contains %d doubles instead of %d")
|
||||
% tableString % table_.size() % expectedSize));
|
||||
#endif
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
|
@ -1,106 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* Potentials.h
|
||||
*
|
||||
* @date Feb 21, 2011
|
||||
* @author Duy-Nguyen Ta
|
||||
*/
|
||||
|
||||
#ifndef POTENTIALS_H_
|
||||
#define POTENTIALS_H_
|
||||
|
||||
#include <vector>
|
||||
#include <set>
|
||||
#include <map>
|
||||
#include <string>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <gtsam/base/types.h>
|
||||
|
||||
namespace gtsam
|
||||
{
|
||||
/**
|
||||
* PotentialTable holds the real-valued potentials for Factors or Conditionals
|
||||
*/
|
||||
class PotentialTable {
|
||||
public:
|
||||
typedef std::vector<double> Table; // container type for potentials f(x1,x2,..)
|
||||
typedef std::vector<size_t> Cardinalities; // just a typedef
|
||||
typedef std::vector<size_t> Assignment; // just a typedef
|
||||
|
||||
/**
|
||||
* An assignment that can be incemented
|
||||
*/
|
||||
struct Iterator: std::vector<size_t> {
|
||||
Cardinalities cardinalities_;
|
||||
Iterator(const Cardinalities& cs):cardinalities_(cs) {
|
||||
for(size_t i=0;i<cs.size();i++) push_back(0);
|
||||
}
|
||||
void operator++();
|
||||
};
|
||||
|
||||
private:
|
||||
std::vector<size_t> cardinalities_; // cardinalities of variables
|
||||
Table table_; // Potential values of all instantiations of the variables, following the variables' order in vector Keys.
|
||||
std::vector<size_t> keyFactors_; // factors to multiply a key's assignment with, to access the potential table
|
||||
|
||||
void generateKeyFactors();
|
||||
void parse(const std::string& tableString);
|
||||
|
||||
public:
|
||||
|
||||
/** compute table size from variable cardinalities */
|
||||
static size_t computeTableSize(const std::vector<size_t>& cardinalities);
|
||||
|
||||
/** construct an empty potential */
|
||||
PotentialTable() {}
|
||||
|
||||
/** Dangerous empty n-ary potential. */
|
||||
PotentialTable(const std::vector<size_t>& cardinalities);
|
||||
|
||||
/** n-ary potential. */
|
||||
PotentialTable(const std::vector<size_t>& cardinalities,
|
||||
const Table& table);
|
||||
|
||||
/** n-ary potential. */
|
||||
PotentialTable(const std::vector<size_t>& cardinalities,
|
||||
const std::string& tableString);
|
||||
|
||||
/** return iterator to first element */
|
||||
Iterator begin() const { return Iterator(cardinalities_);}
|
||||
|
||||
/** equality */
|
||||
bool equals(const PotentialTable& other, double tol = 1e-9) const;
|
||||
|
||||
/** print */
|
||||
void print(const std::string& s = "Potential Table: ") const;
|
||||
|
||||
/** return cardinality of a variable */
|
||||
size_t cardinality(size_t var) const { return cardinalities_[var]; }
|
||||
size_t tableSize() const { return table_.size(); }
|
||||
|
||||
/** accessors to potential values in the table given the assignment */
|
||||
const double& operator()(const Assignment& var) const;
|
||||
const double& operator[](const size_t index) const;
|
||||
|
||||
void setPotential(const Assignment& asg, const double potential);
|
||||
void setPotential(const size_t tableIndex, const double potential);
|
||||
|
||||
/** convert between assignment and where it is in the table */
|
||||
size_t tableIndexFromAssignment(const Assignment& var) const;
|
||||
Assignment assignmentFromTableIndex(const size_t i) const;
|
||||
};
|
||||
|
||||
|
||||
} // namespace
|
||||
|
||||
#endif /* POTENTIALS_H_ */
|
||||
|
|
@ -1,128 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 TypedDiscreteFactor.cpp
|
||||
* @brief
|
||||
* @author Duy-Nguyen Ta
|
||||
* @date Mar 5, 2011
|
||||
*/
|
||||
|
||||
#include <gtsam_unstable/discrete/TypedDiscreteFactor.h>
|
||||
#include <gtsam/discrete/DecisionTree.h>
|
||||
#include <gtsam/inference/Factor-inl.h>
|
||||
#include <boost/make_shared.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ******************************************************************************** */
|
||||
TypedDiscreteFactor::TypedDiscreteFactor(const Indices& keys,
|
||||
const string& table) :
|
||||
Factor<Index> (keys.begin(), keys.end()), potentials_(keys, table) {
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
TypedDiscreteFactor::TypedDiscreteFactor(const Indices& keys,
|
||||
const vector<double>& table) :
|
||||
Factor<Index> (keys.begin(), keys.end()), potentials_(keys, table) {
|
||||
//#define DEBUG_FACTORS
|
||||
#ifdef DEBUG_FACTORS
|
||||
static size_t count = 0;
|
||||
string dotfile = (boost::format("Factor-%03d") % ++count).str();
|
||||
potentials_.dot(dotfile);
|
||||
if (count == 57) potentials_.print("57");
|
||||
#endif
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
double TypedDiscreteFactor::operator()(const Values& values) const {
|
||||
return potentials_(values);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TypedDiscreteFactor::print(const string&s) const {
|
||||
Factor<Index>::print(s);
|
||||
potentials_.print();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool TypedDiscreteFactor::equals(const TypedDiscreteFactor& other, double tol) const {
|
||||
return potentials_.equals(other.potentials_, tol);
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
DiscreteFactor::shared_ptr TypedDiscreteFactor::toDiscreteFactor(
|
||||
const KeyOrdering& ordering) const {
|
||||
throw std::runtime_error("broken");
|
||||
//return boost::make_shared<DiscreteFactor>(keys(), ordering, potentials_);
|
||||
}
|
||||
|
||||
#ifdef OLD
|
||||
DiscreteFactor TypedDiscreteFactor::toDiscreteFactor(
|
||||
const KeyOrdering& ordering, const ProblemType problemType) const {
|
||||
{
|
||||
static bool debug = false;
|
||||
|
||||
// instantiate vector keys and column index in order
|
||||
DiscreteFactor::ColumnIndex orderColumnIndex;
|
||||
vector<Index> keys;
|
||||
BOOST_FOREACH(const KeyOrdering::value_type& ord, ordering)
|
||||
{
|
||||
if (debug) cout << "Key: " << ord.first;
|
||||
|
||||
// find the key with ord.first in this factor
|
||||
vector<Index>::const_iterator it = std::find(keys_.begin(),
|
||||
keys_.end(), ord.first);
|
||||
|
||||
// if found
|
||||
if (it != keys_.end()) {
|
||||
if (debug) cout << "it found: " << (*it) << ", index: "
|
||||
<< ord.second << endl;
|
||||
|
||||
keys.push_back(ord.second); // push back the ordering index
|
||||
orderColumnIndex[ord.second] = columnIndex_.at(ord.first.name());
|
||||
|
||||
if (debug) cout << "map " << ord.second << " with name: "
|
||||
<< ord.first.name() << " to " << columnIndex_.at(
|
||||
ord.first.name()) << endl;
|
||||
}
|
||||
}
|
||||
|
||||
DiscreteFactor f(keys, potentials_, orderColumnIndex, problemType);
|
||||
return f;
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
std::vector<size_t> TypedDiscreteFactor::init(const Indices& keys) {
|
||||
vector<size_t> cardinalities;
|
||||
for (size_t j = 0; j < keys.size(); j++) {
|
||||
Index key = keys[j];
|
||||
keys_.push_back(key);
|
||||
columnIndex_[key.name()] = j;
|
||||
cardinalities.push_back(key.cardinality());
|
||||
}
|
||||
return cardinalities;
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
double TypedDiscreteFactor::potential(const TypedValues& values) const {
|
||||
vector<size_t> assignment(values.size());
|
||||
BOOST_FOREACH(const TypedValues::value_type& val, values)
|
||||
if (columnIndex_.find(val.first) != columnIndex_.end()) assignment[columnIndex_.at(
|
||||
val.first)] = val.second;
|
||||
return potentials_(assignment);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
} // namespace
|
||||
|
|
@ -1,79 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 TypedDiscreteFactor.h
|
||||
* @brief
|
||||
* @author Duy-Nguyen Ta
|
||||
* @date Mar 5, 2011
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam/discrete/DiscreteFactor.h>
|
||||
#include <gtsam/discrete/AlgebraicDecisionTree.h>
|
||||
#include <gtsam/inference/Factor.h>
|
||||
#include <map>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* A factor on discrete variables with string keys
|
||||
*/
|
||||
class TypedDiscreteFactor: public Factor<Index> {
|
||||
|
||||
typedef AlgebraicDecisionDiagram<Index> ADD;
|
||||
|
||||
/** potentials of the factor */
|
||||
ADD potentials_;
|
||||
|
||||
public:
|
||||
|
||||
/** A map from keys to values */
|
||||
typedef ADD::Assignment Values;
|
||||
|
||||
/** Constructor from keys and string table */
|
||||
TypedDiscreteFactor(const Indices& keys, const std::string& table);
|
||||
|
||||
/** Constructor from keys and doubles */
|
||||
TypedDiscreteFactor(const Indices& keys,
|
||||
const std::vector<double>& table);
|
||||
|
||||
/** Evaluate */
|
||||
double operator()(const Values& values) const;
|
||||
|
||||
// Testable
|
||||
bool equals(const TypedDiscreteFactor& other, double tol = 1e-9) const;
|
||||
void print(const std::string& s = "DiscreteFactor: ") const;
|
||||
|
||||
DiscreteFactor::shared_ptr toDiscreteFactor(const KeyOrdering& ordering) const;
|
||||
|
||||
#ifdef OLD
|
||||
/** map each variable name to its column index in the potential table */
|
||||
typedef std::map<std::string, size_t> Index2IndexMap;
|
||||
Index2IndexMap columnIndex_;
|
||||
|
||||
/** Initialize keys, column index, and return cardinalities */
|
||||
std::vector<size_t> init(const Indices& keys);
|
||||
|
||||
public:
|
||||
|
||||
/** Default constructor */
|
||||
TypedDiscreteFactor() {}
|
||||
|
||||
/** Evaluate potential of a given assignment of values */
|
||||
double potential(const TypedValues& values) const;
|
||||
|
||||
#endif
|
||||
|
||||
}; // TypedDiscreteFactor
|
||||
|
||||
} // namespace
|
||||
|
|
@ -1,78 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 TypedDiscreteFactorGraph.cpp
|
||||
* @brief
|
||||
* @author Duy-Nguyen Ta
|
||||
* @date Mar 1, 2011
|
||||
*/
|
||||
|
||||
#include <gtsam_unstable/discrete/TypedDiscreteFactorGraph.h>
|
||||
#include <gtsam/discrete/parseUAI.h>
|
||||
#include <gtsam/discrete/DiscreteFactor.h>
|
||||
#include <gtsam/inference/FactorGraph.h>
|
||||
#include <boost/lexical_cast.hpp>
|
||||
#include <boost/foreach.hpp>
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <stdexcept>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
TypedDiscreteFactorGraph::TypedDiscreteFactorGraph() {
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TypedDiscreteFactorGraph::TypedDiscreteFactorGraph(const string& filename) {
|
||||
bool success = parseUAI(filename, *this);
|
||||
if (!success) throw runtime_error(
|
||||
"TypedDiscreteFactorGraph constructor from filename failed");
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TypedDiscreteFactorGraph::add//
|
||||
(const Indices& keys, const string& table) {
|
||||
push_back(boost::shared_ptr<TypedDiscreteFactor>//
|
||||
(new TypedDiscreteFactor(keys, table)));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TypedDiscreteFactorGraph::add//
|
||||
(const Indices& keys, const vector<double>& table) {
|
||||
push_back(boost::shared_ptr<TypedDiscreteFactor>//
|
||||
(new TypedDiscreteFactor(keys, table)));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TypedDiscreteFactorGraph::print(const string s) {
|
||||
cout << s << endl;
|
||||
cout << "Factors: " << endl;
|
||||
BOOST_FOREACH(const sharedFactor factor, factors_)
|
||||
factor->print();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
double TypedDiscreteFactorGraph::operator()(
|
||||
const TypedDiscreteFactor::Values& values) const {
|
||||
// Loop over all factors and multiply their probabilities
|
||||
double p = 1.0;
|
||||
BOOST_FOREACH(const sharedFactor& factor, *this)
|
||||
p *= (*factor)(values);
|
||||
return p;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
||||
}
|
||||
|
|
@ -1,61 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 TypedDiscreteFactorGraph.h
|
||||
* @brief Factor graph with typed factors (with Index keys)
|
||||
* @author Duy-Nguyen Ta
|
||||
* @author Frank Dellaert
|
||||
* @date Mar 1, 2011
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/discrete/TypedDiscreteFactor.h>
|
||||
#include <gtsam/inference/FactorGraph.h>
|
||||
#include <vector>
|
||||
#include <set>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* Typed discrete factor graph, where keys are strings
|
||||
*/
|
||||
class TypedDiscreteFactorGraph: public FactorGraph<TypedDiscreteFactor> {
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Default constructor
|
||||
*/
|
||||
TypedDiscreteFactorGraph();
|
||||
|
||||
/**
|
||||
* Constructor from file
|
||||
* For now assumes in .uai format from UAI'08 Probablistic Inference Evaluation
|
||||
* See http://graphmod.ics.uci.edu/uai08/FileFormat
|
||||
*/
|
||||
TypedDiscreteFactorGraph(const std::string& filename);
|
||||
|
||||
// Add factors without shared pointer ugliness
|
||||
void add(const Indices& keys, const std::string& table);
|
||||
void add(const Indices& keys, const std::vector<double>& table);
|
||||
|
||||
/** print */
|
||||
void print(const std::string s);
|
||||
|
||||
/** Evaluate potential of a given assignment of values */
|
||||
double operator()(const TypedDiscreteFactor::Values& values) const;
|
||||
|
||||
}; // TypedDiscreteFactorGraph
|
||||
|
||||
|
||||
} // namespace
|
||||
|
|
@ -1,168 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* parseUAI.cpp
|
||||
* @brief: parse UAI 2008 format
|
||||
* @date March 5, 2011
|
||||
* @author Duy-Nguyen Ta
|
||||
* @author Frank Dellaert
|
||||
*/
|
||||
|
||||
//#define PARSE
|
||||
#ifdef PARSE
|
||||
#include <fstream>
|
||||
#include <boost/spirit/include/qi.hpp> // for parsing
|
||||
#include <boost/spirit/include/phoenix.hpp> // for ref
|
||||
#include <boost/spirit/home/phoenix/bind.hpp>
|
||||
#include <boost/spirit/home/phoenix/object.hpp>
|
||||
#include <boost/spirit/home/phoenix/operator.hpp>
|
||||
#include <boost/spirit/include/support_istream_iterator.hpp>
|
||||
|
||||
#include <gtsam/discrete/parseUAI.h>
|
||||
|
||||
using namespace std;
|
||||
namespace qi = boost::spirit::qi;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Keys are the vars of variables connected to a factor
|
||||
// subclass of Indices with special constructor
|
||||
struct Keys: public Indices {
|
||||
Keys() {
|
||||
}
|
||||
// Pick correct vars based on indices
|
||||
Keys(const Indices& vars, const vector<int>& indices) {
|
||||
BOOST_FOREACH(int i, indices)
|
||||
push_back(vars[i]);
|
||||
}
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
// The UAI grammar is defined in a class
|
||||
// Spirit local variables are used, see
|
||||
// http://boost-spirit.com/home/2010/01/21/what-are-rule-bound-semantic-actions
|
||||
/* ************************************************************************* */
|
||||
struct Grammar {
|
||||
|
||||
// declare all parsers as instance variables
|
||||
typedef vector<double> Table;
|
||||
typedef boost::spirit::istream_iterator It;
|
||||
qi::rule<It, qi::space_type> uai, preamble, type, vars, factors, tables;
|
||||
qi::rule<It, qi::space_type, Keys(), qi::locals<size_t> > keys;
|
||||
qi::rule<It, qi::space_type, Table(), qi::locals<size_t> > table;
|
||||
|
||||
// Variables filled by preamble parser
|
||||
size_t nrVars_, nrFactors_;
|
||||
Indices vars_;
|
||||
vector<Keys> factors_;
|
||||
|
||||
// Variables filled by tables parser
|
||||
vector<Table> tables_;
|
||||
|
||||
// The constructor defines the parser rules (declared below)
|
||||
// To debug, just say debug(rule) after defining the rule
|
||||
Grammar() {
|
||||
using boost::phoenix::val;
|
||||
using boost::phoenix::ref;
|
||||
using boost::phoenix::construct;
|
||||
using namespace boost::spirit::qi;
|
||||
|
||||
//--------------- high level parsers with side-effects :-( -----------------
|
||||
|
||||
// A uai file consists of preamble followed by tables
|
||||
uai = preamble >> tables;
|
||||
|
||||
// The preamble defines the variables and factors
|
||||
// The parser fills in the first set of variables above,
|
||||
// including the vector of factor "Neighborhoods"
|
||||
preamble = type >> vars >> int_[ref(nrFactors_) = _1] >> factors;
|
||||
|
||||
// type string, does not seem to matter
|
||||
type = lit("BAYES") | lit("MARKOV");
|
||||
|
||||
// vars parses "3 2 2 3" and synthesizes a Keys class, in this case
|
||||
// containing Indices {v0,2}, {v1,2}, and {v2,3}
|
||||
vars = int_[ref(nrVars_) = _1] >> (repeat(ref(nrVars_))[int_]) //
|
||||
[ref(vars_) = construct<Indices> (_1)];
|
||||
|
||||
// Parse a list of Neighborhoods and fill factors_
|
||||
factors = (repeat(ref(nrFactors_))[keys])//
|
||||
[ref(factors_) = _1];
|
||||
|
||||
// The tables parser fills in the tables_
|
||||
tables = (repeat(ref(nrFactors_))[table])//
|
||||
[ref(tables_) = _1];
|
||||
|
||||
//----------- basic parsers with synthesized attributes :-) -----------------
|
||||
|
||||
// keys parses strings like "2 1 2", indicating
|
||||
// a binary factor (2) on variables v1 and v2.
|
||||
// It returns a Keys class as attribute
|
||||
keys = int_[_a = _1] >> repeat(_a)[int_] //
|
||||
[_val = construct<Keys> (ref(vars_), _1)];
|
||||
|
||||
// The tables are a list of doubles preceded by a count, e.g. "4 1.0 2.0 3.0 4.0"
|
||||
// The table parser returns a PotentialTable::Table attribute
|
||||
table = int_[_a = _1] >> repeat(_a)[double_] //
|
||||
[_val = construct<Table> (_1)];
|
||||
}
|
||||
|
||||
// Add the factors to the graph
|
||||
void addFactorsToGraph(TypedDiscreteFactorGraph& graph) {
|
||||
assert(factors_.size()==nrFactors_);
|
||||
assert(tables_.size()==nrFactors_);
|
||||
for (size_t i = 0; i < nrFactors_; i++)
|
||||
graph.add(factors_[i], tables_[i]);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool parseUAI(const std::string& filename, TypedDiscreteFactorGraph& graph) {
|
||||
|
||||
// open file, disable skipping of whitespace
|
||||
std::ifstream in(filename.c_str());
|
||||
if (!in) {
|
||||
cerr << "Could not open " << filename << endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
in.unsetf(std::ios::skipws);
|
||||
|
||||
// wrap istream into iterator
|
||||
boost::spirit::istream_iterator first(in);
|
||||
boost::spirit::istream_iterator last;
|
||||
|
||||
// Parse and add factors into the graph
|
||||
Grammar grammar;
|
||||
bool success = qi::phrase_parse(first, last, grammar.uai, qi::space);
|
||||
if (success) grammar.addFactorsToGraph(graph);
|
||||
|
||||
return success;
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
|
||||
}// gtsam
|
||||
#else
|
||||
|
||||
#include <gtsam/discrete/parseUAI.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/** Dummy version of function - otherwise, missing symbol */
|
||||
bool parseUAI(const std::string& filename, TypedDiscreteFactorGraph& graph) {
|
||||
return false;
|
||||
}
|
||||
|
||||
} // \namespace gtsam
|
||||
#endif
|
||||
|
|
@ -1,33 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* parseUAI.h
|
||||
* @brief: parse UAI 2008 format
|
||||
* @date March 5, 2011
|
||||
* @author Duy-Nguyen Ta
|
||||
* @author Frank Dellaert
|
||||
*/
|
||||
|
||||
#include <string>
|
||||
#include <gtsam/discrete/TypedDiscreteFactorGraph.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* Constructor from file
|
||||
* For now assumes in .uai format from UAI'08 Probablistic Inference Evaluation
|
||||
* See http://graphmod.ics.uci.edu/uai08/FileFormat
|
||||
*/
|
||||
bool parseUAI(const std::string& filename,
|
||||
gtsam::TypedDiscreteFactorGraph& graph);
|
||||
|
||||
} // gtsam
|
||||
|
|
@ -1,164 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testPotentialTable.cpp
|
||||
* @brief Develop recursive potential operations
|
||||
* @author Frank Dellaert
|
||||
* @date Mar 6, 2011
|
||||
*/
|
||||
|
||||
#include <boost/foreach.hpp>
|
||||
#include <boost/assign/std/vector.hpp> // for operator +=
|
||||
using namespace boost::assign;
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/discrete/PotentialTable.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
/* ******************************************************************************** */
|
||||
TEST( PotentialTable, Iterator)
|
||||
{
|
||||
PotentialTable::Cardinalities cs;
|
||||
cs += 2, 3;
|
||||
PotentialTable::Iterator it(cs);
|
||||
LONGS_EQUAL(0,it[0]);
|
||||
LONGS_EQUAL(0,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(0,it[0]);
|
||||
LONGS_EQUAL(1,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(0,it[0]);
|
||||
LONGS_EQUAL(2,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(1,it[0]);
|
||||
LONGS_EQUAL(0,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(1,it[0]);
|
||||
LONGS_EQUAL(1,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(1,it[0]);
|
||||
LONGS_EQUAL(2,it[1]);
|
||||
++it;
|
||||
LONGS_EQUAL(0,it[0]);
|
||||
LONGS_EQUAL(0,it[1]);
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
#include <boost/unordered_map.hpp>
|
||||
|
||||
TEST( PotentialTable, unordered_map)
|
||||
{
|
||||
boost::unordered_map<bool, int> x;
|
||||
x[false] = 7;
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
|
||||
struct Factor {
|
||||
vector<double> table_;
|
||||
vector<Index> keys_;
|
||||
bool operator==(const Factor& f) const {
|
||||
return table_ == f.table_ && keys_ == f.keys_;
|
||||
}
|
||||
};
|
||||
|
||||
Factor operator*(const double& s, const Factor& f) {
|
||||
Factor r = f;
|
||||
BOOST_FOREACH(double& ri, r.table_)
|
||||
ri *= s;
|
||||
return r;
|
||||
}
|
||||
|
||||
Factor operator*(const Factor& f, const double& s) {
|
||||
Factor r = f;
|
||||
BOOST_FOREACH(double& ri, r.table_)
|
||||
ri *= s;
|
||||
return r;
|
||||
}
|
||||
|
||||
Factor operator*(const Factor& f1, const Factor& f2) {
|
||||
Factor r;
|
||||
|
||||
// base case 1, both tables start with same key
|
||||
if (f1.keys_.front() == f2.keys_.front()) {
|
||||
}
|
||||
|
||||
return r;
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// f(5)*f(5) = f0*f0 @ f1*f1
|
||||
TEST( PotentialTable, baseCase1a)
|
||||
{
|
||||
Factor f1, f2, expected;
|
||||
f1.table_ += 00, 01;
|
||||
f2.table_ += 20, 21;
|
||||
f1.keys_ += 5;
|
||||
f2.keys_ += 5;
|
||||
expected.table_ += 00 * 20, 01 * 21;
|
||||
expected.keys_ += 5;
|
||||
CHECK(f1*f2==expected)
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// f(0,1)*f(0) = f0(1)*f0 @ f1(1)*f1
|
||||
TEST( PotentialTable, baseCase1b)
|
||||
{
|
||||
Factor f1, f2, expected;
|
||||
f1.table_ += 00, 01, 10, 11;
|
||||
f2.table_ += 20, 21;
|
||||
f1.keys_ += 0, 1;
|
||||
f2.keys_ += 0;
|
||||
expected.table_ += 00 * 20, 00 * 21, 01 * 20, 01 * 21, 10 * 20, 10 * 21, 11
|
||||
* 20, 11 * 21;
|
||||
expected.keys_ += 0, 1, 2;
|
||||
CHECK(f1*f2==expected)
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// f0(1)*f(2) = f00*f(2) @ f01*f(2)
|
||||
TEST( PotentialTable, baseCase2)
|
||||
{
|
||||
Factor f1, f2, expected;
|
||||
f1.table_ += 00, 01;
|
||||
f2.table_ += 20, 21;
|
||||
f1.keys_ += 1;
|
||||
f2.keys_ += 2;
|
||||
expected.table_ += 00 * 20, 00 * 21, 01 * 20, 01 * 21;
|
||||
expected.keys_ += 1, 2;
|
||||
CHECK(f1*f2==expected)
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// f(0,1)*f(2) = f0(1)*f(2) @ f1(1)*f(2)
|
||||
// f0(1)*f(2) = f00*f(2) @ f01*f(2)
|
||||
TEST( PotentialTable, multiplication)
|
||||
{
|
||||
Factor f1, f2, expected;
|
||||
f1.table_ += 00, 01, 10, 11;
|
||||
f2.table_ += 20, 21;
|
||||
f1.keys_ += 0, 1;
|
||||
f2.keys_ += 2;
|
||||
expected.table_ += 00 * 20, 00 * 21, 01 * 20, 01 * 21, 10 * 20, 10 * 21, 11
|
||||
* 20, 11 * 21;
|
||||
expected.keys_ += 0, 1, 2;
|
||||
CHECK(f1*f2==expected)
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
TestResult tr;
|
||||
return TestRegistry::runAllTests(tr);
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -1,64 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testTypedDiscreteFactor.cpp
|
||||
* @brief Typed f1s use discrete keys
|
||||
* @author Duy-Nguyen Ta
|
||||
* @date Mar 5, 2011
|
||||
*/
|
||||
|
||||
#include <gtsam_unstable/discrete/TypedDiscreteFactor.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
using namespace boost::assign;
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// initialize some common test values
|
||||
DiscreteKey v0("v0"), v1("v1"), v2("v2", 3);
|
||||
TypedDiscreteFactor::Values values;
|
||||
|
||||
void init() {
|
||||
values[v0] = 0;
|
||||
values[v1] = 0;
|
||||
values[v2] = 1;
|
||||
}
|
||||
|
||||
/* ******************************************************************************** */
|
||||
TEST( TypedDiscreteFactor, constructors)
|
||||
{
|
||||
TypedDiscreteFactor f1(v1 & v2, "0.210 0.333 0.457 0.811 0.000 0.189");
|
||||
EXPECT_LONGS_EQUAL(2, f1.size());
|
||||
// f1.print();
|
||||
|
||||
double expectedP001 = 0.333;
|
||||
EXPECT_DOUBLES_EQUAL(expectedP001, f1(values), 1e-9);
|
||||
|
||||
vector<double> ys;
|
||||
ys += 0.210, 0.333, 0.457, 0.811, 0.000, 0.189;
|
||||
TypedDiscreteFactor f2(v1 & v2, ys);
|
||||
|
||||
EXPECT(assert_equal(f1, f2, 1e-9));
|
||||
EXPECT_LONGS_EQUAL(2, f1.size());
|
||||
EXPECT_DOUBLES_EQUAL(expectedP001, f2(values), 1e-9);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
init();
|
||||
TestResult tr;
|
||||
return TestRegistry::runAllTests(tr);
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -1,204 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* testTypedDiscreteFactorGraph.cpp
|
||||
* @brief test readable factor graphs
|
||||
* @author Duy-Nguyen Ta
|
||||
* @author Frank Dellaert
|
||||
* @date Feb 14, 2011
|
||||
*/
|
||||
|
||||
#include <gtsam_unstable/discrete/TypedDiscreteFactorGraph.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/foreach.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
/* ******************************************************************************** */
|
||||
// initialize some common test values
|
||||
DiscreteKey v0("v0"), v1("v1"), v2("v2", 3);
|
||||
TypedDiscreteFactor::Values values;
|
||||
|
||||
void init() {
|
||||
values[v0] = 0;
|
||||
values[v1] = 0;
|
||||
values[v2] = 1;
|
||||
}
|
||||
|
||||
string path("../../../gtsam/discrete/tests/data/");
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( TypedDiscreteFactorGraph, parseUAI)
|
||||
{
|
||||
// This reads in a small factor graph on discrete variables v0, v1, and v2
|
||||
TypedDiscreteFactorGraph graph(path + "UAI/sampleMARKOV.uai");
|
||||
|
||||
// GTSAM_PRINT(graph);
|
||||
|
||||
LONGS_EQUAL(3,graph.nrFactors())
|
||||
|
||||
double expectedP001 = 0.436 * 0.128 * 0.333;
|
||||
double actualP001 = graph(values);
|
||||
DOUBLES_EQUAL(expectedP001,actualP001,1e-9)
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( TypedDiscreteFactorGraph, parseUAI1)
|
||||
{
|
||||
// This reads in a big graph from UAI 2008
|
||||
TypedDiscreteFactorGraph graph(path + "UAI/uai08_test1.uai");
|
||||
// GTSAM_PRINT(graph);
|
||||
LONGS_EQUAL(54,graph.nrFactors())
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( TypedDiscreteFactorGraph, parseUAI2)
|
||||
{
|
||||
// This reads in a big graph from UAI 2008
|
||||
TypedDiscreteFactorGraph graph(path + "UAI/uai08_test2.uai");
|
||||
// GTSAM_PRINT(graph);
|
||||
LONGS_EQUAL(21,graph.nrFactors())
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( TypedDiscreteFactorGraph, parseUAI3)
|
||||
{
|
||||
// This reads in a big graph from UAI 2008
|
||||
TypedDiscreteFactorGraph graph(path + "UAI/uai08_test3.uai");
|
||||
// GTSAM_PRINT(graph);
|
||||
LONGS_EQUAL(13,graph.nrFactors())
|
||||
}
|
||||
|
||||
///* ******************************************************************************** */
|
||||
//// global test data
|
||||
//
|
||||
//string graphFilename(path + "UAI/uai08_test2.uai");
|
||||
//string evidFilename (path + "UAI/uai08_test2.uai.evid");
|
||||
//
|
||||
///**
|
||||
// * [Cluster] Ordering splitted from libDAI
|
||||
// * {x9}, {x10}, {x11}, {x12}, {x13}, {x14}, {x15}, {x16}, {x17}, {x18}, {x19}, {x20},
|
||||
// * {x0, x1, x8}, {x2, x6, x7}, {x4, x6, x8},
|
||||
// * {x1, x5, x7}, {x1, x3, x7, x8}, {x3, x6, x7, x8})
|
||||
// *
|
||||
// */
|
||||
//size_t ordering[21] = {9,10,11,12,13,14,15,16,17,18,19,20,0,2,4,5,1,3,6,7,8};
|
||||
//vector<Index> vOrdering;
|
||||
//
|
||||
//// Container for all data read from files.
|
||||
//TypedDiscreteFactorGraph container;
|
||||
//
|
||||
//// The factor graph generated from the data, after assigning the elimination ordering
|
||||
//// for each variable
|
||||
//DiscreteFactorGraph::shared_ptr graph;
|
||||
//
|
||||
///* ******************************************************************************** */
|
||||
//// Initialize all test data
|
||||
//void initTestData()
|
||||
//{
|
||||
// container.readFromFile_UAI(graphFilename);
|
||||
// container.readEvidence_UAI(evidFilename);
|
||||
// for (size_t i = 0; i<21; i++) vOrdering.push_back(ordering[i]);
|
||||
// container.setOrdering(vOrdering);
|
||||
// graph = container.generateFactorGraph();
|
||||
//}
|
||||
//
|
||||
//
|
||||
///* ******************************************************************************** */
|
||||
//// Test reading .fg file from libDAI
|
||||
//TEST( TypedDiscreteFactorGraph, readFG)
|
||||
//{
|
||||
// TypedDiscreteFactorGraph graph;
|
||||
// graph.readFromFile_FG(path + "FG/alarm.fg");
|
||||
//// graph.print();
|
||||
//}
|
||||
//
|
||||
///* ******************************************************************************** */
|
||||
//TEST( TypedDiscreteFactorGraph, testSequentialSolver)
|
||||
//{
|
||||
//// tic(0, "Sequential Solver");
|
||||
//
|
||||
// boost::shared_ptr<PotentialTable::MapAssignment> actualMPE
|
||||
// = DiscreteSequentialSolver(*graph).optimize();
|
||||
// BOOST_FOREACH(const PotentialTable::MapAssignment::value_type asg, *actualMPE)
|
||||
// cout << vOrdering[asg.first] << ": " << asg.second << endl;
|
||||
//
|
||||
//// toc(0, "Sequential Solver");
|
||||
// tictoc_print();
|
||||
//
|
||||
//}
|
||||
//
|
||||
///* ******************************************************************************** */
|
||||
//void backSubstitute(const BayesTree<DiscreteConditional>::sharedClique currentClique,
|
||||
// PotentialTable::MapAssignment& assignments) {
|
||||
//
|
||||
// // solve the bayes net in the current node
|
||||
// DiscreteBayesNet::const_reverse_iterator it = currentClique->rbegin();
|
||||
// for (; it!=currentClique->rend(); ++it) {
|
||||
// size_t val = (*it)->solve(assignments); // Solve for that variable
|
||||
// assignments[(*it)->key()] = val; // store result in partial solution
|
||||
// }
|
||||
//
|
||||
// // solve the bayes nets in the child nodes
|
||||
// BOOST_FOREACH(const BayesTree<DiscreteConditional>::sharedClique& child,
|
||||
// currentClique->children()) {
|
||||
// backSubstitute(child, assignments);
|
||||
// }
|
||||
//}
|
||||
//
|
||||
//
|
||||
//void optimizeMultiFrontal(DiscreteFactorGraph::shared_ptr graph) {
|
||||
//
|
||||
// VariableIndex::shared_ptr structure(new VariableIndex(*graph));
|
||||
// JunctionTree<DiscreteFactorGraph>::shared_ptr junctionTree(new JunctionTree<DiscreteFactorGraph>(*graph, *structure));
|
||||
// BayesTree<DiscreteConditional>::sharedClique rootClique = junctionTree->eliminate();
|
||||
//
|
||||
//// toc(1, "GJT eliminate");
|
||||
//
|
||||
//// tictoc_print();
|
||||
//
|
||||
//// // Allocate solution vector
|
||||
//// tic(2, "allocate VectorValues");
|
||||
//// vector<size_t> dims(rootClique->back()->key() + 1, 0);
|
||||
//// countDims(rootClique, dims);
|
||||
//// VectorValues result(dims);
|
||||
//// toc(2, "allocate VectorValues");
|
||||
////
|
||||
//// // back-substitution
|
||||
//// tic(3, "back-substitute");
|
||||
//// btreeBackSubstitute(rootClique, result);
|
||||
//// toc(3, "back-substitute");
|
||||
//// return result;
|
||||
//}
|
||||
//
|
||||
//
|
||||
///* ******************************************************************************** */
|
||||
//
|
||||
//TEST( TypedDiscreteFactorGraph, multifrontalSolver)
|
||||
//{
|
||||
// tic(0, "Multifrontal Solver");
|
||||
// optimizeMultiFrontal(graph);
|
||||
//
|
||||
// toc(0, "Multifrontal Solver");
|
||||
// tictoc_print();
|
||||
//}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { /*initTestData(); */
|
||||
init();
|
||||
TestResult tr;
|
||||
return TestRegistry::runAllTests(tr);
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
|
||||
|
|
@ -1,80 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/*
|
||||
* testTypedDiscreteVariable.cpp
|
||||
*
|
||||
* @date March 2, 2011
|
||||
* @author Duy-Nguyen Ta
|
||||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std;
|
||||
|
||||
/* ******************************************************************************** */
|
||||
|
||||
class DiscreteVariable {
|
||||
int v_;
|
||||
public:
|
||||
DiscreteVariable(int v) :
|
||||
v_(v) {
|
||||
}
|
||||
bool operator ==(const DiscreteVariable& other) const {
|
||||
return v_ == other.v_;
|
||||
}
|
||||
bool operator !=(const DiscreteVariable& other) const {
|
||||
return v_ != other.v_;
|
||||
}
|
||||
};
|
||||
|
||||
class Color: public DiscreteVariable {
|
||||
public:
|
||||
enum Value {
|
||||
red, green, blue
|
||||
};
|
||||
Color(Value v) :
|
||||
DiscreteVariable(v) {
|
||||
}
|
||||
};
|
||||
|
||||
class Flavor: public DiscreteVariable {
|
||||
public:
|
||||
enum Value {
|
||||
sweet, sour
|
||||
};
|
||||
Flavor(Value v) :
|
||||
DiscreteVariable(v) {
|
||||
}
|
||||
};
|
||||
|
||||
//TEST( TypedDiscreteFactorGraph, simple)
|
||||
//{
|
||||
// Color v1(Color::red), v2(Color::green);
|
||||
// CHECK(v1!=v2);
|
||||
// CHECK(v1==v1);
|
||||
//
|
||||
// // Declare a bunch of keys
|
||||
// DiscreteKey<Color> C("Color");
|
||||
// DiscreteKey<Flavor> F("Flavor");
|
||||
//
|
||||
// // Create a factor saying red is associated with sweet,
|
||||
// // green with sour, blue with both
|
||||
// TypedDiscreteFactor factor(C, F, "1 0 0 1 1 1");
|
||||
//}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() {
|
||||
TestResult tr;
|
||||
return TestRegistry::runAllTests(tr);
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
|
||||
Loading…
Reference in New Issue