ChordalBayesNet is now derived from BayesChain

Explicit template instantiations
release/4.3a0
Frank Dellaert 2009-10-30 04:54:11 +00:00
parent dd3795ad5a
commit 83e5286710
14 changed files with 70 additions and 134 deletions

View File

@ -50,6 +50,18 @@ namespace gtsam {
nodes_.insert(make_pair(key,node));
}
/* ************************************************************************* */
template<class Conditional>
void BayesChain<Conditional>::erase(const string& key) {
list<string>::iterator it;
for (it=keys_.begin(); it != keys_.end(); ++it){
if( strcmp(key.c_str(), (*it).c_str()) == 0 )
break;
}
keys_.erase(it);
nodes_.erase(key);
}
/* ************************************************************************* */
} // namespace gtsam

View File

@ -33,8 +33,6 @@ namespace gtsam {
typedef typename std::map<std::string, boost::shared_ptr<Conditional> > Nodes;
Nodes nodes_;
typedef typename Nodes::const_iterator const_iterator;
public:
/** print */
@ -43,8 +41,35 @@ namespace gtsam {
/** check equality */
bool equals(const BayesChain& other, double tol = 1e-9) const;
/** size is the number of nodes */
inline size_t size() const {return nodes_.size();}
/** insert: use reverse topological sort (i.e. parents last) */
void insert(const std::string& key, boost::shared_ptr<Conditional> node);
/** delete */
void erase(const std::string& key);
inline boost::shared_ptr<Conditional> operator[](const std::string& key) const {
const_iterator cg = nodes_.find(key); // get node
assert( cg != nodes_.end() );
return cg->second;
}
/** return begin and end of the nodes. FD: breaks encapsulation? */
typedef typename Nodes::const_iterator const_iterator;
const_iterator const begin() const {return nodes_.begin();}
const_iterator const end() const {return nodes_.end();}
private:
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & BOOST_SERIALIZATION_NVP(keys_);
ar & BOOST_SERIALIZATION_NVP(nodes_);
}
};
} /// namespace gtsam

View File

@ -14,61 +14,22 @@
using namespace std;
using namespace gtsam;
// Explicitly instantiate so we don't have to include everywhere
#include "BayesChain-inl.h"
template class BayesChain<ConditionalGaussian>;
// trick from some reading group
#define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL)
/* ************************************************************************* */
void ChordalBayesNet::print(const string& s) const {
BOOST_FOREACH(string key, keys) {
const_iterator it = nodes.find(key);
it->second->print("\nNode[" + key + "]");
}
}
/* ************************************************************************* */
bool ChordalBayesNet::equals(const ChordalBayesNet& cbn, double tol) const
{
const_iterator it1 = nodes.begin(), it2 = cbn.nodes.begin();
if(nodes.size() != cbn.nodes.size()) return false;
for(; it1 != nodes.end(); it1++, it2++){
const string& j1 = it1->first, j2 = it2->first;
ConditionalGaussian::shared_ptr node1 = it1->second, node2 = it2->second;
if (j1 != j2) return false;
if (!node1->equals(*node2,tol))
return false;
}
return true;
}
/* ************************************************************************* */
void ChordalBayesNet::insert(const string& key, ConditionalGaussian::shared_ptr node)
{
keys.push_front(key);
nodes.insert(make_pair(key,node));
}
/* ************************************************************************* */
void ChordalBayesNet::erase(const string& key)
{
list<string>::iterator it;
for (it=keys.begin(); it != keys.end(); ++it){
if( strcmp(key.c_str(), (*it).c_str()) == 0 )
break;
}
keys.erase(it);
nodes.erase(key);
}
/* ************************************************************************* */
boost::shared_ptr<VectorConfig> ChordalBayesNet::optimize() const
{
boost::shared_ptr<VectorConfig> result(new VectorConfig);
/** solve each node in turn in topological sort order (parents first)*/
BOOST_FOREACH(string key, keys) {
const_iterator cg = nodes.find(key); // get node
assert( cg != nodes.end() ); // make sure it exists
BOOST_FOREACH(string key, keys_) {
const_iterator cg = nodes_.find(key); // get node
assert( cg != nodes_.end() ); // make sure it exists
Vector x = cg->second->solve(*result); // Solve for that variable
result->insert(key,x); // store result in partial solution
}
@ -81,9 +42,9 @@ pair<Matrix,Vector> ChordalBayesNet::matrix() const {
// add the dimensions of all variables to get matrix dimension
// and at the same time create a mapping from keys to indices
size_t N=0; map<string,size_t> indices;
BOOST_REVERSE_FOREACH(string key, keys) {
BOOST_REVERSE_FOREACH(string key, keys_) {
// find corresponding node
const_iterator it = nodes.find(key);
const_iterator it = nodes_.find(key);
indices.insert(make_pair(key,N));
N += it->second->dim();
}
@ -94,7 +55,7 @@ pair<Matrix,Vector> ChordalBayesNet::matrix() const {
string key; size_t I;
FOREACH_PAIR(key,I,indices) {
// find corresponding node
const_iterator it = nodes.find(key);
const_iterator it = nodes_.find(key);
ConditionalGaussian::shared_ptr cg = it->second;
// get RHS and copy to d

View File

@ -10,95 +10,37 @@
#pragma once
#include <list>
#include <boost/serialization/map.hpp>
#include <boost/serialization/list.hpp>
#include "ConditionalGaussian.h"
#include "Testable.h"
#include "BayesChain.h"
namespace gtsam {
/** Chordal Bayes Net, the result of eliminating a factor graph */
class ChordalBayesNet : public Testable<ChordalBayesNet>
class ChordalBayesNet : public BayesChain<ConditionalGaussian>
{
public:
typedef boost::shared_ptr<ChordalBayesNet> shared_ptr;
protected:
/** nodes keys stored in topological sort order, i.e. from parents to children */
std::list<std::string> keys;
/** nodes stored on key */
typedef std::map<std::string,ConditionalGaussian::shared_ptr> Nodes;
Nodes nodes;
typedef Nodes::iterator iterator;
public:
/** Construct an empty net */
ChordalBayesNet() {}
/** Copy Constructor */
ChordalBayesNet(const ChordalBayesNet& cbn_in) : keys(cbn_in.keys), nodes(cbn_in.nodes) {}
// ChordalBayesNet(const ChordalBayesNet& cbn_in) :
// keys_(cbn_in.keys_), nodes_(cbn_in.nodes_) {}
/** Destructor */
virtual ~ChordalBayesNet() {}
/** print */
void print(const std::string& s="") const;
/** check equality */
bool equals(const ChordalBayesNet& cbn, double tol=1e-9) const;
/** insert: use reverse topological sort (i.e. parents last) */
void insert(const std::string& key, ConditionalGaussian::shared_ptr node);
/** delete */
void erase(const std::string& key);
/** return node with given key */
inline ConditionalGaussian::shared_ptr get (const std::string& key) const {
const_iterator cg = nodes.find(key); // get node
assert( cg != nodes.end() );
return cg->second;
}
inline ConditionalGaussian::shared_ptr operator[](const std::string& key) const {
const_iterator cg = nodes.find(key); // get node
assert( cg != nodes.end() );
return cg->second;
}
/** return begin and end of the nodes. FD: breaks encapsulation? */
typedef Nodes::const_iterator const_iterator;
const_iterator const begin() const {return nodes.begin();}
const_iterator const end() const {return nodes.end();}
/**
* optimize, i.e. return x = inv(R)*d
*/
boost::shared_ptr<VectorConfig> optimize() const;
/** size is the number of nodes */
size_t size() const {return nodes.size();}
/**
* Return (dense) upper-triangular matrix representation
*/
std::pair<Matrix,Vector> matrix() const;
private:
/** Serialization function */
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & BOOST_SERIALIZATION_NVP(keys);
ar & BOOST_SERIALIZATION_NVP(nodes);
}
};
} /// namespace gtsam

View File

@ -15,10 +15,15 @@
#include "ChordalBayesNet.h"
#include "FactorGraph-inl.h"
#include "LinearFactorGraph.h"
#include "SymbolicBayesChain-inl.h"
using namespace std;
using namespace gtsam;
// explicitly instantiate conversion from LinearFG to SymbolicFG
template SymbolicBayesChain::SymbolicBayesChain
(FactorGraph<LinearFactor> const&, Ordering const&);
/* ************************************************************************* */
LinearFactorGraph::LinearFactorGraph(const ChordalBayesNet& CBN)
{

View File

@ -37,7 +37,6 @@ external_libs:
@echo Compiling CppUnitLite...; cd ../CppUnitLite; make all
@echo Compiling Colamd...; cd ../colamd; make all
clean : clean_external_libs
@echo Cleaning Cpp...; rm -f *.o *.lo *.*~ libgtsam.la $(check_PROGRAMS)
@ -162,8 +161,8 @@ testVSLAMFactor_LDADD = libgtsam.la
# The header files will be installed in ~/include/gtsam
headers = gtsam.h Value.h Testable.h Factor.h LinearFactorSet.h Point2Prior.h
headers += Simulated2DOdometry.h Simulated2DMeasurement.h smallExample.h
headers = gtsam.h Value.h Testable.h Factor.h LinearFactorSet.h BayesChain.h
headers += Point2Prior.h Simulated2DOdometry.h Simulated2DMeasurement.h smallExample.h
headers += $(sources:.cpp=.h)
# templates:
headers += FactorGraph.h FactorGraph-inl.h

View File

@ -10,13 +10,16 @@
// trick from some reading group
#define FOREACH_PAIR( KEY, VAL, COL) BOOST_FOREACH (boost::tie(KEY,VAL),COL)
#include "BayesChain-inl.h"
#include "SymbolicBayesChain.h"
#include "BayesChain-inl.h"
using namespace std;
namespace gtsam {
// Explicitly instantiate so we don't have to include everywhere
template class BayesChain<SymbolicConditional>;
typedef pair<string,SymbolicConditional::shared_ptr> pp;
/* ************************************************************************* */

View File

@ -8,7 +8,6 @@
#include <boost/foreach.hpp>
#include "Ordering.h"
#include "SymbolicFactorGraph.h"
#include "BayesChain-inl.h"
#include "SymbolicBayesChain.h"
using namespace std;

View File

@ -11,17 +11,12 @@
#pragma once
#include <boost/shared_ptr.hpp>
//#include "ConstrainedNonlinearFactorGraph.h" // will be added back once design is solidified
#include "ConstrainedLinearFactorGraph.h"
#include "NonlinearFactorGraph.h"
#include "ChordalBayesNet.h"
#include "LinearFactorGraph.h"
#include "VectorConfig.h"
// \namespace
namespace gtsam {
class ConstrainedLinearFactorGraph;
typedef NonlinearFactorGraph<VectorConfig> ExampleNonlinearFactorGraph;
/**

View File

@ -6,8 +6,7 @@
#include <CppUnitLite/TestHarness.h>
#include "BayesChain-inl.h"
#include "SymbolicBayesChain-inl.h"
#include "SymbolicBayesChain.h"
#include "smallExample.h"
#include "BayesTree.h"

View File

@ -20,8 +20,6 @@
#include "ChordalBayesNet.h"
#include "smallExample.h"
using namespace gtsam;
/* ************************************************************************* */

View File

@ -42,7 +42,7 @@ TEST( ConstrainedLinearFactorGraph, elimination1 )
Matrix Ay1 = eye(2) * 10;
Vector b2 = Vector_(2, 1.0, 2.0);
ConstrainedConditionalGaussian expectedCCG1(b2, Ax1, "y", Ay1);
CHECK(expectedCCG1.equals(*(cbn->get("x"))));
CHECK(expectedCCG1.equals(*((*cbn)["x"])));
// verify remaining factor on y
// Gaussian factor on X becomes different Gaussian factor on Y
@ -66,7 +66,7 @@ TEST( ConstrainedLinearFactorGraph, elimination1 )
R(1, 0) = 0.0; R(1, 1) = 44.7214;
Vector br = Vector_(2, 8.9443, 4.4721);
ConditionalGaussian expected2(br, R);
CHECK(expected2.equals(*(cbn->get("y"))));
CHECK(expected2.equals(*((*cbn)["y"])));
}
/* ************************************************************************* */

View File

@ -8,8 +8,7 @@
#include "smallExample.h"
#include "FactorGraph-inl.h"
#include "BayesChain-inl.h"
#include "SymbolicBayesChain-inl.h"
#include "SymbolicBayesChain.h"
using namespace std;
using namespace gtsam;

View File

@ -9,7 +9,6 @@
#include "smallExample.h"
#include "FactorGraph-inl.h"
#include "SymbolicFactorGraph.h"
#include "BayesChain-inl.h"
#include "SymbolicConditional.h"
#include "SymbolicBayesChain.h"