#include <LevenbergMarquardtState.h>
|
GaussianFactorGraph | buildDampedSystem (GaussianFactorGraph damped) const |
| Build a damped system for a specific lambda, vanilla version. More...
|
|
GaussianFactorGraph | buildDampedSystem (GaussianFactorGraph damped, const VectorValues &sqrtHessianDiagonal) const |
| Build a damped system, use hessianDiagonal per variable (more expensive) More...
|
|
std::unique_ptr< This > | decreaseLambda (const LevenbergMarquardtParams ¶ms, double stepQuality, Values &&newValues, double newError) const |
|
CachedModel * | getCachedModel (size_t dim) const |
|
void | increaseLambda (const LevenbergMarquardtParams ¶ms) |
|
| LevenbergMarquardtState (const Values &initialValues, double _error, double _lambda, double currentFactor, unsigned int _iterations=0, unsigned int totalNumberInnerIterations=0) |
|
| LevenbergMarquardtState (Values &&initialValues, double _error, double _lambda, double currentFactor, unsigned int _iterations=0, unsigned int totalNumberInnerIterations=0) |
|
| NonlinearOptimizerState (const Values &values, double error, size_t iterations=0) |
|
| NonlinearOptimizerState (Values &&values, double error, size_t iterations=0) |
|
virtual | ~NonlinearOptimizerState () |
|
Definition at line 42 of file LevenbergMarquardtState.h.
◆ This
◆ LevenbergMarquardtState() [1/2]
gtsam::internal::LevenbergMarquardtState::LevenbergMarquardtState |
( |
const Values & |
initialValues, |
|
|
double |
_error, |
|
|
double |
_lambda, |
|
|
double |
currentFactor, |
|
|
unsigned int |
_iterations = 0 , |
|
|
unsigned int |
totalNumberInnerIterations = 0 |
|
) |
| |
|
inline |
◆ LevenbergMarquardtState() [2/2]
gtsam::internal::LevenbergMarquardtState::LevenbergMarquardtState |
( |
Values && |
initialValues, |
|
|
double |
_error, |
|
|
double |
_lambda, |
|
|
double |
currentFactor, |
|
|
unsigned int |
_iterations = 0 , |
|
|
unsigned int |
totalNumberInnerIterations = 0 |
|
) |
| |
|
inline |
◆ buildDampedSystem() [1/2]
◆ buildDampedSystem() [2/2]
◆ decreaseLambda()
std::unique_ptr<This> gtsam::internal::LevenbergMarquardtState::decreaseLambda |
( |
const LevenbergMarquardtParams & |
params, |
|
|
double |
stepQuality, |
|
|
Values && |
newValues, |
|
|
double |
newError |
|
) |
| const |
|
inline |
◆ getCachedModel()
CachedModel* gtsam::internal::LevenbergMarquardtState::getCachedModel |
( |
size_t |
dim | ) |
const |
|
inline |
◆ increaseLambda()
◆ currentFactor
double gtsam::internal::LevenbergMarquardtState::currentFactor |
◆ lambda
double gtsam::internal::LevenbergMarquardtState::lambda |
◆ noiseModelCache
std::vector<CachedModel> gtsam::internal::LevenbergMarquardtState::noiseModelCache |
|
mutable |
◆ totalNumberInnerIterations
int gtsam::internal::LevenbergMarquardtState::totalNumberInnerIterations |
The documentation for this struct was generated from the following file: