Fix wrapper

release/4.3a0
Frank Dellaert 2024-09-26 14:51:39 -07:00
parent bb4c3c95ab
commit 1a566ea2bb
2 changed files with 9 additions and 12 deletions

View File

@ -75,10 +75,12 @@ virtual class HybridConditional {
#include <gtsam/hybrid/HybridGaussianFactor.h> #include <gtsam/hybrid/HybridGaussianFactor.h>
class HybridGaussianFactor : gtsam::HybridFactor { class HybridGaussianFactor : gtsam::HybridFactor {
HybridGaussianFactor( HybridGaussianFactor(
const gtsam::KeyVector& continuousKeys, const gtsam::DiscreteKey& discreteKey,
const std::vector<gtsam::GaussianFactor::shared_ptr>& factors);
HybridGaussianFactor(
const gtsam::DiscreteKey& discreteKey, const gtsam::DiscreteKey& discreteKey,
const std::vector<std::pair<gtsam::GaussianFactor::shared_ptr, double>>& const std::vector<std::pair<gtsam::GaussianFactor::shared_ptr, double>>&
factorsList); factorPairs);
void print(string s = "HybridGaussianFactor\n", void print(string s = "HybridGaussianFactor\n",
const gtsam::KeyFormatter& keyFormatter = const gtsam::KeyFormatter& keyFormatter =
@ -88,13 +90,9 @@ class HybridGaussianFactor : gtsam::HybridFactor {
#include <gtsam/hybrid/HybridGaussianConditional.h> #include <gtsam/hybrid/HybridGaussianConditional.h>
class HybridGaussianConditional : gtsam::HybridFactor { class HybridGaussianConditional : gtsam::HybridFactor {
HybridGaussianConditional( HybridGaussianConditional(
const gtsam::KeyVector& continuousFrontals,
const gtsam::KeyVector& continuousParents,
const gtsam::DiscreteKeys& discreteParents, const gtsam::DiscreteKeys& discreteParents,
const gtsam::HybridGaussianConditional::Conditionals& conditionals); const gtsam::HybridGaussianConditional::Conditionals& conditionals);
HybridGaussianConditional( HybridGaussianConditional(
const gtsam::KeyVector& continuousFrontals,
const gtsam::KeyVector& continuousParents,
const gtsam::DiscreteKey& discreteParent, const gtsam::DiscreteKey& discreteParent,
const std::vector<gtsam::GaussianConditional::shared_ptr>& conditionals); const std::vector<gtsam::GaussianConditional::shared_ptr>& conditionals);
@ -246,15 +244,15 @@ class HybridNonlinearFactorGraph {
#include <gtsam/hybrid/HybridNonlinearFactor.h> #include <gtsam/hybrid/HybridNonlinearFactor.h>
class HybridNonlinearFactor : gtsam::HybridFactor { class HybridNonlinearFactor : gtsam::HybridFactor {
HybridNonlinearFactor( HybridNonlinearFactor(
const gtsam::KeyVector& keys, const gtsam::DiscreteKey& discreteKey, const gtsam::DiscreteKey& discreteKey,
const std::vector<gtsam::NonlinearFactor*>& factors); const std::vector<gtsam::NonlinearFactor*>& factors);
HybridNonlinearFactor( HybridNonlinearFactor(
const gtsam::KeyVector& keys, const gtsam::DiscreteKey& discreteKey, const gtsam::DiscreteKey& discreteKey,
const std::vector<std::pair<gtsam::NonlinearFactor*, double>>& factors); const std::vector<std::pair<gtsam::NonlinearFactor*, double>>& factors);
HybridNonlinearFactor( HybridNonlinearFactor(
const gtsam::KeyVector& keys, const gtsam::DiscreteKeys& discreteKeys, const gtsam::DiscreteKeys& discreteKeys,
const gtsam::DecisionTree< const gtsam::DecisionTree<
gtsam::Key, std::pair<gtsam::NonlinearFactor*, double>>& factors); gtsam::Key, std::pair<gtsam::NonlinearFactor*, double>>& factors);

View File

@ -17,7 +17,7 @@ from gtsam.symbol_shorthand import C, M, X, Z
from gtsam.utils.test_case import GtsamTestCase from gtsam.utils.test_case import GtsamTestCase
import gtsam import gtsam
from gtsam import (DiscreteConditional, DiscreteKeys, GaussianConditional, from gtsam import (DiscreteConditional, GaussianConditional,
HybridBayesNet, HybridGaussianConditional, HybridBayesNet, HybridGaussianConditional,
HybridGaussianFactor, HybridGaussianFactorGraph, HybridGaussianFactor, HybridGaussianFactorGraph,
HybridValues, JacobianFactor, noiseModel) HybridValues, JacobianFactor, noiseModel)
@ -102,8 +102,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase):
X(0), [0], X(0), [0],
sigma=3) sigma=3)
bayesNet.push_back( bayesNet.push_back(
HybridGaussianConditional([Z(i)], [X(0)], mode, HybridGaussianConditional(mode, [conditional0, conditional1]))
[conditional0, conditional1]))
# Create prior on X(0). # Create prior on X(0).
prior_on_x0 = GaussianConditional.FromMeanAndStddev( prior_on_x0 = GaussianConditional.FromMeanAndStddev(