@@ -510,12 +510,17 @@ virtual class GaussianConditional : gtsam::JacobianFactor {
510
510
GaussianConditional (size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S,
511
511
size_t name2, gtsam::Matrix T,
512
512
const gtsam::noiseModel::Diagonal* sigmas);
513
+ GaussianConditional (const vector<std::pair<gtsam::Key, gtsam::Matrix>> terms,
514
+ size_t nrFrontals, gtsam::Vector d,
515
+ const gtsam::noiseModel::Diagonal* sigmas);
513
516
514
517
// Constructors with no noise model
515
518
GaussianConditional (size_t key, gtsam::Vector d, gtsam::Matrix R);
516
519
GaussianConditional (size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S);
517
520
GaussianConditional (size_t key, gtsam::Vector d, gtsam::Matrix R, size_t name1, gtsam::Matrix S,
518
521
size_t name2, gtsam::Matrix T);
522
+ GaussianConditional (const gtsam::KeyVector& keys, size_t nrFrontals,
523
+ const gtsam::VerticalBlockMatrix& augmentedMatrix);
519
524
520
525
// Named constructors
521
526
static gtsam::GaussianConditional FromMeanAndStddev (gtsam::Key key,
0 commit comments