Fixed computing shortcuts in BayesTree
parent
84d6b5be6a
commit
45456aab8e
404
.cproject
404
.cproject
|
@ -322,14 +322,6 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianFactor.run" path="linear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -356,6 +348,7 @@
|
|||
</target>
|
||||
<target name="tests/testBayesTree.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testBayesTree.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -363,6 +356,7 @@
|
|||
</target>
|
||||
<target name="testBinaryBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testBinaryBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -410,6 +404,7 @@
|
|||
</target>
|
||||
<target name="testSymbolicBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -417,6 +412,7 @@
|
|||
</target>
|
||||
<target name="tests/testSymbolicFactor.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testSymbolicFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -424,6 +420,7 @@
|
|||
</target>
|
||||
<target name="testSymbolicFactorGraph.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -439,11 +436,20 @@
|
|||
</target>
|
||||
<target name="tests/testBayesTree" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testBayesTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianFactor.run" path="linear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -478,7 +484,6 @@
|
|||
</target>
|
||||
<target name="testGraph.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -574,7 +579,6 @@
|
|||
</target>
|
||||
<target name="testInference.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testInference.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -582,7 +586,6 @@
|
|||
</target>
|
||||
<target name="testGaussianBayesNet.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -590,7 +593,6 @@
|
|||
</target>
|
||||
<target name="testGaussianFactor.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -598,7 +600,6 @@
|
|||
</target>
|
||||
<target name="testJunctionTree.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testJunctionTree.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -606,7 +607,6 @@
|
|||
</target>
|
||||
<target name="testSymbolicBayesNet.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -614,7 +614,6 @@
|
|||
</target>
|
||||
<target name="testSymbolicFactorGraph.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -820,6 +819,14 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianISAM.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianISAM.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="SimpleRotation.run" path="examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -918,6 +925,7 @@
|
|||
</target>
|
||||
<target name="testErrors.run" path="linear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testErrors.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1253,7 +1261,6 @@
|
|||
</target>
|
||||
<target name="testSimulated2DOriented.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated2DOriented.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1293,7 +1300,6 @@
|
|||
</target>
|
||||
<target name="testSimulated2D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated2D.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1301,7 +1307,6 @@
|
|||
</target>
|
||||
<target name="testSimulated3D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated3D.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1349,7 +1354,6 @@
|
|||
</target>
|
||||
<target name="tests/testGaussianISAM2" path="build/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1371,6 +1375,86 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>install</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>clean</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>check</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>all</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="dist" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>dist</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testEliminationTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testEliminationTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="slam/tests/testGaussianISAM2" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>slam/tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testVariableIndex" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testVariableIndex</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="linear/tests/testGaussianJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>linear/tests/testGaussianJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testRot3.run" path="geometry" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -1467,86 +1551,6 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>install</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>clean</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>check</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>all</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="dist" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>dist</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testEliminationTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testEliminationTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="slam/tests/testGaussianISAM2" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>slam/tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testVariableIndex" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testVariableIndex</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="linear/tests/testGaussianJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>linear/tests/testGaussianJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="build" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -1901,14 +1905,6 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianFactor.run" path="linear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -1935,6 +1931,7 @@
|
|||
</target>
|
||||
<target name="tests/testBayesTree.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testBayesTree.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1942,6 +1939,7 @@
|
|||
</target>
|
||||
<target name="testBinaryBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testBinaryBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1989,6 +1987,7 @@
|
|||
</target>
|
||||
<target name="testSymbolicBayesNet.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -1996,6 +1995,7 @@
|
|||
</target>
|
||||
<target name="tests/testSymbolicFactor.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testSymbolicFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2003,6 +2003,7 @@
|
|||
</target>
|
||||
<target name="testSymbolicFactorGraph.run" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2018,11 +2019,20 @@
|
|||
</target>
|
||||
<target name="tests/testBayesTree" path="inference" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testBayesTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianFactor.run" path="linear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -2057,7 +2067,6 @@
|
|||
</target>
|
||||
<target name="testGraph.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2153,7 +2162,6 @@
|
|||
</target>
|
||||
<target name="testInference.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testInference.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2161,7 +2169,6 @@
|
|||
</target>
|
||||
<target name="testGaussianBayesNet.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2169,7 +2176,6 @@
|
|||
</target>
|
||||
<target name="testGaussianFactor.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianFactor.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2177,7 +2183,6 @@
|
|||
</target>
|
||||
<target name="testJunctionTree.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testJunctionTree.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2185,7 +2190,6 @@
|
|||
</target>
|
||||
<target name="testSymbolicBayesNet.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicBayesNet.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2193,7 +2197,6 @@
|
|||
</target>
|
||||
<target name="testSymbolicFactorGraph.run" path="tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSymbolicFactorGraph.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2399,6 +2402,14 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testGaussianISAM.run" path="build/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testGaussianISAM.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="SimpleRotation.run" path="examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -2497,6 +2508,7 @@
|
|||
</target>
|
||||
<target name="testErrors.run" path="linear" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testErrors.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2832,7 +2844,6 @@
|
|||
</target>
|
||||
<target name="testSimulated2DOriented.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated2DOriented.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2872,7 +2883,6 @@
|
|||
</target>
|
||||
<target name="testSimulated2D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated2D.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2880,7 +2890,6 @@
|
|||
</target>
|
||||
<target name="testSimulated3D.run" path="slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>testSimulated3D.run</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2928,7 +2937,6 @@
|
|||
</target>
|
||||
<target name="tests/testGaussianISAM2" path="build/slam" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments/>
|
||||
<buildTarget>tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>false</useDefaultCommand>
|
||||
|
@ -2950,6 +2958,86 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>install</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>clean</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>check</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>all</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="dist" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>dist</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testEliminationTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testEliminationTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="slam/tests/testGaussianISAM2" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>slam/tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testVariableIndex" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testVariableIndex</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="linear/tests/testGaussianJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>linear/tests/testGaussianJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="testRot3.run" path="geometry" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
@ -3046,86 +3134,6 @@
|
|||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="install" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>install</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="clean" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>clean</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>check</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="all" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>all</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="dist" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>dist</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testEliminationTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testEliminationTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="slam/tests/testGaussianISAM2" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>slam/tests/testGaussianISAM2</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testVariableIndex" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testVariableIndex</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="inference/tests/testJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>inference/tests/testJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="linear/tests/testGaussianJunctionTree" path="" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
<buildTarget>linear/tests/testGaussianJunctionTree</buildTarget>
|
||||
<stopOnError>true</stopOnError>
|
||||
<useDefaultCommand>true</useDefaultCommand>
|
||||
<runAllBuilders>true</runAllBuilders>
|
||||
</target>
|
||||
<target name="check" path="build" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||
<buildCommand>make</buildCommand>
|
||||
<buildArguments>-j2</buildArguments>
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
#include <boost/format.hpp>
|
||||
#include <boost/lambda/lambda.hpp>
|
||||
#include <boost/iterator/transform_iterator.hpp>
|
||||
#include <boost/pool/pool_alloc.hpp>
|
||||
#include <fstream>
|
||||
using namespace boost::assign;
|
||||
namespace lam = boost::lambda;
|
||||
|
@ -248,67 +249,85 @@ namespace gtsam {
|
|||
return stats;
|
||||
}
|
||||
|
||||
// /* ************************************************************************* */
|
||||
// // The shortcut density is a conditional P(S|R) of the separator of this
|
||||
// // clique on the root. We can compute it recursively from the parent shortcut
|
||||
// // P(Sp|R) as \int P(Fp|Sp) P(Sp|R), where Fp are the frontal nodes in p
|
||||
// // TODO, why do we actually return a shared pointer, why does eliminate?
|
||||
// /* ************************************************************************* */
|
||||
// template<class Conditional>
|
||||
// template<class Factor>
|
||||
// BayesNet<Conditional>
|
||||
// BayesTree<Conditional>::Clique::shortcut(shared_ptr R) {
|
||||
// // A first base case is when this clique or its parent is the root,
|
||||
// // in which case we return an empty Bayes net.
|
||||
//
|
||||
// if (R.get()==this || parent_==R) {
|
||||
// BayesNet<Conditional> empty;
|
||||
// return empty;
|
||||
// }
|
||||
//
|
||||
// // The parent clique has a Conditional for each frontal node in Fp
|
||||
// // so we can obtain P(Fp|Sp) in factor graph form
|
||||
// FactorGraph<Factor> p_Fp_Sp(*parent_);
|
||||
//
|
||||
// // If not the base case, obtain the parent shortcut P(Sp|R) as factors
|
||||
// FactorGraph<Factor> p_Sp_R(parent_->shortcut<Factor>(R));
|
||||
//
|
||||
// // now combine P(Cp|R) = P(Fp|Sp) * P(Sp|R)
|
||||
// FactorGraph<Factor> p_Cp_R = combine(p_Fp_Sp, p_Sp_R);
|
||||
//
|
||||
// // Eliminate into a Bayes net with ordering designed to integrate out
|
||||
// // any variables not in *our* separator. Variables to integrate out must be
|
||||
// // eliminated first hence the desired ordering is [Cp\S S].
|
||||
// // However, an added wrinkle is that Cp might overlap with the root.
|
||||
// // Keys corresponding to the root should not be added to the ordering at all.
|
||||
//
|
||||
// // Get the key list Cp=Fp+Sp, which will form the basis for the integrands
|
||||
// Ordering integrands = parent_->keys();
|
||||
//
|
||||
// // Start ordering with the separator
|
||||
// Ordering ordering = separator_;
|
||||
//
|
||||
// // remove any variables in the root, after this integrands = Cp\R, ordering = S\R
|
||||
// BOOST_FOREACH(varid_t key, R->ordering()) {
|
||||
// integrands.remove(key);
|
||||
// ordering.remove(key);
|
||||
// }
|
||||
//
|
||||
// // remove any variables in the separator, after this integrands = Cp\R\S
|
||||
// BOOST_FOREACH(varid_t key, separator_) integrands.remove(key);
|
||||
//
|
||||
// // form the ordering as [Cp\R\S S\R]
|
||||
// BOOST_REVERSE_FOREACH(varid_t key, integrands) ordering.push_front(key);
|
||||
//
|
||||
// // eliminate to get marginal
|
||||
// BayesNet<Conditional> p_S_R = eliminate<Factor,Conditional>(p_Cp_R,ordering);
|
||||
//
|
||||
// // remove all integrands
|
||||
// BOOST_FOREACH(varid_t key, integrands) p_S_R.pop_front();
|
||||
//
|
||||
// // return the parent shortcut P(Sp|R)
|
||||
// return p_S_R;
|
||||
// }
|
||||
/* ************************************************************************* */
|
||||
// The shortcut density is a conditional P(S|R) of the separator of this
|
||||
// clique on the root. We can compute it recursively from the parent shortcut
|
||||
// P(Sp|R) as \int P(Fp|Sp) P(Sp|R), where Fp are the frontal nodes in p
|
||||
// TODO, why do we actually return a shared pointer, why does eliminate?
|
||||
/* ************************************************************************* */
|
||||
template<class Conditional>
|
||||
template<class FactorGraph>
|
||||
BayesNet<Conditional>
|
||||
BayesTree<Conditional>::Clique::shortcut(shared_ptr R) {
|
||||
// A first base case is when this clique or its parent is the root,
|
||||
// in which case we return an empty Bayes net.
|
||||
|
||||
sharedClique parent(parent_.lock());
|
||||
|
||||
if (R.get()==this || parent==R) {
|
||||
BayesNet<Conditional> empty;
|
||||
return empty;
|
||||
}
|
||||
|
||||
// The parent clique has a Conditional for each frontal node in Fp
|
||||
// so we can obtain P(Fp|Sp) in factor graph form
|
||||
FactorGraph p_Fp_Sp(*parent);
|
||||
|
||||
// If not the base case, obtain the parent shortcut P(Sp|R) as factors
|
||||
FactorGraph p_Sp_R(parent->shortcut<FactorGraph>(R));
|
||||
|
||||
// now combine P(Cp|R) = P(Fp|Sp) * P(Sp|R)
|
||||
FactorGraph p_Cp_R = combine(p_Fp_Sp, p_Sp_R);
|
||||
|
||||
// Eliminate into a Bayes net with ordering designed to integrate out
|
||||
// any variables not in *our* separator. Variables to integrate out must be
|
||||
// eliminated first hence the desired ordering is [Cp\S S].
|
||||
// However, an added wrinkle is that Cp might overlap with the root.
|
||||
// Keys corresponding to the root should not be added to the ordering at all.
|
||||
|
||||
typedef set<varid_t, std::less<varid_t>, boost::fast_pool_allocator<varid_t> > FastJSet;
|
||||
|
||||
// Get the key list Cp=Fp+Sp, which will form the basis for the integrands
|
||||
vector<varid_t> parentKeys(parent->keys());
|
||||
FastJSet integrands(parentKeys.begin(), parentKeys.end());
|
||||
|
||||
// Start ordering with the separator
|
||||
FastJSet separator(separator_.begin(), separator_.end());
|
||||
|
||||
// remove any variables in the root, after this integrands = Cp\R, ordering = S\R
|
||||
BOOST_FOREACH(varid_t key, R->ordering()) {
|
||||
integrands.erase(key);
|
||||
separator.erase(key);
|
||||
}
|
||||
|
||||
// remove any variables in the separator, after this integrands = Cp\R\S
|
||||
BOOST_FOREACH(varid_t key, separator_) integrands.erase(key);
|
||||
|
||||
// form the ordering as [Cp\R\S S\R]
|
||||
vector<varid_t> ordering; ordering.reserve(integrands.size() + separator.size());
|
||||
BOOST_FOREACH(varid_t key, integrands) ordering.push_back(key);
|
||||
BOOST_FOREACH(varid_t key, separator) ordering.push_back(key);
|
||||
|
||||
// eliminate to get marginal
|
||||
typename FactorGraph::variableindex_type varIndex(p_Cp_R);
|
||||
Permutation toFront = Permutation::PullToFront(ordering, varIndex.size());
|
||||
Permutation::shared_ptr toFrontInverse(toFront.inverse());
|
||||
BOOST_FOREACH(const typename FactorGraph::sharedFactor& factor, p_Cp_R) {
|
||||
factor->permuteWithInverse(*toFrontInverse);
|
||||
}
|
||||
varIndex.permute(toFront);
|
||||
BayesNet<Conditional> p_S_R = *Inference::EliminateUntil(p_Cp_R, ordering.size(), varIndex);
|
||||
|
||||
// remove all integrands
|
||||
for(varid_t j=0; j<integrands.size(); ++j)
|
||||
p_S_R.pop_front();
|
||||
|
||||
// Undo the permutation on the shortcut
|
||||
p_S_R.permuteWithInverse(toFront);
|
||||
|
||||
// return the parent shortcut P(Sp|R)
|
||||
return p_S_R;
|
||||
}
|
||||
|
||||
// /* ************************************************************************* */
|
||||
// // P(C) = \int_R P(F|S) P(S|R) P(R)
|
||||
|
|
|
@ -94,11 +94,11 @@ namespace gtsam {
|
|||
*/
|
||||
bool permuteSeparatorWithInverse(const Permutation& inversePermutation);
|
||||
|
||||
// /** return the conditional P(S|Root) on the separator given the root */
|
||||
// // TODO: create a cached version
|
||||
// template<class Factor>
|
||||
// BayesNet<Conditional> shortcut(shared_ptr root);
|
||||
//
|
||||
/** return the conditional P(S|Root) on the separator given the root */
|
||||
// TODO: create a cached version
|
||||
template<class FactorGraph>
|
||||
BayesNet<Conditional> shortcut(shared_ptr root);
|
||||
|
||||
// /** return the marginal P(C) of the clique */
|
||||
// template<class Factor>
|
||||
// FactorGraph<Factor> marginal(shared_ptr root);
|
||||
|
|
|
@ -359,11 +359,10 @@ namespace gtsam {
|
|||
// }
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class Factor>
|
||||
FactorGraph<Factor> combine(const FactorGraph<Factor>& fg1,
|
||||
const FactorGraph<Factor>& fg2) {
|
||||
template<class FactorGraph>
|
||||
FactorGraph combine(const FactorGraph& fg1, const FactorGraph& fg2) {
|
||||
// create new linear factor graph equal to the first one
|
||||
FactorGraph<Factor> fg = fg1;
|
||||
FactorGraph fg = fg1;
|
||||
|
||||
// add the second factors_ in the graph
|
||||
fg.push_back(fg2);
|
||||
|
|
|
@ -188,8 +188,8 @@ namespace gtsam {
|
|||
* @param const &fg2 Linear factor graph
|
||||
* @return a new combined factor graph
|
||||
*/
|
||||
template<class Factor>
|
||||
FactorGraph<Factor> combine(const FactorGraph<Factor>& fg1, const FactorGraph<Factor>& fg2);
|
||||
template<class FactorGraph>
|
||||
FactorGraph combine(const FactorGraph& fg1, const FactorGraph& fg2);
|
||||
|
||||
// /**
|
||||
// * Extract and combine all the factors that involve a given node
|
||||
|
@ -214,7 +214,10 @@ namespace gtsam {
|
|||
FactorGraph<Factor>::FactorGraph(const Derived& factorGraph) {
|
||||
factors_.reserve(factorGraph.size());
|
||||
BOOST_FOREACH(const typename Derived::sharedFactor& factor, factorGraph) {
|
||||
this->push_back(factor);
|
||||
if(factor)
|
||||
this->push_back(sharedFactor(new Factor(*factor)));
|
||||
else
|
||||
this->push_back(sharedFactor());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -24,9 +24,8 @@ check_PROGRAMS += tests/testVariableIndex tests/testVariableSlots
|
|||
|
||||
# Inference
|
||||
headers += inference-inl.h VariableSlots-inl.h
|
||||
sources += inference.cpp VariableSlots.cpp
|
||||
sources += inference.cpp VariableSlots.cpp Permutation.cpp
|
||||
headers += graph.h graph-inl.h
|
||||
headers += Permutation.h
|
||||
headers += VariableIndex.h
|
||||
headers += FactorGraph.h FactorGraph-inl.h
|
||||
headers += ClusterTree.h ClusterTree-inl.h
|
||||
|
|
|
@ -0,0 +1,88 @@
|
|||
/**
|
||||
* @file Permutation.cpp
|
||||
* @brief
|
||||
* @author Richard Roberts
|
||||
* @created Oct 9, 2010
|
||||
*/
|
||||
|
||||
#include <gtsam/inference/Permutation.h>
|
||||
|
||||
#include <iostream>
|
||||
#include <boost/foreach.hpp>
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
Permutation Permutation::Identity(varid_t nVars) {
|
||||
Permutation ret(nVars);
|
||||
for(varid_t i=0; i<nVars; ++i)
|
||||
ret[i] = i;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Permutation Permutation::PullToFront(const vector<varid_t>& toFront, size_t size) {
|
||||
|
||||
Permutation ret(size);
|
||||
|
||||
// Mask of which variables have been pulled, used to reorder
|
||||
vector<bool> pulled(size, false);
|
||||
|
||||
for(varid_t j=0; j<toFront.size(); ++j) {
|
||||
ret[j] = toFront[j];
|
||||
pulled[toFront[j]] = true;
|
||||
assert(toFront[j] < size);
|
||||
}
|
||||
|
||||
varid_t nextVar = toFront.size();
|
||||
for(varid_t j=0; j<size; ++j)
|
||||
if(!pulled[j])
|
||||
ret[nextVar++] = j;
|
||||
assert(nextVar == size);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Permutation::shared_ptr Permutation::permute(const Permutation& permutation) const {
|
||||
const size_t nVars = permutation.size();
|
||||
Permutation::shared_ptr result(new Permutation(nVars));
|
||||
for(size_t j=0; j<nVars; ++j) {
|
||||
assert(permutation[j] < rangeIndices_.size());
|
||||
(*result)[j] = operator[](permutation[j]);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Permutation::shared_ptr Permutation::partialPermutation(
|
||||
const Permutation& selector, const Permutation& partialPermutation) const {
|
||||
assert(selector.size() == partialPermutation.size());
|
||||
Permutation::shared_ptr result(new Permutation(*this));
|
||||
|
||||
for(varid_t subsetPos=0; subsetPos<selector.size(); ++subsetPos)
|
||||
(*result)[selector[subsetPos]] = (*this)[selector[partialPermutation[subsetPos]]];
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
Permutation::shared_ptr Permutation::inverse() const {
|
||||
Permutation::shared_ptr result(new Permutation(this->size()));
|
||||
for(varid_t i=0; i<this->size(); ++i) {
|
||||
assert((*this)[i] < this->size());
|
||||
(*result)[(*this)[i]] = i;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Permutation::print(const std::string& str) const {
|
||||
std::cout << str;
|
||||
BOOST_FOREACH(varid_t s, rangeIndices_) { std::cout << s << " "; }
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
}
|
|
@ -10,7 +10,7 @@
|
|||
#include <gtsam/base/types.h>
|
||||
|
||||
#include <vector>
|
||||
#include <iostream>
|
||||
#include <string>
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -81,6 +81,12 @@ public:
|
|||
*/
|
||||
static Permutation Identity(varid_t nVars);
|
||||
|
||||
/**
|
||||
* Create a permutation that pulls the given variables to the front while
|
||||
* pushing the rest to the back.
|
||||
*/
|
||||
static Permutation PullToFront(const std::vector<varid_t>& toFront, size_t size);
|
||||
|
||||
iterator begin() { return rangeIndices_.begin(); }
|
||||
const_iterator begin() const { return rangeIndices_.begin(); }
|
||||
iterator end() { return rangeIndices_.end(); }
|
||||
|
@ -180,52 +186,4 @@ public:
|
|||
};
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
inline Permutation Permutation::Identity(varid_t nVars) {
|
||||
Permutation ret(nVars);
|
||||
for(varid_t i=0; i<nVars; ++i)
|
||||
ret[i] = i;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
inline Permutation::shared_ptr Permutation::permute(const Permutation& permutation) const {
|
||||
const size_t nVars = permutation.size();
|
||||
Permutation::shared_ptr result(new Permutation(nVars));
|
||||
for(size_t j=0; j<nVars; ++j) {
|
||||
assert(permutation[j] < rangeIndices_.size());
|
||||
(*result)[j] = operator[](permutation[j]);
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
inline Permutation::shared_ptr Permutation::partialPermutation(
|
||||
const Permutation& selector, const Permutation& partialPermutation) const {
|
||||
assert(selector.size() == partialPermutation.size());
|
||||
Permutation::shared_ptr result(new Permutation(*this));
|
||||
|
||||
for(varid_t subsetPos=0; subsetPos<selector.size(); ++subsetPos)
|
||||
(*result)[selector[subsetPos]] = (*this)[selector[partialPermutation[subsetPos]]];
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
inline Permutation::shared_ptr Permutation::inverse() const {
|
||||
Permutation::shared_ptr result(new Permutation(this->size()));
|
||||
for(varid_t i=0; i<this->size(); ++i) {
|
||||
assert((*this)[i] < this->size());
|
||||
(*result)[(*this)[i]] = i;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
inline void Permutation::print(const std::string& str) const {
|
||||
std::cout << str;
|
||||
BOOST_FOREACH(varid_t s, rangeIndices_) { std::cout << s << " "; }
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -93,51 +93,50 @@ C3 x4 : x5
|
|||
C4 x3 : x4
|
||||
C5 x2 : x3
|
||||
C6 x1 : x2
|
||||
/* ************************************************************************* */
|
||||
// SL-FIX TEST( BayesTree, linear_smoother_shortcuts )
|
||||
//{
|
||||
// // Create smoother with 7 nodes
|
||||
// GaussianFactorGraph smoother = createSmoother(7);
|
||||
// Ordering ordering;
|
||||
// for (int t = 1; t <= 7; t++)
|
||||
// ordering.push_back(symbol('x', t));
|
||||
//
|
||||
// // eliminate using the "natural" ordering
|
||||
// GaussianBayesNet chordalBayesNet = smoother.eliminate(ordering);
|
||||
//
|
||||
// // Create the Bayes tree
|
||||
// GaussianISAM bayesTree(chordalBayesNet);
|
||||
// LONGS_EQUAL(6,bayesTree.size());
|
||||
//
|
||||
// // Check the conditional P(Root|Root)
|
||||
// GaussianBayesNet empty;
|
||||
// GaussianISAM::sharedClique R = bayesTree.root();
|
||||
// GaussianBayesNet actual1 = R->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(empty,actual1,tol));
|
||||
//
|
||||
// // Check the conditional P(C2|Root)
|
||||
// GaussianISAM::sharedClique C2 = bayesTree["x5"];
|
||||
// GaussianBayesNet actual2 = C2->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(empty,actual2,tol));
|
||||
//
|
||||
// // Check the conditional P(C3|Root)
|
||||
// double sigma3 = 0.61808;
|
||||
// Matrix A56 = Matrix_(2,2,-0.382022,0.,0.,-0.382022);
|
||||
// GaussianBayesNet expected3;
|
||||
// push_front(expected3,"x5", zero(2), eye(2)/sigma3, "x6", A56/sigma3, ones(2));
|
||||
// GaussianISAM::sharedClique C3 = bayesTree["x4"];
|
||||
// GaussianBayesNet actual3 = C3->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(expected3,actual3,tol));
|
||||
//
|
||||
// // Check the conditional P(C4|Root)
|
||||
// double sigma4 = 0.661968;
|
||||
// Matrix A46 = Matrix_(2,2,-0.146067,0.,0.,-0.146067);
|
||||
// GaussianBayesNet expected4;
|
||||
// push_front(expected4,"x4", zero(2), eye(2)/sigma4, "x6", A46/sigma4, ones(2));
|
||||
// GaussianISAM::sharedClique C4 = bayesTree["x3"];
|
||||
// GaussianBayesNet actual4 = C4->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(expected4,actual4,tol));
|
||||
//}
|
||||
**************************************************************************** */
|
||||
TEST( BayesTree, linear_smoother_shortcuts )
|
||||
{
|
||||
// Create smoother with 7 nodes
|
||||
Ordering ordering;
|
||||
GaussianFactorGraph smoother;
|
||||
boost::tie(smoother, ordering) = createSmoother(7);
|
||||
|
||||
// eliminate using the "natural" ordering
|
||||
GaussianBayesNet chordalBayesNet = *Inference::Eliminate(smoother);
|
||||
|
||||
// Create the Bayes tree
|
||||
GaussianISAM bayesTree(chordalBayesNet);
|
||||
LONGS_EQUAL(6,bayesTree.size());
|
||||
|
||||
// Check the conditional P(Root|Root)
|
||||
GaussianBayesNet empty;
|
||||
GaussianISAM::sharedClique R = bayesTree.root();
|
||||
GaussianBayesNet actual1 = R->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(empty,actual1,tol));
|
||||
|
||||
// Check the conditional P(C2|Root)
|
||||
GaussianISAM::sharedClique C2 = bayesTree[ordering["x5"]];
|
||||
GaussianBayesNet actual2 = C2->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(empty,actual2,tol));
|
||||
|
||||
// Check the conditional P(C3|Root)
|
||||
double sigma3 = 0.61808;
|
||||
Matrix A56 = Matrix_(2,2,-0.382022,0.,0.,-0.382022);
|
||||
GaussianBayesNet expected3;
|
||||
push_front(expected3,ordering["x5"], zero(2), eye(2)/sigma3, ordering["x6"], A56/sigma3, ones(2));
|
||||
GaussianISAM::sharedClique C3 = bayesTree[ordering["x4"]];
|
||||
GaussianBayesNet actual3 = C3->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(expected3,actual3,tol));
|
||||
|
||||
// Check the conditional P(C4|Root)
|
||||
double sigma4 = 0.661968;
|
||||
Matrix A46 = Matrix_(2,2,-0.146067,0.,0.,-0.146067);
|
||||
GaussianBayesNet expected4;
|
||||
push_front(expected4, ordering["x4"], zero(2), eye(2)/sigma4, ordering["x6"], A46/sigma4, ones(2));
|
||||
GaussianISAM::sharedClique C4 = bayesTree[ordering["x3"]];
|
||||
GaussianBayesNet actual4 = C4->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(expected4,actual4,tol));
|
||||
}
|
||||
|
||||
/* ************************************************************************* *
|
||||
Bayes tree for smoother with "nested dissection" ordering:
|
||||
|
@ -157,7 +156,7 @@ C6 x1 : x2
|
|||
C3 x1 : x2
|
||||
C4 x7 : x6
|
||||
|
||||
/* ************************************************************************* */
|
||||
************************************************************************* */
|
||||
// SL-FIX TEST( BayesTree, balanced_smoother_marginals )
|
||||
//{
|
||||
// // Create smoother with 7 nodes
|
||||
|
@ -208,35 +207,35 @@ C6 x1 : x2
|
|||
//}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// SL-FIX TEST( BayesTree, balanced_smoother_shortcuts )
|
||||
//{
|
||||
// // Create smoother with 7 nodes
|
||||
// GaussianFactorGraph smoother = createSmoother(7);
|
||||
// Ordering ordering;
|
||||
// ordering += "x1","x3","x5","x7","x2","x6","x4";
|
||||
//
|
||||
// // Create the Bayes tree
|
||||
// GaussianBayesNet chordalBayesNet = smoother.eliminate(ordering);
|
||||
// GaussianISAM bayesTree(chordalBayesNet);
|
||||
//
|
||||
// // Check the conditional P(Root|Root)
|
||||
// GaussianBayesNet empty;
|
||||
// GaussianISAM::sharedClique R = bayesTree.root();
|
||||
// GaussianBayesNet actual1 = R->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(empty,actual1,tol));
|
||||
//
|
||||
// // Check the conditional P(C2|Root)
|
||||
// GaussianISAM::sharedClique C2 = bayesTree["x3"];
|
||||
// GaussianBayesNet actual2 = C2->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(empty,actual2,tol));
|
||||
//
|
||||
// // Check the conditional P(C3|Root), which should be equal to P(x2|x4)
|
||||
// GaussianConditional::shared_ptr p_x2_x4 = chordalBayesNet["x2"];
|
||||
// GaussianBayesNet expected3; expected3.push_back(p_x2_x4);
|
||||
// GaussianISAM::sharedClique C3 = bayesTree["x1"];
|
||||
// GaussianBayesNet actual3 = C3->shortcut<GaussianFactor>(R);
|
||||
// CHECK(assert_equal(expected3,actual3,tol));
|
||||
//}
|
||||
TEST( BayesTree, balanced_smoother_shortcuts )
|
||||
{
|
||||
// Create smoother with 7 nodes
|
||||
Ordering ordering;
|
||||
ordering += "x1","x3","x5","x7","x2","x6","x4";
|
||||
GaussianFactorGraph smoother = createSmoother(7, ordering).first;
|
||||
|
||||
// Create the Bayes tree
|
||||
GaussianBayesNet chordalBayesNet = *Inference::Eliminate(smoother);
|
||||
GaussianISAM bayesTree(chordalBayesNet);
|
||||
|
||||
// Check the conditional P(Root|Root)
|
||||
GaussianBayesNet empty;
|
||||
GaussianISAM::sharedClique R = bayesTree.root();
|
||||
GaussianBayesNet actual1 = R->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(empty,actual1,tol));
|
||||
|
||||
// Check the conditional P(C2|Root)
|
||||
GaussianISAM::sharedClique C2 = bayesTree[ordering["x3"]];
|
||||
GaussianBayesNet actual2 = C2->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(empty,actual2,tol));
|
||||
|
||||
// Check the conditional P(C3|Root), which should be equal to P(x2|x4)
|
||||
GaussianConditional::shared_ptr p_x2_x4 = chordalBayesNet[ordering["x2"]];
|
||||
GaussianBayesNet expected3; expected3.push_back(p_x2_x4);
|
||||
GaussianISAM::sharedClique C3 = bayesTree[ordering["x1"]];
|
||||
GaussianBayesNet actual3 = C3->shortcut<GaussianFactorGraph>(R);
|
||||
CHECK(assert_equal(expected3,actual3,tol));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// SL-FIX TEST( BayesTree, balanced_smoother_clique_marginals )
|
||||
|
|
Loading…
Reference in New Issue