Fix wrapper
parent
bb4c3c95ab
commit
1a566ea2bb
|
@ -75,10 +75,12 @@ virtual class HybridConditional {
|
|||
#include <gtsam/hybrid/HybridGaussianFactor.h>
|
||||
class HybridGaussianFactor : gtsam::HybridFactor {
|
||||
HybridGaussianFactor(
|
||||
const gtsam::KeyVector& continuousKeys,
|
||||
const gtsam::DiscreteKey& discreteKey,
|
||||
const std::vector<gtsam::GaussianFactor::shared_ptr>& factors);
|
||||
HybridGaussianFactor(
|
||||
const gtsam::DiscreteKey& discreteKey,
|
||||
const std::vector<std::pair<gtsam::GaussianFactor::shared_ptr, double>>&
|
||||
factorsList);
|
||||
factorPairs);
|
||||
|
||||
void print(string s = "HybridGaussianFactor\n",
|
||||
const gtsam::KeyFormatter& keyFormatter =
|
||||
|
@ -88,13 +90,9 @@ class HybridGaussianFactor : gtsam::HybridFactor {
|
|||
#include <gtsam/hybrid/HybridGaussianConditional.h>
|
||||
class HybridGaussianConditional : gtsam::HybridFactor {
|
||||
HybridGaussianConditional(
|
||||
const gtsam::KeyVector& continuousFrontals,
|
||||
const gtsam::KeyVector& continuousParents,
|
||||
const gtsam::DiscreteKeys& discreteParents,
|
||||
const gtsam::HybridGaussianConditional::Conditionals& conditionals);
|
||||
HybridGaussianConditional(
|
||||
const gtsam::KeyVector& continuousFrontals,
|
||||
const gtsam::KeyVector& continuousParents,
|
||||
const gtsam::DiscreteKey& discreteParent,
|
||||
const std::vector<gtsam::GaussianConditional::shared_ptr>& conditionals);
|
||||
|
||||
|
@ -246,15 +244,15 @@ class HybridNonlinearFactorGraph {
|
|||
#include <gtsam/hybrid/HybridNonlinearFactor.h>
|
||||
class HybridNonlinearFactor : gtsam::HybridFactor {
|
||||
HybridNonlinearFactor(
|
||||
const gtsam::KeyVector& keys, const gtsam::DiscreteKey& discreteKey,
|
||||
const gtsam::DiscreteKey& discreteKey,
|
||||
const std::vector<gtsam::NonlinearFactor*>& factors);
|
||||
|
||||
HybridNonlinearFactor(
|
||||
const gtsam::KeyVector& keys, const gtsam::DiscreteKey& discreteKey,
|
||||
const gtsam::DiscreteKey& discreteKey,
|
||||
const std::vector<std::pair<gtsam::NonlinearFactor*, double>>& factors);
|
||||
|
||||
HybridNonlinearFactor(
|
||||
const gtsam::KeyVector& keys, const gtsam::DiscreteKeys& discreteKeys,
|
||||
const gtsam::DiscreteKeys& discreteKeys,
|
||||
const gtsam::DecisionTree<
|
||||
gtsam::Key, std::pair<gtsam::NonlinearFactor*, double>>& factors);
|
||||
|
||||
|
|
|
@ -17,7 +17,7 @@ from gtsam.symbol_shorthand import C, M, X, Z
|
|||
from gtsam.utils.test_case import GtsamTestCase
|
||||
|
||||
import gtsam
|
||||
from gtsam import (DiscreteConditional, DiscreteKeys, GaussianConditional,
|
||||
from gtsam import (DiscreteConditional, GaussianConditional,
|
||||
HybridBayesNet, HybridGaussianConditional,
|
||||
HybridGaussianFactor, HybridGaussianFactorGraph,
|
||||
HybridValues, JacobianFactor, noiseModel)
|
||||
|
@ -102,8 +102,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase):
|
|||
X(0), [0],
|
||||
sigma=3)
|
||||
bayesNet.push_back(
|
||||
HybridGaussianConditional([Z(i)], [X(0)], mode,
|
||||
[conditional0, conditional1]))
|
||||
HybridGaussianConditional(mode, [conditional0, conditional1]))
|
||||
|
||||
# Create prior on X(0).
|
||||
prior_on_x0 = GaussianConditional.FromMeanAndStddev(
|
||||
|
|
Loading…
Reference in New Issue