wrapped more mEstimators as well as their weight functions
parent
19315cc3f3
commit
f68c06a10d
31
gtsam.h
31
gtsam.h
|
@ -1362,6 +1362,8 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Fair: gtsam::noiseModel::mEstimator::Base {
|
virtual class Fair: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
@ -1370,6 +1372,8 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Huber: gtsam::noiseModel::mEstimator::Base {
|
virtual class Huber: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
@ -1378,6 +1382,18 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
|
};
|
||||||
|
|
||||||
|
virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
Cauchy(double k);
|
||||||
|
static gtsam::noiseModel::mEstimator::Cauchy* Create(double k);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
|
virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
@ -1386,6 +1402,8 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
|
virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
@ -1394,8 +1412,21 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {
|
||||||
|
GemanMcClure(double k);
|
||||||
|
static gtsam::noiseModel::mEstimator::GemanMcClure* Create(double k);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serializable() const;
|
||||||
|
|
||||||
|
double weight(double error) const;
|
||||||
|
};
|
||||||
|
|
||||||
|
//TODO DCS and L2WithDeadZone mEstimators
|
||||||
|
|
||||||
}///\namespace mEstimator
|
}///\namespace mEstimator
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue