From 7d58207dae808697d9812b88f8c101f62e1184af Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 29 Dec 2022 11:55:19 -0500 Subject: [PATCH] Renamed add to emplace, add is for shared pointers --- gtsam/hybrid/HybridBayesNet.h | 21 ++++++++++++++++--- gtsam/hybrid/hybrid.i | 25 +++++++++++++++-------- gtsam/hybrid/tests/testHybridBayesNet.cpp | 12 +++++------ 3 files changed, 41 insertions(+), 17 deletions(-) diff --git a/gtsam/hybrid/HybridBayesNet.h b/gtsam/hybrid/HybridBayesNet.h index 488ee0d14..a64b3bb4f 100644 --- a/gtsam/hybrid/HybridBayesNet.h +++ b/gtsam/hybrid/HybridBayesNet.h @@ -69,23 +69,38 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet { /// Add HybridConditional to Bayes Net using Base::add; + /// Add a Gaussian Mixture to the Bayes Net. + void addMixture(const GaussianMixture::shared_ptr &ptr) { + push_back(HybridConditional(ptr)); + } + + /// Add a Gaussian conditional to the Bayes Net. + void addGaussian(const GaussianConditional::shared_ptr &ptr) { + push_back(HybridConditional(ptr)); + } + + /// Add a discrete conditional to the Bayes Net. + void addDiscrete(const DiscreteConditional::shared_ptr &ptr) { + push_back(HybridConditional(ptr)); + } + /// Add a Gaussian Mixture to the Bayes Net. template - void addMixture(T &&...args) { + void emplaceMixture(T &&...args) { push_back(HybridConditional( boost::make_shared(std::forward(args)...))); } /// Add a Gaussian conditional to the Bayes Net. template - void addGaussian(T &&...args) { + void emplaceGaussian(T &&...args) { push_back(HybridConditional( boost::make_shared(std::forward(args)...))); } /// Add a discrete conditional to the Bayes Net. template - void addDiscrete(T &&...args) { + void emplaceDiscrete(T &&...args) { push_back(HybridConditional( boost::make_shared(std::forward(args)...))); } diff --git a/gtsam/hybrid/hybrid.i b/gtsam/hybrid/hybrid.i index acda94638..ab070c68f 100644 --- a/gtsam/hybrid/hybrid.i +++ b/gtsam/hybrid/hybrid.i @@ -108,14 +108,23 @@ class HybridBayesTree { class HybridBayesNet { HybridBayesNet(); void add(const gtsam::HybridConditional& s); - void addMixture(const gtsam::GaussianMixture& s); - void addGaussian(const gtsam::GaussianConditional& s); - void addDiscrete(const gtsam::DiscreteConditional& s); - void addDiscrete(const gtsam::DiscreteKey& key, string spec); - void addDiscrete(const gtsam::DiscreteKey& key, - const gtsam::DiscreteKeys& parents, string spec); - void addDiscrete(const gtsam::DiscreteKey& key, - const std::vector& parents, string spec); + void addMixture(const gtsam::GaussianMixture* s); + void addGaussian(const gtsam::GaussianConditional* s); + void addDiscrete(const gtsam::DiscreteConditional* s); + + void emplaceMixture(const gtsam::GaussianMixture& s); + void emplaceGaussian(const gtsam::GaussianConditional& s); + void emplaceDiscrete(const gtsam::DiscreteConditional& s); + void emplaceDiscrete(const gtsam::DiscreteKey& key, string spec); + void emplaceDiscrete(const gtsam::DiscreteKey& key, + const gtsam::DiscreteKeys& parents, string spec); + void emplaceDiscrete(const gtsam::DiscreteKey& key, + const std::vector& parents, + string spec); + + gtsam::GaussianMixture* atMixture(size_t i) const; + gtsam::GaussianConditional* atGaussian(size_t i) const; + gtsam::DiscreteConditional* atDiscrete(size_t i) const; bool empty() const; size_t size() const; diff --git a/gtsam/hybrid/tests/testHybridBayesNet.cpp b/gtsam/hybrid/tests/testHybridBayesNet.cpp index 8c887a2aa..9a2ca1208 100644 --- a/gtsam/hybrid/tests/testHybridBayesNet.cpp +++ b/gtsam/hybrid/tests/testHybridBayesNet.cpp @@ -43,7 +43,7 @@ static const DiscreteKey Asia(asiaKey, 2); // Test creation of a pure discrete Bayes net. TEST(HybridBayesNet, Creation) { HybridBayesNet bayesNet; - bayesNet.addDiscrete(Asia, "99/1"); + bayesNet.emplaceDiscrete(Asia, "99/1"); DiscreteConditional expected(Asia, "99/1"); CHECK(bayesNet.atDiscrete(0)); @@ -54,7 +54,7 @@ TEST(HybridBayesNet, Creation) { // Test adding a Bayes net to another one. TEST(HybridBayesNet, Add) { HybridBayesNet bayesNet; - bayesNet.addDiscrete(Asia, "99/1"); + bayesNet.emplaceDiscrete(Asia, "99/1"); HybridBayesNet other; other.push_back(bayesNet); @@ -65,7 +65,7 @@ TEST(HybridBayesNet, Add) { // Test evaluate for a pure discrete Bayes net P(Asia). TEST(HybridBayesNet, evaluatePureDiscrete) { HybridBayesNet bayesNet; - bayesNet.addDiscrete(Asia, "99/1"); + bayesNet.emplaceDiscrete(Asia, "99/1"); HybridValues values; values.insert(asiaKey, 0); EXPECT_DOUBLES_EQUAL(0.99, bayesNet.evaluate(values), 1e-9); @@ -87,10 +87,10 @@ TEST(HybridBayesNet, evaluateHybrid) { // Create hybrid Bayes net. HybridBayesNet bayesNet; - bayesNet.addGaussian(continuousConditional); - bayesNet.addMixture(GaussianMixture::FromConditionals( + bayesNet.emplaceGaussian(continuousConditional); + bayesNet.emplaceMixture(GaussianMixture::FromConditionals( {X(1)}, {}, {Asia}, {conditional0, conditional1})); - bayesNet.addDiscrete(Asia, "99/1"); + bayesNet.emplaceDiscrete(Asia, "99/1"); // Create values at which to evaluate. HybridValues values;