Renamed add to emplace, add is for shared pointers

release/4.3a0
Frank Dellaert 2022-12-29 11:55:19 -05:00
parent a6b90023f3
commit 7d58207dae
3 changed files with 41 additions and 17 deletions

View File

@ -69,23 +69,38 @@ class GTSAM_EXPORT HybridBayesNet : public BayesNet<HybridConditional> {
/// Add HybridConditional to Bayes Net /// Add HybridConditional to Bayes Net
using Base::add; 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. /// Add a Gaussian Mixture to the Bayes Net.
template <typename... T> template <typename... T>
void addMixture(T &&...args) { void emplaceMixture(T &&...args) {
push_back(HybridConditional( push_back(HybridConditional(
boost::make_shared<GaussianMixture>(std::forward<T>(args)...))); boost::make_shared<GaussianMixture>(std::forward<T>(args)...)));
} }
/// Add a Gaussian conditional to the Bayes Net. /// Add a Gaussian conditional to the Bayes Net.
template <typename... T> template <typename... T>
void addGaussian(T &&...args) { void emplaceGaussian(T &&...args) {
push_back(HybridConditional( push_back(HybridConditional(
boost::make_shared<GaussianConditional>(std::forward<T>(args)...))); boost::make_shared<GaussianConditional>(std::forward<T>(args)...)));
} }
/// Add a discrete conditional to the Bayes Net. /// Add a discrete conditional to the Bayes Net.
template <typename... T> template <typename... T>
void addDiscrete(T &&...args) { void emplaceDiscrete(T &&...args) {
push_back(HybridConditional( push_back(HybridConditional(
boost::make_shared<DiscreteConditional>(std::forward<T>(args)...))); boost::make_shared<DiscreteConditional>(std::forward<T>(args)...)));
} }

View File

@ -108,14 +108,23 @@ class HybridBayesTree {
class HybridBayesNet { class HybridBayesNet {
HybridBayesNet(); HybridBayesNet();
void add(const gtsam::HybridConditional& s); void add(const gtsam::HybridConditional& s);
void addMixture(const gtsam::GaussianMixture& s); void addMixture(const gtsam::GaussianMixture* s);
void addGaussian(const gtsam::GaussianConditional& s); void addGaussian(const gtsam::GaussianConditional* s);
void addDiscrete(const gtsam::DiscreteConditional& s); void addDiscrete(const gtsam::DiscreteConditional* s);
void addDiscrete(const gtsam::DiscreteKey& key, string spec);
void addDiscrete(const gtsam::DiscreteKey& key, 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); const gtsam::DiscreteKeys& parents, string spec);
void addDiscrete(const gtsam::DiscreteKey& key, void emplaceDiscrete(const gtsam::DiscreteKey& key,
const std::vector<gtsam::DiscreteKey>& parents, string spec); const std::vector<gtsam::DiscreteKey>& 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; bool empty() const;
size_t size() const; size_t size() const;

View File

@ -43,7 +43,7 @@ static const DiscreteKey Asia(asiaKey, 2);
// Test creation of a pure discrete Bayes net. // Test creation of a pure discrete Bayes net.
TEST(HybridBayesNet, Creation) { TEST(HybridBayesNet, Creation) {
HybridBayesNet bayesNet; HybridBayesNet bayesNet;
bayesNet.addDiscrete(Asia, "99/1"); bayesNet.emplaceDiscrete(Asia, "99/1");
DiscreteConditional expected(Asia, "99/1"); DiscreteConditional expected(Asia, "99/1");
CHECK(bayesNet.atDiscrete(0)); CHECK(bayesNet.atDiscrete(0));
@ -54,7 +54,7 @@ TEST(HybridBayesNet, Creation) {
// Test adding a Bayes net to another one. // Test adding a Bayes net to another one.
TEST(HybridBayesNet, Add) { TEST(HybridBayesNet, Add) {
HybridBayesNet bayesNet; HybridBayesNet bayesNet;
bayesNet.addDiscrete(Asia, "99/1"); bayesNet.emplaceDiscrete(Asia, "99/1");
HybridBayesNet other; HybridBayesNet other;
other.push_back(bayesNet); other.push_back(bayesNet);
@ -65,7 +65,7 @@ TEST(HybridBayesNet, Add) {
// Test evaluate for a pure discrete Bayes net P(Asia). // Test evaluate for a pure discrete Bayes net P(Asia).
TEST(HybridBayesNet, evaluatePureDiscrete) { TEST(HybridBayesNet, evaluatePureDiscrete) {
HybridBayesNet bayesNet; HybridBayesNet bayesNet;
bayesNet.addDiscrete(Asia, "99/1"); bayesNet.emplaceDiscrete(Asia, "99/1");
HybridValues values; HybridValues values;
values.insert(asiaKey, 0); values.insert(asiaKey, 0);
EXPECT_DOUBLES_EQUAL(0.99, bayesNet.evaluate(values), 1e-9); EXPECT_DOUBLES_EQUAL(0.99, bayesNet.evaluate(values), 1e-9);
@ -87,10 +87,10 @@ TEST(HybridBayesNet, evaluateHybrid) {
// Create hybrid Bayes net. // Create hybrid Bayes net.
HybridBayesNet bayesNet; HybridBayesNet bayesNet;
bayesNet.addGaussian(continuousConditional); bayesNet.emplaceGaussian(continuousConditional);
bayesNet.addMixture(GaussianMixture::FromConditionals( bayesNet.emplaceMixture(GaussianMixture::FromConditionals(
{X(1)}, {}, {Asia}, {conditional0, conditional1})); {X(1)}, {}, {Asia}, {conditional0, conditional1}));
bayesNet.addDiscrete(Asia, "99/1"); bayesNet.emplaceDiscrete(Asia, "99/1");
// Create values at which to evaluate. // Create values at which to evaluate.
HybridValues values; HybridValues values;