Skip to content

Commit

Permalink
Merge pull request #1757 from borglab/fan/add_eliminate_qr
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal committed May 30, 2024
2 parents 42b27e4 + 6f408fe commit 50021ed
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 2 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/build-python.yml
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ jobs:
uses: ilammy/msvc-dev-cmd@v1
with:
arch: x${{matrix.platform}}
toolset: 14.38
toolset: 14.2

- name: cl version (Windows)
if: runner.os == 'Windows'
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ jobs:
uses: ilammy/msvc-dev-cmd@v1
with:
arch: x${{ matrix.platform }}
toolset: 14.38
toolset: 14.2

- name: cl version
shell: cmd
Expand Down
21 changes: 21 additions & 0 deletions gtsam/linear/linear.i
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base {

virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {
Cauchy(double k);
Cauchy(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::Cauchy* Create(double k);

// enabling serialization functionality
Expand All @@ -139,6 +140,7 @@ virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {

virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
Tukey(double k);
Tukey(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::Tukey* Create(double k);

// enabling serialization functionality
Expand All @@ -150,6 +152,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base {

virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
Welsch(double k);
Welsch(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::Welsch* Create(double k);

// enabling serialization functionality
Expand All @@ -161,6 +164,7 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base {

virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {
GemanMcClure(double c);
GemanMcClure(double c, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::GemanMcClure* Create(double c);

// enabling serialization functionality
Expand All @@ -172,6 +176,7 @@ virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {

virtual class DCS: gtsam::noiseModel::mEstimator::Base {
DCS(double c);
DCS(double c, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::DCS* Create(double c);

// enabling serialization functionality
Expand All @@ -183,6 +188,7 @@ virtual class DCS: gtsam::noiseModel::mEstimator::Base {

virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base {
L2WithDeadZone(double k);
L2WithDeadZone(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::L2WithDeadZone* Create(double k);

// enabling serialization functionality
Expand All @@ -193,6 +199,7 @@ virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base {
};

virtual class AsymmetricTukey: gtsam::noiseModel::mEstimator::Base {
AsymmetricTukey(double k);
AsymmetricTukey(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::AsymmetricTukey* Create(double k);

Expand All @@ -203,6 +210,18 @@ virtual class AsymmetricTukey: gtsam::noiseModel::mEstimator::Base {
double loss(double error) const;
};

virtual class AsymmetricCauchy: gtsam::noiseModel::mEstimator::Base {
AsymmetricCauchy(double k);
AsymmetricCauchy(double k, gtsam::noiseModel::mEstimator::Base::ReweightScheme reweight);
static gtsam::noiseModel::mEstimator::AsymmetricCauchy* Create(double k);

// enabling serialization functionality
void serializable() const;

double weight(double error) const;
double loss(double error) const;
};

virtual class Custom: gtsam::noiseModel::mEstimator::Base {
Custom(gtsam::noiseModel::mEstimator::CustomWeightFunction weight,
gtsam::noiseModel::mEstimator::CustomLossFunction loss,
Expand Down Expand Up @@ -356,6 +375,8 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
void serialize() const;
};

pair<gtsam::GaussianConditional, gtsam::JacobianFactor*> EliminateQR(const gtsam::GaussianFactorGraph& factors, const gtsam::Ordering& keys);

#include <gtsam/linear/HessianFactor.h>
virtual class HessianFactor : gtsam::GaussianFactor {
//Constructors
Expand Down

0 comments on commit 50021ed

Please sign in to comment.