Public Types | Public Member Functions | Public Attributes | List of all members
gtsam::ShonanAveragingParameters< d > Struct Template Reference

Parameters governing optimization etc. More...

#include <ShonanAveraging.h>

Public Types

using Anchor = std::pair< size_t, Rot >
 
using Rot = typename std::conditional< d==2, Rot2, Rot3 >::type
 

Public Member Functions

std::pair< size_t, RotgetAnchor () const
 
double getAnchorWeight () const
 
bool getCertifyOptimality () const
 
double getGaugesWeight () const
 
double getKarcherWeight () const
 
LevenbergMarquardtParams getLMParams () const
 
double getOptimalityThreshold () const
 
bool getUseHuber () const
 
void print (const std::string &s="") const
 Print the parameters and flags used for rotation averaging. More...
 
void setAnchor (size_t index, const Rot &value)
 
void setAnchorWeight (double value)
 
void setCertifyOptimality (bool value)
 
void setGaugesWeight (double value)
 
void setKarcherWeight (double value)
 
void setOptimalityThreshold (double value)
 
void setUseHuber (bool value)
 
 ShonanAveragingParameters (const LevenbergMarquardtParams &lm=LevenbergMarquardtParams::CeresDefaults(), const std::string &method="JACOBI", double optimalityThreshold=-1e-4, double alpha=0.0, double beta=1.0, double gamma=0.0)
 

Public Attributes

double alpha
 weight of anchor-based prior (default 0) More...
 
Anchor anchor
 pose to use as anchor if not Karcher More...
 
double beta
 weight of Karcher-based prior (default 1) More...
 
bool certifyOptimality
 if enabled solution optimality is certified (default true) More...
 
double gamma
 
LevenbergMarquardtParams lm
 LM parameters. More...
 
double optimalityThreshold
 threshold used in checkOptimality More...
 
bool useHuber
 if enabled, the Huber loss is used (default false) More...
 

Detailed Description

template<size_t d>
struct gtsam::ShonanAveragingParameters< d >

Parameters governing optimization etc.

Definition at line 46 of file ShonanAveraging.h.

Member Typedef Documentation

◆ Anchor

template<size_t d>
using gtsam::ShonanAveragingParameters< d >::Anchor = std::pair<size_t, Rot>

Definition at line 49 of file ShonanAveraging.h.

◆ Rot

template<size_t d>
using gtsam::ShonanAveragingParameters< d >::Rot = typename std::conditional<d == 2, Rot2, Rot3>::type

Definition at line 48 of file ShonanAveraging.h.

Constructor & Destructor Documentation

◆ ShonanAveragingParameters()

template<size_t d>
gtsam::ShonanAveragingParameters< d >::ShonanAveragingParameters ( const LevenbergMarquardtParams lm = LevenbergMarquardtParams::CeresDefaults(),
const std::string &  method = "JACOBI",
double  optimalityThreshold = -1e-4,
double  alpha = 0.0,
double  beta = 1.0,
double  gamma = 0.0 
)

Definition at line 50 of file ShonanAveraging.cpp.

Member Function Documentation

◆ getAnchor()

template<size_t d>
std::pair<size_t, Rot> gtsam::ShonanAveragingParameters< d >::getAnchor ( ) const
inline

Definition at line 76 of file ShonanAveraging.h.

◆ getAnchorWeight()

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::getAnchorWeight ( ) const
inline

Definition at line 79 of file ShonanAveraging.h.

◆ getCertifyOptimality()

template<size_t d>
bool gtsam::ShonanAveragingParameters< d >::getCertifyOptimality ( ) const
inline

Definition at line 91 of file ShonanAveraging.h.

◆ getGaugesWeight()

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::getGaugesWeight ( ) const
inline

Definition at line 85 of file ShonanAveraging.h.

◆ getKarcherWeight()

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::getKarcherWeight ( ) const
inline

Definition at line 82 of file ShonanAveraging.h.

◆ getLMParams()

template<size_t d>
LevenbergMarquardtParams gtsam::ShonanAveragingParameters< d >::getLMParams ( ) const
inline

Definition at line 70 of file ShonanAveraging.h.

◆ getOptimalityThreshold()

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::getOptimalityThreshold ( ) const
inline

Definition at line 73 of file ShonanAveraging.h.

◆ getUseHuber()

template<size_t d>
bool gtsam::ShonanAveragingParameters< d >::getUseHuber ( ) const
inline

Definition at line 88 of file ShonanAveraging.h.

◆ print()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::print ( const std::string &  s = "") const
inline

Print the parameters and flags used for rotation averaging.

Definition at line 94 of file ShonanAveraging.h.

◆ setAnchor()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setAnchor ( size_t  index,
const Rot value 
)
inline

Definition at line 75 of file ShonanAveraging.h.

◆ setAnchorWeight()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setAnchorWeight ( double  value)
inline

Definition at line 78 of file ShonanAveraging.h.

◆ setCertifyOptimality()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setCertifyOptimality ( bool  value)
inline

Definition at line 90 of file ShonanAveraging.h.

◆ setGaugesWeight()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setGaugesWeight ( double  value)
inline

Definition at line 84 of file ShonanAveraging.h.

◆ setKarcherWeight()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setKarcherWeight ( double  value)
inline

Definition at line 81 of file ShonanAveraging.h.

◆ setOptimalityThreshold()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setOptimalityThreshold ( double  value)
inline

Definition at line 72 of file ShonanAveraging.h.

◆ setUseHuber()

template<size_t d>
void gtsam::ShonanAveragingParameters< d >::setUseHuber ( bool  value)
inline

Definition at line 87 of file ShonanAveraging.h.

Member Data Documentation

◆ alpha

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::alpha

weight of anchor-based prior (default 0)

Definition at line 55 of file ShonanAveraging.h.

◆ anchor

template<size_t d>
Anchor gtsam::ShonanAveragingParameters< d >::anchor

pose to use as anchor if not Karcher

Definition at line 54 of file ShonanAveraging.h.

◆ beta

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::beta

weight of Karcher-based prior (default 1)

Definition at line 56 of file ShonanAveraging.h.

◆ certifyOptimality

template<size_t d>
bool gtsam::ShonanAveragingParameters< d >::certifyOptimality

if enabled solution optimality is certified (default true)

Definition at line 61 of file ShonanAveraging.h.

◆ gamma

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::gamma

weight of gauge-fixing factors (default 0)

Definition at line 57 of file ShonanAveraging.h.

◆ lm

LM parameters.

Definition at line 52 of file ShonanAveraging.h.

◆ optimalityThreshold

template<size_t d>
double gtsam::ShonanAveragingParameters< d >::optimalityThreshold

threshold used in checkOptimality

Definition at line 53 of file ShonanAveraging.h.

◆ useHuber

template<size_t d>
bool gtsam::ShonanAveragingParameters< d >::useHuber

if enabled, the Huber loss is used (default false)

Definition at line 59 of file ShonanAveraging.h.


The documentation for this struct was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:08