Renamed BayesNet::insert -> push_back. BayesTree now uses Bayes nets as nodes.
parent
a8d267c4ca
commit
eab038651e
33
.cproject
33
.cproject
|
@ -300,6 +300,7 @@
|
||||||
<buildTargets>
|
<buildTargets>
|
||||||
<target name="install" path="wrap" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="install" path="wrap" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>install</buildTarget>
|
<buildTarget>install</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -307,6 +308,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="check" path="wrap" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="check" path="wrap" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>check</buildTarget>
|
<buildTarget>check</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -314,14 +316,15 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="check" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="check" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
<buildArguments>-k</buildArguments>
|
||||||
<buildTarget>check</buildTarget>
|
<buildTarget>check</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
<target name="testSimpleCamera.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testSimpleCamera.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testSimpleCamera.run</buildTarget>
|
<buildTarget>testSimpleCamera.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -337,7 +340,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testVSLAMFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testVSLAMFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testVSLAMFactor.run</buildTarget>
|
<buildTarget>testVSLAMFactor.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -345,6 +347,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testCalibratedCamera.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testCalibratedCamera.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testCalibratedCamera.run</buildTarget>
|
<buildTarget>testCalibratedCamera.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -352,7 +355,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testConditionalGaussian.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testConditionalGaussian.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testConditionalGaussian.run</buildTarget>
|
<buildTarget>testConditionalGaussian.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -360,6 +362,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testPose2.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testPose2.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testPose2.run</buildTarget>
|
<buildTarget>testPose2.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -375,6 +378,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testRot3.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testRot3.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testRot3.run</buildTarget>
|
<buildTarget>testRot3.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -382,7 +386,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testNonlinearOptimizer.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testNonlinearOptimizer.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testNonlinearOptimizer.run</buildTarget>
|
<buildTarget>testNonlinearOptimizer.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -390,6 +393,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testLinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testLinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testLinearFactor.run</buildTarget>
|
<buildTarget>testLinearFactor.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -397,6 +401,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testConstrainedNonlinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testConstrainedNonlinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testConstrainedNonlinearFactorGraph.run</buildTarget>
|
<buildTarget>testConstrainedNonlinearFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -404,6 +409,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testLinearFactorGraph.run</buildTarget>
|
<buildTarget>testLinearFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -411,7 +417,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testNonlinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testNonlinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testNonlinearFactorGraph.run</buildTarget>
|
<buildTarget>testNonlinearFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -419,6 +424,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testPose3.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testPose3.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testPose3.run</buildTarget>
|
<buildTarget>testPose3.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -426,7 +432,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testConstrainedLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testConstrainedLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testConstrainedLinearFactorGraph.run</buildTarget>
|
<buildTarget>testConstrainedLinearFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -434,7 +439,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testVectorConfig.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testVectorConfig.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testVectorConfig.run</buildTarget>
|
<buildTarget>testVectorConfig.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -442,7 +446,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testPoint2.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testPoint2.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testPoint2.run</buildTarget>
|
<buildTarget>testPoint2.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -450,6 +453,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testNonlinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testNonlinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testNonlinearFactor.run</buildTarget>
|
<buildTarget>testNonlinearFactor.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -457,6 +461,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="timeLinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="timeLinearFactor.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>timeLinearFactor.run</buildTarget>
|
<buildTarget>timeLinearFactor.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -464,6 +469,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="timeLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="timeLinearFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>timeLinearFactorGraph.run</buildTarget>
|
<buildTarget>timeLinearFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -471,6 +477,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testGaussianBayesNet.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testGaussianBayesNet.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testGaussianBayesNet.run</buildTarget>
|
<buildTarget>testGaussianBayesNet.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -478,7 +485,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testBayesTree.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testBayesTree.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testBayesTree.run</buildTarget>
|
<buildTarget>testBayesTree.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>false</useDefaultCommand>
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
@ -486,7 +492,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testSymbolicBayesChain.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testSymbolicBayesChain.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testSymbolicBayesChain.run</buildTarget>
|
<buildTarget>testSymbolicBayesChain.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>false</useDefaultCommand>
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
@ -494,7 +499,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testSymbolicFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testSymbolicFactorGraph.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>false</useDefaultCommand>
|
<useDefaultCommand>false</useDefaultCommand>
|
||||||
|
@ -502,6 +506,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testVector.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testVector.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testVector.run</buildTarget>
|
<buildTarget>testVector.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -509,6 +514,7 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="testMatrix.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testMatrix.run" path="cpp" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments/>
|
||||||
<buildTarget>testMatrix.run</buildTarget>
|
<buildTarget>testMatrix.run</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -516,7 +522,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>install</buildTarget>
|
<buildTarget>install</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -524,7 +529,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>clean</buildTarget>
|
<buildTarget>clean</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
@ -532,7 +536,6 @@
|
||||||
</target>
|
</target>
|
||||||
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments/>
|
|
||||||
<buildTarget>check</buildTarget>
|
<buildTarget>check</buildTarget>
|
||||||
<stopOnError>true</stopOnError>
|
<stopOnError>true</stopOnError>
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
|
|
@ -37,7 +37,7 @@ namespace gtsam {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
template<class Conditional>
|
template<class Conditional>
|
||||||
void BayesNet<Conditional>::insert
|
void BayesNet<Conditional>::push_back
|
||||||
(const boost::shared_ptr<Conditional>& conditional) {
|
(const boost::shared_ptr<Conditional>& conditional) {
|
||||||
indices_.insert(make_pair(conditional->key(),conditionals_.size()));
|
indices_.insert(make_pair(conditional->key(),conditionals_.size()));
|
||||||
conditionals_.push_back(conditional);
|
conditionals_.push_back(conditional);
|
||||||
|
|
|
@ -67,8 +67,8 @@ namespace gtsam {
|
||||||
/** check equality */
|
/** check equality */
|
||||||
bool equals(const BayesNet& other, double tol = 1e-9) const;
|
bool equals(const BayesNet& other, double tol = 1e-9) const;
|
||||||
|
|
||||||
/** insert: use reverse topological sort (i.e. parents last / elimination order) */
|
/** push_back: use reverse topological sort (i.e. parents last / elimination order) */
|
||||||
void insert(const boost::shared_ptr<Conditional>& conditional);
|
void push_back(const boost::shared_ptr<Conditional>& conditional);
|
||||||
|
|
||||||
/** size is the number of nodes */
|
/** size is the number of nodes */
|
||||||
inline size_t size() const {
|
inline size_t size() const {
|
||||||
|
|
|
@ -13,16 +13,16 @@ namespace gtsam {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
template<class Conditional>
|
template<class Conditional>
|
||||||
Front<Conditional>::Front(const conditional_ptr& conditional) {
|
BayesTree<Conditional>::Node::Node(const boost::shared_ptr<Conditional>& conditional) {
|
||||||
add(conditional);
|
|
||||||
separator_ = conditional->parents();
|
separator_ = conditional->parents();
|
||||||
|
this->push_back(conditional);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
template<class Conditional>
|
template<class Conditional>
|
||||||
void Front<Conditional>::print(const string& s) const {
|
void BayesTree<Conditional>::Node::print(const string& s) const {
|
||||||
cout << s;
|
cout << s;
|
||||||
BOOST_FOREACH(const conditional_ptr& conditional, conditionals_)
|
BOOST_REVERSE_FOREACH(const conditional_ptr& conditional, this->conditionals_)
|
||||||
cout << " " << conditional->key();
|
cout << " " << conditional->key();
|
||||||
if (!separator_.empty()) {
|
if (!separator_.empty()) {
|
||||||
cout << " :";
|
cout << " :";
|
||||||
|
@ -34,14 +34,10 @@ namespace gtsam {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
template<class Conditional>
|
template<class Conditional>
|
||||||
bool Front<Conditional>::equals(const Front<Conditional>& other, double tol) const {
|
void BayesTree<Conditional>::Node::printTree(const string& indent) const {
|
||||||
return equal(conditionals_.begin(),conditionals_.end(),other.conditionals_.begin(),equals_star<Conditional>);
|
print(indent);
|
||||||
}
|
BOOST_FOREACH(shared_ptr child, children_)
|
||||||
|
child->printTree(indent+" ");
|
||||||
/* ************************************************************************* */
|
|
||||||
template<class Conditional>
|
|
||||||
void Front<Conditional>::add(const conditional_ptr& conditional) {
|
|
||||||
conditionals_.push_front(conditional);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -104,12 +100,13 @@ namespace gtsam {
|
||||||
"BayesTree::insert('"+key+"'): parent '" + parent + "' was not yet inserted"));
|
"BayesTree::insert('"+key+"'): parent '" + parent + "' was not yet inserted"));
|
||||||
int index = it->second;
|
int index = it->second;
|
||||||
node_ptr parent_clique = nodes_[index];
|
node_ptr parent_clique = nodes_[index];
|
||||||
|
if (verbose) cout << "Parent clique " << index << " of size " << parent_clique->size() << endl;
|
||||||
|
|
||||||
// if the parents and parent clique have the same size, add to parent clique
|
// if the parents and parent clique have the same size, add to parent clique
|
||||||
if (parent_clique->size() == parents.size()) {
|
if (parent_clique->size() == parents.size()) {
|
||||||
if (verbose) cout << "Adding to clique " << index << endl;
|
if (verbose) cout << "Adding to clique " << index << endl;
|
||||||
nodeMap_.insert(make_pair(key, index));
|
nodeMap_.insert(make_pair(key, index));
|
||||||
parent_clique->add(conditional);
|
parent_clique->push_back(conditional);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -13,36 +13,12 @@
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <boost/serialization/map.hpp>
|
#include <boost/serialization/map.hpp>
|
||||||
#include <boost/serialization/list.hpp>
|
#include <boost/serialization/list.hpp>
|
||||||
|
|
||||||
#include "Testable.h"
|
#include "Testable.h"
|
||||||
#include "BayesNet.h"
|
#include "BayesNet.h"
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
/** A clique in a Bayes tree consisting of frontal nodes and conditionals */
|
|
||||||
template<class Conditional>
|
|
||||||
class Front: Testable<Front<Conditional> > {
|
|
||||||
private:
|
|
||||||
typedef boost::shared_ptr<Conditional> conditional_ptr;
|
|
||||||
std::list<conditional_ptr> conditionals_; /** conditionals */
|
|
||||||
std::list<std::string> separator_; /** separator keys */
|
|
||||||
public:
|
|
||||||
|
|
||||||
/** constructor */
|
|
||||||
Front(const conditional_ptr& conditional);
|
|
||||||
|
|
||||||
/** print */
|
|
||||||
void print(const std::string& s = "") const;
|
|
||||||
|
|
||||||
/** check equality */
|
|
||||||
bool equals(const Front<Conditional>& other, double tol = 1e-9) const;
|
|
||||||
|
|
||||||
/** add a frontal node */
|
|
||||||
void add(const conditional_ptr& conditional);
|
|
||||||
|
|
||||||
/** return size of the clique */
|
|
||||||
inline size_t size() const {return conditionals_.size() + separator_.size();}
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Bayes tree
|
* Bayes tree
|
||||||
* Templated on the Conditional class, the type of node in the underlying Bayes chain.
|
* Templated on the Conditional class, the type of node in the underlying Bayes chain.
|
||||||
|
@ -58,20 +34,27 @@ namespace gtsam {
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
/** A Node in the tree is a Front with tree connectivity */
|
/** A Node in the tree is an incomplete Bayes net: the variables
|
||||||
struct Node : public Front<Conditional> {
|
* in the Bayes net are the frontal nodes, and the variables conditioned
|
||||||
|
* on is the separator. We also have pointers up and down the tree.
|
||||||
|
*/
|
||||||
|
struct Node : public BayesNet<Conditional> {
|
||||||
typedef boost::shared_ptr<Node> shared_ptr;
|
typedef boost::shared_ptr<Node> shared_ptr;
|
||||||
shared_ptr parent_;
|
shared_ptr parent_;
|
||||||
|
std::list<std::string> separator_; /** separator keys */
|
||||||
std::list<shared_ptr> children_;
|
std::list<shared_ptr> children_;
|
||||||
|
|
||||||
Node(const boost::shared_ptr<Conditional>& conditional):Front<Conditional>(conditional) {}
|
//* Constructor */
|
||||||
|
Node(const boost::shared_ptr<Conditional>& conditional);
|
||||||
|
|
||||||
|
/** The size *includes* the separator */
|
||||||
|
size_t size() const { return this->conditionals_.size() + separator_.size(); }
|
||||||
|
|
||||||
|
/** print this node */
|
||||||
|
void print(const std::string& s="Bayes tree node") const;
|
||||||
|
|
||||||
/** print this node and entire subtree below it*/
|
/** print this node and entire subtree below it*/
|
||||||
void printTree(const std::string& indent) const {
|
void printTree(const std::string& indent) const;
|
||||||
print(indent);
|
|
||||||
BOOST_FOREACH(shared_ptr child, children_)
|
|
||||||
child->printTree(indent+" ");
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/** vector of Nodes */
|
/** vector of Nodes */
|
||||||
|
@ -107,7 +90,7 @@ namespace gtsam {
|
||||||
inline size_t size() const { return nodes_.size();}
|
inline size_t size() const { return nodes_.size();}
|
||||||
|
|
||||||
/** return root clique */
|
/** return root clique */
|
||||||
const Front<Conditional>& root() const {return *(nodes_[0]);}
|
const BayesNet<Conditional>& root() const {return *(nodes_[0]);}
|
||||||
|
|
||||||
}; // BayesTree
|
}; // BayesTree
|
||||||
|
|
||||||
|
|
|
@ -79,12 +79,12 @@ GaussianBayesNet::shared_ptr ConstrainedLinearFactorGraph::eliminate(const Order
|
||||||
if (is_constrained(key))
|
if (is_constrained(key))
|
||||||
{
|
{
|
||||||
ConditionalGaussian::shared_ptr ccg = eliminate_constraint(key);
|
ConditionalGaussian::shared_ptr ccg = eliminate_constraint(key);
|
||||||
cbn->insert(ccg);
|
cbn->push_back(ccg);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
ConditionalGaussian::shared_ptr cg = eliminateOne<ConditionalGaussian>(key);
|
ConditionalGaussian::shared_ptr cg = eliminateOne<ConditionalGaussian>(key);
|
||||||
cbn->insert(cg);
|
cbn->push_back(cg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -63,7 +63,7 @@ LinearFactorGraph::eliminate_partially(const Ordering& ordering)
|
||||||
|
|
||||||
BOOST_FOREACH(string key, ordering) {
|
BOOST_FOREACH(string key, ordering) {
|
||||||
ConditionalGaussian::shared_ptr cg = eliminateOne<ConditionalGaussian>(key);
|
ConditionalGaussian::shared_ptr cg = eliminateOne<ConditionalGaussian>(key);
|
||||||
chordalBayesNet->insert(cg);
|
chordalBayesNet->push_back(cg);
|
||||||
}
|
}
|
||||||
|
|
||||||
return chordalBayesNet;
|
return chordalBayesNet;
|
||||||
|
|
|
@ -26,7 +26,7 @@ namespace gtsam {
|
||||||
|
|
||||||
BOOST_FOREACH(string key, ordering) {
|
BOOST_FOREACH(string key, ordering) {
|
||||||
SymbolicConditional::shared_ptr conditional = eliminateOne<SymbolicConditional>(key);
|
SymbolicConditional::shared_ptr conditional = eliminateOne<SymbolicConditional>(key);
|
||||||
bayesNet->insert(conditional);
|
bayesNet->push_back(conditional);
|
||||||
}
|
}
|
||||||
|
|
||||||
return bayesNet;
|
return bayesNet;
|
||||||
|
|
|
@ -203,8 +203,8 @@ GaussianBayesNet createSmallGaussianBayesNet()
|
||||||
Px_y(new ConditionalGaussian("x",d1,R11,"y",S12)),
|
Px_y(new ConditionalGaussian("x",d1,R11,"y",S12)),
|
||||||
Py(new ConditionalGaussian("y",d2,R22));
|
Py(new ConditionalGaussian("y",d2,R22));
|
||||||
GaussianBayesNet cbn;
|
GaussianBayesNet cbn;
|
||||||
cbn.insert(Px_y);
|
cbn.push_back(Px_y);
|
||||||
cbn.insert(Py);
|
cbn.push_back(Py);
|
||||||
|
|
||||||
return cbn;
|
return cbn;
|
||||||
}
|
}
|
||||||
|
|
|
@ -27,10 +27,12 @@ SymbolicConditional::shared_ptr B(new SymbolicConditional("B")), L(
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
TEST( BayesTree, Front )
|
TEST( BayesTree, Front )
|
||||||
{
|
{
|
||||||
Front<SymbolicConditional> f1(B);
|
BayesNet<SymbolicConditional> f1;
|
||||||
f1.add(L);
|
f1.push_back(B);
|
||||||
Front<SymbolicConditional> f2(L);
|
f1.push_back(L);
|
||||||
f2.add(B);
|
BayesNet<SymbolicConditional> f2;
|
||||||
|
f2.push_back(L);
|
||||||
|
f2.push_back(B);
|
||||||
CHECK(f1.equals(f1));
|
CHECK(f1.equals(f1));
|
||||||
CHECK(!f1.equals(f2));
|
CHECK(!f1.equals(f2));
|
||||||
}
|
}
|
||||||
|
@ -51,21 +53,24 @@ TEST( BayesTree, constructor )
|
||||||
LONGS_EQUAL(4,bayesTree.size());
|
LONGS_EQUAL(4,bayesTree.size());
|
||||||
|
|
||||||
// Check root
|
// Check root
|
||||||
Front<SymbolicConditional> expected_root(B);
|
BayesNet<SymbolicConditional> expected_root;
|
||||||
expected_root.add(L);
|
expected_root.push_back(B);
|
||||||
expected_root.add(E);
|
expected_root.push_back(L);
|
||||||
Front<SymbolicConditional> actual_root = bayesTree.root();
|
expected_root.push_back(E);
|
||||||
|
BayesNet<SymbolicConditional> actual_root = bayesTree.root();
|
||||||
CHECK(assert_equal(expected_root,actual_root));
|
CHECK(assert_equal(expected_root,actual_root));
|
||||||
|
|
||||||
// Create from symbolic Bayes chain in which we want to discover cliques
|
// Create from symbolic Bayes chain in which we want to discover cliques
|
||||||
SymbolicBayesNet ASIA;
|
SymbolicBayesNet ASIA;
|
||||||
ASIA.insert(X);
|
ASIA.push_back(X);
|
||||||
ASIA.insert(T);
|
ASIA.push_back(T);
|
||||||
ASIA.insert(S);
|
ASIA.push_back(S);
|
||||||
ASIA.insert(E);
|
ASIA.push_back(E);
|
||||||
ASIA.insert(L);
|
ASIA.push_back(L);
|
||||||
ASIA.insert(B);
|
ASIA.push_back(B);
|
||||||
BayesTree<SymbolicConditional> bayesTree2(ASIA);
|
bool verbose = true;
|
||||||
|
BayesTree<SymbolicConditional> bayesTree2(ASIA,verbose);
|
||||||
|
if (verbose) bayesTree2.print("bayesTree2");
|
||||||
|
|
||||||
// Check whether the same
|
// Check whether the same
|
||||||
CHECK(assert_equal(bayesTree,bayesTree2));
|
CHECK(assert_equal(bayesTree,bayesTree2));
|
||||||
|
|
|
@ -276,9 +276,9 @@ TEST( LinearFactorGraph, eliminateAll )
|
||||||
ConditionalGaussian::shared_ptr cg3(new ConditionalGaussian("x2",d3, R3, "l1", A21, "x1", A22));
|
ConditionalGaussian::shared_ptr cg3(new ConditionalGaussian("x2",d3, R3, "l1", A21, "x1", A22));
|
||||||
|
|
||||||
GaussianBayesNet expected;
|
GaussianBayesNet expected;
|
||||||
expected.insert(cg3);
|
expected.push_back(cg3);
|
||||||
expected.insert(cg2);
|
expected.push_back(cg2);
|
||||||
expected.insert(cg1);
|
expected.push_back(cg1);
|
||||||
|
|
||||||
// Check one ordering
|
// Check one ordering
|
||||||
LinearFactorGraph fg1 = createLinearFactorGraph();
|
LinearFactorGraph fg1 = createLinearFactorGraph();
|
||||||
|
|
|
@ -27,9 +27,9 @@ TEST( SymbolicBayesNet, constructor )
|
||||||
l1(new SymbolicConditional("l1","x1")),
|
l1(new SymbolicConditional("l1","x1")),
|
||||||
x1(new SymbolicConditional("x1"));
|
x1(new SymbolicConditional("x1"));
|
||||||
SymbolicBayesNet expected;
|
SymbolicBayesNet expected;
|
||||||
expected.insert(x2);
|
expected.push_back(x2);
|
||||||
expected.insert(l1);
|
expected.push_back(l1);
|
||||||
expected.insert(x1);
|
expected.push_back(x1);
|
||||||
|
|
||||||
// Create from a factor graph
|
// Create from a factor graph
|
||||||
LinearFactorGraph factorGraph = createLinearFactorGraph();
|
LinearFactorGraph factorGraph = createLinearFactorGraph();
|
||||||
|
|
|
@ -129,9 +129,9 @@ TEST( LinearFactorGraph, eliminate )
|
||||||
SymbolicConditional::shared_ptr x1(new SymbolicConditional("x1"));
|
SymbolicConditional::shared_ptr x1(new SymbolicConditional("x1"));
|
||||||
|
|
||||||
SymbolicBayesNet expected;
|
SymbolicBayesNet expected;
|
||||||
expected.insert(x2);
|
expected.push_back(x2);
|
||||||
expected.insert(l1);
|
expected.push_back(l1);
|
||||||
expected.insert(x1);
|
expected.push_back(x1);
|
||||||
|
|
||||||
// create a test graph
|
// create a test graph
|
||||||
LinearFactorGraph factorGraph = createLinearFactorGraph();
|
LinearFactorGraph factorGraph = createLinearFactorGraph();
|
||||||
|
|
Loading…
Reference in New Issue