#include <LossFunctions.h>
Public Types | |
typedef boost::shared_ptr< GemanMcClure > | shared_ptr |
Public Types inherited from gtsam::noiseModel::mEstimator::Base | |
enum | ReweightScheme { Scalar, Block } |
typedef boost::shared_ptr< Base > | shared_ptr |
Public Member Functions | |
bool | equals (const Base &expected, double tol=1e-8) const override |
GemanMcClure (double c=1.0, const ReweightScheme reweight=Block) | |
double | loss (double distance) const override |
void | print (const std::string &s) const override |
double | weight (double distance) const override |
~GemanMcClure () override | |
Public Member Functions inherited from gtsam::noiseModel::mEstimator::Base | |
Base (const ReweightScheme reweight=Block) | |
void | reweight (Vector &error) const |
void | reweight (std::vector< Matrix > &A, Vector &error) const |
void | reweight (Matrix &A, Vector &error) const |
void | reweight (Matrix &A1, Matrix &A2, Vector &error) const |
void | reweight (Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const |
double | sqrtWeight (double distance) const |
Vector | sqrtWeight (const Vector &error) const |
Vector | weight (const Vector &error) const |
virtual | ~Base () |
Static Public Member Functions | |
static shared_ptr | Create (double k, const ReweightScheme reweight=Block) |
Protected Attributes | |
double | c_ |
Protected Attributes inherited from gtsam::noiseModel::mEstimator::Base | |
ReweightScheme | reweight_ |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | boost::serialization::access |
GemanMcClure implements the "Geman-McClure" robust error model (Zhang97ivc).
Note that Geman-McClure weight function uses the parameter c == 1.0, but here it's allowed to use different values, so we actually have the generalized Geman-McClure from (Agarwal15phd).
Definition at line 285 of file LossFunctions.h.
typedef boost::shared_ptr<GemanMcClure> gtsam::noiseModel::mEstimator::GemanMcClure::shared_ptr |
Definition at line 287 of file LossFunctions.h.
gtsam::noiseModel::mEstimator::GemanMcClure::GemanMcClure | ( | double | c = 1.0 , |
const ReweightScheme | reweight = Block |
||
) |
Definition at line 310 of file LossFunctions.cpp.
|
inlineoverride |
Definition at line 290 of file LossFunctions.h.
|
static |
Definition at line 337 of file LossFunctions.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 331 of file LossFunctions.cpp.
|
overridevirtual |
Reimplemented from gtsam::noiseModel::mEstimator::Base.
Definition at line 321 of file LossFunctions.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 327 of file LossFunctions.cpp.
|
inlineprivate |
Definition at line 304 of file LossFunctions.h.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 314 of file LossFunctions.cpp.
|
friend |
Serialization function
Definition at line 302 of file LossFunctions.h.
|
protected |
Definition at line 298 of file LossFunctions.h.