Public Types | Public Member Functions | Private Attributes | List of all members
gtsam::GncOptimizer< GncParameters > Class Template Reference

#include <GncOptimizer.h>

Public Types

typedef GncParameters::OptimizerType BaseOptimizer
 For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimizer. More...
 

Public Member Functions

Vector calculateWeights (const Values &currentEstimate, const double mu)
 Calculate gnc weights. More...
 
bool checkConvergence (const double mu, const Vector &weights, const double cost, const double prev_cost) const
 Check for convergence between consecutive GNC iterations. More...
 
bool checkCostConvergence (const double cost, const double prev_cost) const
 Check convergence of relative cost differences. More...
 
bool checkMuConvergence (const double mu) const
 Check if we have reached the value of mu for which the surrogate loss matches the original loss. More...
 
bool checkWeightsConvergence (const Vector &weights) const
 Check convergence of weights to binary values. More...
 
bool equals (const GncOptimizer &other, double tol=1e-9) const
 Equals. More...
 
const NonlinearFactorGraphgetFactors () const
 Access a copy of the internal factor graph. More...
 
const VectorgetInlierCostThresholds () const
 Get the inlier threshold. More...
 
const GncParameters & getParams () const
 Access a copy of the parameters. More...
 
const ValuesgetState () const
 Access a copy of the internal values. More...
 
const VectorgetWeights () const
 Access a copy of the GNC weights. More...
 
 GncOptimizer (const NonlinearFactorGraph &graph, const Values &initialValues, const GncParameters &params=GncParameters())
 Constructor. More...
 
double initializeMu () const
 Initialize the gnc parameter mu such that loss is approximately convex (remark 5 in GNC paper). More...
 
Vector initializeWeightsFromKnownInliersAndOutliers () const
 
NonlinearFactorGraph makeWeightedGraph (const Vector &weights) const
 Create a graph where each factor is weighted by the gnc weights. More...
 
Values optimize ()
 Compute optimal solution using graduated non-convexity. More...
 
void setInlierCostThresholds (const double inth)
 
void setInlierCostThresholds (const Vector &inthVec)
 
void setInlierCostThresholdsAtProbability (const double alpha)
 
void setWeights (const Vector w)
 
double updateMu (const double mu) const
 Update the gnc parameter mu to gradually increase nonconvexity. More...
 

Private Attributes

Vector barcSq_
 Inlier thresholds. A factor is considered an inlier if factor.error() < barcSq_[i] (where i is the position of the factor in the factor graph. Note that factor.error() whitens by the covariance. More...
 
NonlinearFactorGraph nfg_
 Original factor graph to be solved by GNC. More...
 
GncParameters params_
 GNC parameters. More...
 
Values state_
 Initial values to be used at each iteration by GNC. More...
 
Vector weights_
 Weights associated to each factor in GNC (this could be a local variable in optimize, but it is useful to make it accessible from outside). More...
 

Detailed Description

template<class GncParameters>
class gtsam::GncOptimizer< GncParameters >

Definition at line 45 of file GncOptimizer.h.

Member Typedef Documentation

◆ BaseOptimizer

template<class GncParameters>
typedef GncParameters::OptimizerType gtsam::GncOptimizer< GncParameters >::BaseOptimizer

For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimizer.

Definition at line 48 of file GncOptimizer.h.

Constructor & Destructor Documentation

◆ GncOptimizer()

template<class GncParameters>
gtsam::GncOptimizer< GncParameters >::GncOptimizer ( const NonlinearFactorGraph graph,
const Values initialValues,
const GncParameters &  params = GncParameters() 
)
inline

Constructor.

Definition at line 59 of file GncOptimizer.h.

Member Function Documentation

◆ calculateWeights()

template<class GncParameters>
Vector gtsam::GncOptimizer< GncParameters >::calculateWeights ( const Values currentEstimate,
const double  mu 
)
inline

Calculate gnc weights.

Definition at line 423 of file GncOptimizer.h.

◆ checkConvergence()

template<class GncParameters>
bool gtsam::GncOptimizer< GncParameters >::checkConvergence ( const double  mu,
const Vector weights,
const double  cost,
const double  prev_cost 
) const
inline

Check for convergence between consecutive GNC iterations.

Definition at line 391 of file GncOptimizer.h.

◆ checkCostConvergence()

template<class GncParameters>
bool gtsam::GncOptimizer< GncParameters >::checkCostConvergence ( const double  cost,
const double  prev_cost 
) const
inline

Check convergence of relative cost differences.

Definition at line 353 of file GncOptimizer.h.

◆ checkMuConvergence()

template<class GncParameters>
bool gtsam::GncOptimizer< GncParameters >::checkMuConvergence ( const double  mu) const
inline

Check if we have reached the value of mu for which the surrogate loss matches the original loss.

Definition at line 334 of file GncOptimizer.h.

◆ checkWeightsConvergence()

template<class GncParameters>
bool gtsam::GncOptimizer< GncParameters >::checkWeightsConvergence ( const Vector weights) const
inline

Check convergence of weights to binary values.

Definition at line 364 of file GncOptimizer.h.

◆ equals()

template<class GncParameters>
bool gtsam::GncOptimizer< GncParameters >::equals ( const GncOptimizer< GncParameters > &  other,
double  tol = 1e-9 
) const
inline

Equals.

Definition at line 169 of file GncOptimizer.h.

◆ getFactors()

template<class GncParameters>
const NonlinearFactorGraph& gtsam::GncOptimizer< GncParameters >::getFactors ( ) const
inline

Access a copy of the internal factor graph.

Definition at line 154 of file GncOptimizer.h.

◆ getInlierCostThresholds()

template<class GncParameters>
const Vector& gtsam::GncOptimizer< GncParameters >::getInlierCostThresholds ( ) const
inline

Get the inlier threshold.

Definition at line 166 of file GncOptimizer.h.

◆ getParams()

template<class GncParameters>
const GncParameters& gtsam::GncOptimizer< GncParameters >::getParams ( ) const
inline

Access a copy of the parameters.

Definition at line 160 of file GncOptimizer.h.

◆ getState()

template<class GncParameters>
const Values& gtsam::GncOptimizer< GncParameters >::getState ( ) const
inline

Access a copy of the internal values.

Definition at line 157 of file GncOptimizer.h.

◆ getWeights()

template<class GncParameters>
const Vector& gtsam::GncOptimizer< GncParameters >::getWeights ( ) const
inline

Access a copy of the GNC weights.

Definition at line 163 of file GncOptimizer.h.

◆ initializeMu()

template<class GncParameters>
double gtsam::GncOptimizer< GncParameters >::initializeMu ( ) const
inline

Initialize the gnc parameter mu such that loss is approximately convex (remark 5 in GNC paper).

Definition at line 274 of file GncOptimizer.h.

◆ initializeWeightsFromKnownInliersAndOutliers()

template<class GncParameters>
Vector gtsam::GncOptimizer< GncParameters >::initializeWeightsFromKnownInliersAndOutliers ( ) const
inline

Definition at line 176 of file GncOptimizer.h.

◆ makeWeightedGraph()

template<class GncParameters>
NonlinearFactorGraph gtsam::GncOptimizer< GncParameters >::makeWeightedGraph ( const Vector weights) const
inline

Create a graph where each factor is weighted by the gnc weights.

Definition at line 398 of file GncOptimizer.h.

◆ optimize()

template<class GncParameters>
Values gtsam::GncOptimizer< GncParameters >::optimize ( )
inline

Compute optimal solution using graduated non-convexity.

Definition at line 185 of file GncOptimizer.h.

◆ setInlierCostThresholds() [1/2]

template<class GncParameters>
void gtsam::GncOptimizer< GncParameters >::setInlierCostThresholds ( const double  inth)
inline

Set the maximum weighted residual error for an inlier (same for all factors). For a factor in the form f(x) = 0.5 * || r(x) ||^2_Omega, the inlier threshold is the largest value of f(x) for the corresponding measurement to be considered an inlier. In other words, an inlier at x is such that 0.5 * || r(x) ||^2_Omega <= barcSq. Assuming an isotropic measurement covariance sigma^2 * Identity, the cost becomes: 0.5 * 1/sigma^2 || r(x) ||^2 <= barcSq. Hence || r(x) ||^2 <= 2 * barcSq * sigma^2.

Definition at line 117 of file GncOptimizer.h.

◆ setInlierCostThresholds() [2/2]

template<class GncParameters>
void gtsam::GncOptimizer< GncParameters >::setInlierCostThresholds ( const Vector inthVec)
inline

Set the maximum weighted residual error for an inlier (one for each factor). For a factor in the form f(x) = 0.5 * || r(x) ||^2_Omega, the inlier threshold is the largest value of f(x) for the corresponding measurement to be considered an inlier. In other words, an inlier at x is such that 0.5 * || r(x) ||^2_Omega <= barcSq.

Definition at line 125 of file GncOptimizer.h.

◆ setInlierCostThresholdsAtProbability()

template<class GncParameters>
void gtsam::GncOptimizer< GncParameters >::setInlierCostThresholdsAtProbability ( const double  alpha)
inline

Set the maximum weighted residual error threshold by specifying the probability alpha that the inlier residuals are smaller than that threshold

Definition at line 132 of file GncOptimizer.h.

◆ setWeights()

template<class GncParameters>
void gtsam::GncOptimizer< GncParameters >::setWeights ( const Vector  w)
inline

Set weights for each factor. This is typically not needed, but provides an extra interface for the user to initialize the weightst

Definition at line 144 of file GncOptimizer.h.

◆ updateMu()

template<class GncParameters>
double gtsam::GncOptimizer< GncParameters >::updateMu ( const double  mu) const
inline

Update the gnc parameter mu to gradually increase nonconvexity.

Definition at line 319 of file GncOptimizer.h.

Member Data Documentation

◆ barcSq_

template<class GncParameters>
Vector gtsam::GncOptimizer< GncParameters >::barcSq_
private

Inlier thresholds. A factor is considered an inlier if factor.error() < barcSq_[i] (where i is the position of the factor in the factor graph. Note that factor.error() whitens by the covariance.

Definition at line 55 of file GncOptimizer.h.

◆ nfg_

template<class GncParameters>
NonlinearFactorGraph gtsam::GncOptimizer< GncParameters >::nfg_
private

Original factor graph to be solved by GNC.

Definition at line 51 of file GncOptimizer.h.

◆ params_

template<class GncParameters>
GncParameters gtsam::GncOptimizer< GncParameters >::params_
private

GNC parameters.

Definition at line 53 of file GncOptimizer.h.

◆ state_

template<class GncParameters>
Values gtsam::GncOptimizer< GncParameters >::state_
private

Initial values to be used at each iteration by GNC.

Definition at line 52 of file GncOptimizer.h.

◆ weights_

template<class GncParameters>
Vector gtsam::GncOptimizer< GncParameters >::weights_
private

Weights associated to each factor in GNC (this could be a local variable in optimize, but it is useful to make it accessible from outside).

Definition at line 54 of file GncOptimizer.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:19