fix wrapper

release/4.3a0
Varun Agrawal 2024-09-17 14:20:46 -04:00
parent d4923dbfa9
commit a276affe00
1 changed files with 3 additions and 4 deletions

View File

@ -76,7 +76,7 @@ virtual class HybridConditional {
class HybridGaussianFactor : gtsam::HybridFactor {
HybridGaussianFactor(
const gtsam::KeyVector& continuousKeys,
const gtsam::DiscreteKeys& discreteKeys,
const gtsam::DiscreteKey& discreteKey,
const std::vector<std::pair<gtsam::GaussianFactor::shared_ptr, double>>&
factorsList);
@ -91,8 +91,7 @@ class HybridGaussianConditional : gtsam::HybridFactor {
const gtsam::KeyVector& continuousFrontals,
const gtsam::KeyVector& continuousParents,
const gtsam::DiscreteKeys& discreteParents,
const std::vector<gtsam::GaussianConditional::shared_ptr>&
conditionalsList);
const gtsam::HybridGaussianConditional::Conditionals& conditionals);
gtsam::HybridGaussianFactor* likelihood(
const gtsam::VectorValues& frontals) const;
@ -248,7 +247,7 @@ class HybridNonlinearFactor : gtsam::HybridFactor {
bool normalized = false);
HybridNonlinearFactor(
const gtsam::KeyVector& keys, const gtsam::DiscreteKeys& discreteKeys,
const gtsam::KeyVector& keys, const gtsam::DiscreteKey& discreteKey,
const std::vector<std::pair<gtsam::NonlinearFactor*, double>>& factors,
bool normalized = false);