@@ -128,6 +128,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base {
128128
129129virtual class Cauchy : gtsam::noiseModel::mEstimator ::Base {
130130 Cauchy (double k);
131+ Cauchy (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
131132 static gtsam::noiseModel::mEstimator ::Cauchy* Create (double k);
132133
133134 // enabling serialization functionality
@@ -139,6 +140,7 @@ virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {
139140
140141virtual class Tukey : gtsam::noiseModel::mEstimator ::Base {
141142 Tukey (double k);
143+ Tukey (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
142144 static gtsam::noiseModel::mEstimator ::Tukey* Create (double k);
143145
144146 // enabling serialization functionality
@@ -150,6 +152,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
150152
151153virtual class Welsch : gtsam::noiseModel::mEstimator ::Base {
152154 Welsch (double k);
155+ Welsch (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
153156 static gtsam::noiseModel::mEstimator ::Welsch* Create (double k);
154157
155158 // enabling serialization functionality
@@ -161,6 +164,7 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
161164
162165virtual class GemanMcClure : gtsam::noiseModel::mEstimator ::Base {
163166 GemanMcClure (double c);
167+ GemanMcClure (double c, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
164168 static gtsam::noiseModel::mEstimator ::GemanMcClure* Create (double c);
165169
166170 // enabling serialization functionality
@@ -172,6 +176,7 @@ virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {
172176
173177virtual class DCS : gtsam::noiseModel::mEstimator ::Base {
174178 DCS (double c);
179+ DCS (double c, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
175180 static gtsam::noiseModel::mEstimator ::DCS* Create (double c);
176181
177182 // enabling serialization functionality
@@ -183,6 +188,7 @@ virtual class DCS: gtsam::noiseModel::mEstimator::Base {
183188
184189virtual class L2WithDeadZone : gtsam::noiseModel::mEstimator ::Base {
185190 L2WithDeadZone (double k);
191+ L2WithDeadZone (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
186192 static gtsam::noiseModel::mEstimator ::L2WithDeadZone* Create (double k);
187193
188194 // enabling serialization functionality
@@ -193,6 +199,7 @@ virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base {
193199};
194200
195201virtual class AsymmetricTukey : gtsam::noiseModel::mEstimator ::Base {
202+ AsymmetricTukey (double k);
196203 AsymmetricTukey (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
197204 static gtsam::noiseModel::mEstimator ::AsymmetricTukey* Create (double k);
198205
@@ -203,6 +210,18 @@ virtual class AsymmetricTukey: gtsam::noiseModel::mEstimator::Base {
203210 double loss (double error) const ;
204211};
205212
213+ virtual class AsymmetricCauchy : gtsam::noiseModel::mEstimator ::Base {
214+ AsymmetricCauchy (double k);
215+ AsymmetricCauchy (double k, gtsam::noiseModel::mEstimator ::Base::ReweightScheme reweight);
216+ static gtsam::noiseModel::mEstimator ::AsymmetricCauchy* Create (double k);
217+
218+ // enabling serialization functionality
219+ void serializable () const ;
220+
221+ double weight (double error) const ;
222+ double loss (double error) const ;
223+ };
224+
206225virtual class Custom : gtsam::noiseModel::mEstimator ::Base {
207226 Custom (gtsam::noiseModel::mEstimator ::CustomWeightFunction weight,
208227 gtsam::noiseModel::mEstimator ::CustomLossFunction loss,
@@ -356,6 +375,8 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
356375 void serialize () const ;
357376};
358377
378+ pair<gtsam::GaussianConditional, gtsam::JacobianFactor*> EliminateQR (const gtsam::GaussianFactorGraph& factors, const gtsam::Ordering& keys);
379+
359380#include < gtsam/linear/HessianFactor.h>
360381virtual class HessianFactor : gtsam::GaussianFactor {
361382 // Constructors
0 commit comments