Remove FromConditionals
							parent
							
								
									7ba5392525
								
							
						
					
					
						commit
						d4ee6997f7
					
				|  | @ -42,15 +42,12 @@ const GaussianMixture::Conditionals &GaussianMixture::conditionals() const { | |||
| } | ||||
| 
 | ||||
| /* *******************************************************************************/ | ||||
| GaussianMixture GaussianMixture::FromConditionals( | ||||
| GaussianMixture::GaussianMixture( | ||||
|     const KeyVector &continuousFrontals, const KeyVector &continuousParents, | ||||
|     const DiscreteKeys &discreteParents, | ||||
|     const std::vector<GaussianConditional::shared_ptr> &conditionalsList) { | ||||
|   Conditionals dt(discreteParents, conditionalsList); | ||||
| 
 | ||||
|   return GaussianMixture(continuousFrontals, continuousParents, discreteParents, | ||||
|                          dt); | ||||
| } | ||||
|     const std::vector<GaussianConditional::shared_ptr> &conditionalsList) | ||||
|     : GaussianMixture(continuousFrontals, continuousParents, discreteParents, | ||||
|                       Conditionals(discreteParents, conditionalsList)) {} | ||||
| 
 | ||||
| /* *******************************************************************************/ | ||||
| GaussianMixture::Sum GaussianMixture::add( | ||||
|  |  | |||
|  | @ -114,7 +114,7 @@ class GTSAM_EXPORT GaussianMixture | |||
|    * @param discreteParents Discrete parents variables | ||||
|    * @param conditionals List of conditionals | ||||
|    */ | ||||
|   static This FromConditionals( | ||||
|   GaussianMixture( | ||||
|       const KeyVector &continuousFrontals, const KeyVector &continuousParents, | ||||
|       const DiscreteKeys &discreteParents, | ||||
|       const std::vector<GaussianConditional::shared_ptr> &conditionals); | ||||
|  |  | |||
|  | @ -66,12 +66,13 @@ class GaussianMixtureFactor : gtsam::HybridFactor { | |||
| 
 | ||||
| #include <gtsam/hybrid/GaussianMixture.h> | ||||
| class GaussianMixture : gtsam::HybridFactor { | ||||
|   static GaussianMixture FromConditionals( | ||||
|       const gtsam::KeyVector& continuousFrontals, | ||||
|       const gtsam::KeyVector& continuousParents, | ||||
|       const gtsam::DiscreteKeys& discreteParents, | ||||
|       const std::vector<gtsam::GaussianConditional::shared_ptr>& | ||||
|           conditionalsList); | ||||
|   GaussianMixture(const gtsam::KeyVector& continuousFrontals, | ||||
|                   const gtsam::KeyVector& continuousParents, | ||||
|                   const gtsam::DiscreteKeys& discreteParents, | ||||
|                   const std::vector<gtsam::GaussianConditional::shared_ptr>& | ||||
|                       conditionalsList); | ||||
| 
 | ||||
|   gtsam::GaussianMixtureFactor* likelihood(const gtsam::VectorValues &frontals) const; | ||||
| 
 | ||||
|   void print(string s = "GaussianMixture\n", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|  | @ -104,7 +105,7 @@ class HybridBayesTree { | |||
|                  gtsam::DefaultKeyFormatter) const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/hybrid/HybridBayesTree.h> | ||||
| #include <gtsam/hybrid/HybridBayesNet.h> | ||||
| class HybridBayesNet { | ||||
|   HybridBayesNet(); | ||||
|   void add(const gtsam::HybridConditional& s); | ||||
|  | @ -113,6 +114,11 @@ class HybridBayesNet { | |||
|   void addDiscrete(const gtsam::DiscreteConditional* s); | ||||
| 
 | ||||
|   void emplaceMixture(const gtsam::GaussianMixture& s); | ||||
|   void emplaceMixture(const gtsam::KeyVector& continuousFrontals, | ||||
|                       const gtsam::KeyVector& continuousParents, | ||||
|                       const gtsam::DiscreteKeys& discreteParents, | ||||
|                       const std::vector<gtsam::GaussianConditional::shared_ptr>& | ||||
|                           conditionalsList); | ||||
|   void emplaceGaussian(const gtsam::GaussianConditional& s); | ||||
|   void emplaceDiscrete(const gtsam::DiscreteConditional& s); | ||||
|   void emplaceDiscrete(const gtsam::DiscreteKey& key, string spec); | ||||
|  | @ -162,9 +168,8 @@ class HybridGaussianFactorGraph { | |||
|   void push_back(const gtsam::HybridBayesNet& bayesNet); | ||||
|   void push_back(const gtsam::HybridBayesTree& bayesTree); | ||||
|   void push_back(const gtsam::GaussianMixtureFactor* gmm); | ||||
| 
 | ||||
|   void add(gtsam::DecisionTreeFactor* factor); | ||||
|   void add(gtsam::JacobianFactor* factor); | ||||
|   void push_back(gtsam::DecisionTreeFactor* factor); | ||||
|   void push_back(gtsam::JacobianFactor* factor); | ||||
| 
 | ||||
|   bool empty() const; | ||||
|   void remove(size_t i); | ||||
|  |  | |||
|  | @ -148,9 +148,7 @@ static GaussianMixture createSimpleGaussianMixture() { | |||
|       GaussianConditional::FromMeanAndStddev(Z(0), I, X(0), Vector1(0), 0.5)); | ||||
|   const auto conditional1 = boost::make_shared<GaussianConditional>( | ||||
|       GaussianConditional::FromMeanAndStddev(Z(0), I, X(0), Vector1(0), 3)); | ||||
|   const auto gm = GaussianMixture::FromConditionals( | ||||
|       {Z(0)}, {X(0)}, {mode}, {conditional0, conditional1}); | ||||
|   return gm; | ||||
|   return GaussianMixture({Z(0)}, {X(0)}, {mode}, {conditional0, conditional1}); | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
|  |  | |||
|  | @ -88,8 +88,8 @@ TEST(HybridBayesNet, evaluateHybrid) { | |||
|   // Create hybrid Bayes net.
 | ||||
|   HybridBayesNet bayesNet; | ||||
|   bayesNet.emplaceGaussian(continuousConditional); | ||||
|   bayesNet.emplaceMixture(GaussianMixture::FromConditionals( | ||||
|       {X(1)}, {}, {Asia}, {conditional0, conditional1})); | ||||
|   GaussianMixture gm({X(1)}, {}, {Asia}, {conditional0, conditional1}); | ||||
|   bayesNet.emplaceMixture(gm);  // copy :-(
 | ||||
|   bayesNet.emplaceDiscrete(Asia, "99/1"); | ||||
| 
 | ||||
|   // Create values at which to evaluate.
 | ||||
|  |  | |||
|  | @ -42,14 +42,13 @@ class TestHybridBayesNet(GtsamTestCase): | |||
|         conditional1 = GaussianConditional(X(1), [2], I_1x1, model1) | ||||
|         dkeys = DiscreteKeys() | ||||
|         dkeys.push_back(Asia) | ||||
|         gm = GaussianMixture.FromConditionals([X(1)], [], dkeys, | ||||
|                                               [conditional0, conditional1])  # | ||||
|         gm = GaussianMixture([X(1)], [], dkeys, [conditional0, conditional1])  | ||||
| 
 | ||||
|         # Create hybrid Bayes net. | ||||
|         bayesNet = HybridBayesNet() | ||||
|         bayesNet.addGaussian(gc) | ||||
|         bayesNet.addMixture(gm) | ||||
|         bayesNet.addDiscrete(Asia, "99/1") | ||||
|         bayesNet.emplaceDiscrete(Asia, "99/1") | ||||
| 
 | ||||
|         # Create values at which to evaluate. | ||||
|         values = HybridValues() | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue