31 #include "../stuff/timeutil.h" 41 OptimizationAlgorithmDogleg::OptimizationAlgorithmDogleg(
BlockSolverBase* solver) :
61 assert(dynamic_cast<BlockSolverBase*>(
_solver) &&
"underlying linear solver is not a block solver");
65 if (iteration == 0 && !online) {
101 double bNormSquared = b.squaredNorm();
102 double alpha = bNormSquared /
_auxVector.dot(b);
105 double hsdNorm =
_hsd.norm();
106 double hgnNorm = -1.;
108 bool solvedGaussNewton =
false;
109 bool goodStep =
false;
115 if (! solvedGaussNewton) {
116 const double minLambda = 1e-12;
117 const double maxLambda = 1e3;
118 solvedGaussNewton =
true;
122 bool solverOk =
false;
150 assert(hgnNorm >= 0. &&
"Norm of the GN step is not computed");
156 else if (hsdNorm >
_delta) {
162 double bmaSquaredNorm =
_auxVector.squaredNorm();
165 beta = (-c + sqrt(c*c + bmaSquaredNorm * (
_delta*
_delta - _hsd.squaredNorm()))) / bmaSquaredNorm;
167 double hsdSqrNorm = _hsd.squaredNorm();
170 assert(beta > 0. && beta < 1 &&
"Error while computing beta");
173 assert(
_hdl.norm() <
_delta + 1e-5 &&
"Computed step does not correspond to the trust region");
185 double newChi =
_optimizer-> activeRobustChi2();
186 double nonLinearGain = currentChi - newChi;
187 if (fabs(linearGain) < 1e-12)
189 double rho = nonLinearGain / linearGain;
203 }
while (!goodStep && numTries < _maxTrialsAfterFailure->value());
222 case STEP_SD:
return "Descent";
225 default:
return "Undefined";
virtual void restoreDiagonal()=0
statistics about the optimization
#define __PRETTY_FUNCTION__
static const char * stepType2Str(int stepType)
convert the type into an integer
Eigen::VectorXd _hdl
final dogleg step
double timeResiduals
residuals
virtual ~OptimizationAlgorithmDogleg()
bool _wasPDInAllIterations
the matrix we solve was positive definite in all iterations -> if not apply damping ...
Property< double > * _userDeltaInit
void pop(SparseOptimizer::VertexContainer &vlist)
pop (restore) the estimate a subset of the variables from the stack
virtual bool setLambda(double lambda, bool backup=false)=0
Eigen::VectorXd _hsd
steepest decent step
Property< double > * _initialLambda
void computeActiveErrors()
void discardTop(SparseOptimizer::VertexContainer &vlist)
ignore the latest stored element on the stack, remove it from the stack but do not restore the estima...
Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg.
PropertyMap _properties
the properties of your solver, use this to store the parameters of your solver
double _currentLambda
the damping factor to force positive definite matrix
P * makeProperty(const std::string &name_, const typename P::ValueType &v)
Property< int > * _maxTrialsAfterFailure
double _delta
trust region
Property< double > * _lamdbaFactor
SparseOptimizer * _optimizer
the optimizer the solver is working on
static G2OBatchStatistics * globalStats()
virtual void multiplyHessian(double *dest, const double *src) const =0
double get_monotonic_time()
virtual SolverResult solve(int iteration, bool online=false)
SparseOptimizer * optimizer() const
the optimizer (graph) on which the solver works
virtual void printVerbose(std::ostream &os) const
double * x()
return x, the solution vector
double * b()
return b, the right hand side of the system
virtual bool buildSystem()=0
size_t vectorSize() const
return the size of the solution vector (x) and b
double activeRobustChi2() const
Eigen::VectorXd _auxVector
auxilary vector used to perform multiplications or other stuff
int _lastStep
type of the step taken by the algorithm
double timeQuadraticForm
construct the quadratic form in the graph
void push(SparseOptimizer::VertexContainer &vlist)
push the estimate of a subset of the variables onto a stack
base for the block solvers with some basic function interfaces
virtual bool buildStructure(bool zeroBlocks=false)=0