Wrapper and tests for logProbability
parent
eb37d080d4
commit
87ff4af32d
|
|
@ -95,6 +95,9 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor {
|
||||||
DiscreteConditional(const gtsam::DecisionTreeFactor& joint,
|
DiscreteConditional(const gtsam::DecisionTreeFactor& joint,
|
||||||
const gtsam::DecisionTreeFactor& marginal,
|
const gtsam::DecisionTreeFactor& marginal,
|
||||||
const gtsam::Ordering& orderedKeys);
|
const gtsam::Ordering& orderedKeys);
|
||||||
|
double logProbability(const gtsam::DiscreteValues& values) const;
|
||||||
|
double evaluate(const gtsam::DiscreteValues& values) const;
|
||||||
|
double operator()(const gtsam::DiscreteValues& values) const;
|
||||||
gtsam::DiscreteConditional operator*(
|
gtsam::DiscreteConditional operator*(
|
||||||
const gtsam::DiscreteConditional& other) const;
|
const gtsam::DiscreteConditional& other) const;
|
||||||
gtsam::DiscreteConditional marginal(gtsam::Key key) const;
|
gtsam::DiscreteConditional marginal(gtsam::Key key) const;
|
||||||
|
|
@ -157,7 +160,12 @@ class DiscreteBayesNet {
|
||||||
const gtsam::KeyFormatter& keyFormatter =
|
const gtsam::KeyFormatter& keyFormatter =
|
||||||
gtsam::DefaultKeyFormatter) const;
|
gtsam::DefaultKeyFormatter) const;
|
||||||
bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const;
|
bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const;
|
||||||
|
|
||||||
|
// Standard interface.
|
||||||
|
double logProbability(const gtsam::DiscreteValues& values) const;
|
||||||
|
double evaluate(const gtsam::DiscreteValues& values) const;
|
||||||
double operator()(const gtsam::DiscreteValues& values) const;
|
double operator()(const gtsam::DiscreteValues& values) const;
|
||||||
|
|
||||||
gtsam::DiscreteValues sample() const;
|
gtsam::DiscreteValues sample() const;
|
||||||
gtsam::DiscreteValues sample(gtsam::DiscreteValues given) const;
|
gtsam::DiscreteValues sample(gtsam::DiscreteValues given) const;
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -61,6 +61,9 @@ virtual class HybridConditional {
|
||||||
size_t nrParents() const;
|
size_t nrParents() const;
|
||||||
|
|
||||||
// Standard interface:
|
// Standard interface:
|
||||||
|
double logProbability(const gtsam::HybridValues& values) const;
|
||||||
|
double evaluate(const gtsam::HybridValues& values) const;
|
||||||
|
double operator()(const gtsam::HybridValues& values) const;
|
||||||
gtsam::GaussianMixture* asMixture() const;
|
gtsam::GaussianMixture* asMixture() const;
|
||||||
gtsam::GaussianConditional* asGaussian() const;
|
gtsam::GaussianConditional* asGaussian() const;
|
||||||
gtsam::DiscreteConditional* asDiscrete() const;
|
gtsam::DiscreteConditional* asDiscrete() const;
|
||||||
|
|
@ -133,7 +136,10 @@ class HybridBayesNet {
|
||||||
gtsam::KeySet keys() const;
|
gtsam::KeySet keys() const;
|
||||||
const gtsam::HybridConditional* at(size_t i) const;
|
const gtsam::HybridConditional* at(size_t i) const;
|
||||||
|
|
||||||
double evaluate(const gtsam::HybridValues& x) const;
|
// Standard interface:
|
||||||
|
double logProbability(const gtsam::HybridValues& values) const;
|
||||||
|
double evaluate(const gtsam::HybridValues& values) const;
|
||||||
|
|
||||||
gtsam::HybridValues optimize() const;
|
gtsam::HybridValues optimize() const;
|
||||||
gtsam::HybridValues sample(const gtsam::HybridValues &given) const;
|
gtsam::HybridValues sample(const gtsam::HybridValues &given) const;
|
||||||
gtsam::HybridValues sample() const;
|
gtsam::HybridValues sample() const;
|
||||||
|
|
|
||||||
|
|
@ -497,6 +497,7 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
|
||||||
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
bool equals(const gtsam::GaussianConditional& cg, double tol) const;
|
||||||
|
|
||||||
// Standard Interface
|
// Standard Interface
|
||||||
|
double logProbability(const gtsam::VectorValues& x) const;
|
||||||
double evaluate(const gtsam::VectorValues& x) const;
|
double evaluate(const gtsam::VectorValues& x) const;
|
||||||
double error(const gtsam::VectorValues& x) const;
|
double error(const gtsam::VectorValues& x) const;
|
||||||
gtsam::Key firstFrontalKey() const;
|
gtsam::Key firstFrontalKey() const;
|
||||||
|
|
@ -558,6 +559,8 @@ virtual class GaussianBayesNet {
|
||||||
gtsam::GaussianConditional* back() const;
|
gtsam::GaussianConditional* back() const;
|
||||||
|
|
||||||
// Standard interface
|
// Standard interface
|
||||||
|
// Standard Interface
|
||||||
|
double logProbability(const gtsam::VectorValues& x) const;
|
||||||
double evaluate(const gtsam::VectorValues& x) const;
|
double evaluate(const gtsam::VectorValues& x) const;
|
||||||
double error(const gtsam::VectorValues& x) const;
|
double error(const gtsam::VectorValues& x) const;
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -11,13 +11,15 @@ Author: Frank Dellaert
|
||||||
|
|
||||||
# pylint: disable=no-name-in-module, invalid-name
|
# pylint: disable=no-name-in-module, invalid-name
|
||||||
|
|
||||||
|
import math
|
||||||
import textwrap
|
import textwrap
|
||||||
import unittest
|
import unittest
|
||||||
|
|
||||||
|
from gtsam.utils.test_case import GtsamTestCase
|
||||||
|
|
||||||
import gtsam
|
import gtsam
|
||||||
from gtsam import (DiscreteBayesNet, DiscreteConditional, DiscreteDistribution,
|
from gtsam import (DiscreteBayesNet, DiscreteConditional, DiscreteDistribution,
|
||||||
DiscreteFactorGraph, DiscreteKeys, DiscreteValues, Ordering)
|
DiscreteFactorGraph, DiscreteKeys, DiscreteValues, Ordering)
|
||||||
from gtsam.utils.test_case import GtsamTestCase
|
|
||||||
|
|
||||||
# Some keys:
|
# Some keys:
|
||||||
Asia = (0, 2)
|
Asia = (0, 2)
|
||||||
|
|
@ -111,7 +113,7 @@ class TestDiscreteBayesNet(GtsamTestCase):
|
||||||
self.assertEqual(len(actualSample), 8)
|
self.assertEqual(len(actualSample), 8)
|
||||||
|
|
||||||
def test_fragment(self):
|
def test_fragment(self):
|
||||||
"""Test sampling and optimizing for Asia fragment."""
|
"""Test evaluate/sampling/optimizing for Asia fragment."""
|
||||||
|
|
||||||
# Create a reverse-topologically sorted fragment:
|
# Create a reverse-topologically sorted fragment:
|
||||||
fragment = DiscreteBayesNet()
|
fragment = DiscreteBayesNet()
|
||||||
|
|
@ -125,8 +127,14 @@ class TestDiscreteBayesNet(GtsamTestCase):
|
||||||
given[key[0]] = 0
|
given[key[0]] = 0
|
||||||
|
|
||||||
# Now sample from fragment:
|
# Now sample from fragment:
|
||||||
actual = fragment.sample(given)
|
values = fragment.sample(given)
|
||||||
self.assertEqual(len(actual), 5)
|
self.assertEqual(len(values), 5)
|
||||||
|
|
||||||
|
for i in [0, 1, 2]:
|
||||||
|
self.assertAlmostEqual(fragment.at(i).logProbability(values),
|
||||||
|
math.log(fragment.at(i).evaluate(values)))
|
||||||
|
self.assertAlmostEqual(fragment.logProbability(values),
|
||||||
|
math.log(fragment.evaluate(values)))
|
||||||
|
|
||||||
def test_dot(self):
|
def test_dot(self):
|
||||||
"""Check that dot works with position hints."""
|
"""Check that dot works with position hints."""
|
||||||
|
|
|
||||||
|
|
@ -12,13 +12,15 @@ Author: Frank Dellaert
|
||||||
|
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
|
|
||||||
|
import math
|
||||||
import unittest
|
import unittest
|
||||||
|
|
||||||
import gtsam
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
from gtsam import GaussianBayesNet, GaussianConditional
|
|
||||||
from gtsam.utils.test_case import GtsamTestCase
|
from gtsam.utils.test_case import GtsamTestCase
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
from gtsam import GaussianBayesNet, GaussianConditional
|
||||||
|
|
||||||
# some keys
|
# some keys
|
||||||
_x_ = 11
|
_x_ = 11
|
||||||
_y_ = 22
|
_y_ = 22
|
||||||
|
|
@ -45,6 +47,18 @@ class TestGaussianBayesNet(GtsamTestCase):
|
||||||
np.testing.assert_equal(R, R1)
|
np.testing.assert_equal(R, R1)
|
||||||
np.testing.assert_equal(d, d1)
|
np.testing.assert_equal(d, d1)
|
||||||
|
|
||||||
|
def test_evaluate(self):
|
||||||
|
"""Test evaluate method"""
|
||||||
|
bayesNet = smallBayesNet()
|
||||||
|
values = gtsam.VectorValues()
|
||||||
|
values.insert(_x_, np.array([9.0]))
|
||||||
|
values.insert(_y_, np.array([5.0]))
|
||||||
|
for i in [0, 1]:
|
||||||
|
self.assertAlmostEqual(bayesNet.at(i).logProbability(values),
|
||||||
|
math.log(bayesNet.at(i).evaluate(values)))
|
||||||
|
self.assertAlmostEqual(bayesNet.logProbability(values),
|
||||||
|
math.log(bayesNet.evaluate(values)))
|
||||||
|
|
||||||
def test_sample(self):
|
def test_sample(self):
|
||||||
"""Test sample method"""
|
"""Test sample method"""
|
||||||
bayesNet = smallBayesNet()
|
bayesNet = smallBayesNet()
|
||||||
|
|
|
||||||
|
|
@ -10,14 +10,15 @@ Author: Frank Dellaert
|
||||||
"""
|
"""
|
||||||
# pylint: disable=invalid-name, no-name-in-module, no-member
|
# pylint: disable=invalid-name, no-name-in-module, no-member
|
||||||
|
|
||||||
|
import math
|
||||||
import unittest
|
import unittest
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
from gtsam.symbol_shorthand import A, X
|
from gtsam.symbol_shorthand import A, X
|
||||||
from gtsam.utils.test_case import GtsamTestCase
|
from gtsam.utils.test_case import GtsamTestCase
|
||||||
|
|
||||||
from gtsam import (DiscreteKeys, GaussianMixture, DiscreteConditional, GaussianConditional, GaussianMixture,
|
from gtsam import (DiscreteConditional, DiscreteKeys, GaussianConditional,
|
||||||
HybridBayesNet, HybridValues, noiseModel)
|
GaussianMixture, HybridBayesNet, HybridValues, noiseModel)
|
||||||
|
|
||||||
|
|
||||||
class TestHybridBayesNet(GtsamTestCase):
|
class TestHybridBayesNet(GtsamTestCase):
|
||||||
|
|
@ -30,7 +31,7 @@ class TestHybridBayesNet(GtsamTestCase):
|
||||||
|
|
||||||
# Create the continuous conditional
|
# Create the continuous conditional
|
||||||
I_1x1 = np.eye(1)
|
I_1x1 = np.eye(1)
|
||||||
gc = GaussianConditional.FromMeanAndStddev(X(0), 2 * I_1x1, X(1), [-4],
|
conditional = GaussianConditional.FromMeanAndStddev(X(0), 2 * I_1x1, X(1), [-4],
|
||||||
5.0)
|
5.0)
|
||||||
|
|
||||||
# Create the noise models
|
# Create the noise models
|
||||||
|
|
@ -45,7 +46,7 @@ class TestHybridBayesNet(GtsamTestCase):
|
||||||
|
|
||||||
# Create hybrid Bayes net.
|
# Create hybrid Bayes net.
|
||||||
bayesNet = HybridBayesNet()
|
bayesNet = HybridBayesNet()
|
||||||
bayesNet.push_back(gc)
|
bayesNet.push_back(conditional)
|
||||||
bayesNet.push_back(GaussianMixture(
|
bayesNet.push_back(GaussianMixture(
|
||||||
[X(1)], [], discrete_keys, [conditional0, conditional1]))
|
[X(1)], [], discrete_keys, [conditional0, conditional1]))
|
||||||
bayesNet.push_back(DiscreteConditional(Asia, "99/1"))
|
bayesNet.push_back(DiscreteConditional(Asia, "99/1"))
|
||||||
|
|
@ -56,13 +57,17 @@ class TestHybridBayesNet(GtsamTestCase):
|
||||||
values.insert(X(0), [-6])
|
values.insert(X(0), [-6])
|
||||||
values.insert(X(1), [1])
|
values.insert(X(1), [1])
|
||||||
|
|
||||||
conditionalProbability = gc.evaluate(values.continuous())
|
conditionalProbability = conditional.evaluate(values.continuous())
|
||||||
mixtureProbability = conditional0.evaluate(values.continuous())
|
mixtureProbability = conditional0.evaluate(values.continuous())
|
||||||
self.assertAlmostEqual(conditionalProbability * mixtureProbability *
|
self.assertAlmostEqual(conditionalProbability * mixtureProbability *
|
||||||
0.99,
|
0.99,
|
||||||
bayesNet.evaluate(values),
|
bayesNet.evaluate(values),
|
||||||
places=5)
|
places=5)
|
||||||
|
|
||||||
|
# Check logProbability
|
||||||
|
self.assertAlmostEqual(bayesNet.logProbability(values),
|
||||||
|
math.log(bayesNet.evaluate(values)))
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
unittest.main()
|
unittest.main()
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue