#include <LossFunctions.h>
Public Types | |
typedef boost::shared_ptr< L2WithDeadZone > | 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 |
L2WithDeadZone (double k=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 |
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 | k_ |
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 |
L2WithDeadZone implements a standard L2 penalty, but with a dead zone of width 2*k, centered at the origin. The resulting penalty within the dead zone is always zero, and grows quadratically outside the dead zone. In this sense, the L2WithDeadZone penalty is "robust to inliers", rather than being robust to outliers. This penalty can be used to create barrier functions in a general way.
Definition at line 346 of file LossFunctions.h.
typedef boost::shared_ptr<L2WithDeadZone> gtsam::noiseModel::mEstimator::L2WithDeadZone::shared_ptr |
Definition at line 351 of file LossFunctions.h.
gtsam::noiseModel::mEstimator::L2WithDeadZone::L2WithDeadZone | ( | double | k = 1.0 , |
const ReweightScheme | reweight = Block |
||
) |
Definition at line 387 of file LossFunctions.cpp.
|
static |
Definition at line 418 of file LossFunctions.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 412 of file LossFunctions.cpp.
|
overridevirtual |
Reimplemented from gtsam::noiseModel::mEstimator::Base.
Definition at line 403 of file LossFunctions.cpp.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 408 of file LossFunctions.cpp.
|
inlineprivate |
Definition at line 364 of file LossFunctions.h.
|
overridevirtual |
Implements gtsam::noiseModel::mEstimator::Base.
Definition at line 394 of file LossFunctions.cpp.
|
friend |
Serialization function
Definition at line 362 of file LossFunctions.h.
|
protected |
Definition at line 348 of file LossFunctions.h.