Skip to content

Commit

Permalink
Fix wrapper
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert committed Sep 26, 2024
1 parent bb4c3c9 commit 1a566ea
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 12 deletions.
16 changes: 7 additions & 9 deletions gtsam/hybrid/hybrid.i
Original file line number Diff line number Diff line change
Expand Up @@ -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 =
Expand All @@ -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);

Expand Down Expand Up @@ -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);

Expand Down
5 changes: 2 additions & 3 deletions python/gtsam/tests/test_HybridFactorGraph.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
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)
Expand Down Expand Up @@ -102,8 +102,7 @@ def tiny(num_measurements: int = 1,
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(
Expand Down

0 comments on commit 1a566ea

Please sign in to comment.