small_gicp
Public Member Functions | Public Attributes | List of all members
small_gicp::GaussNewtonOptimizer Struct Reference

GaussNewton optimizer. More...

#include <optimizer.hpp>

Public Member Functions

 GaussNewtonOptimizer ()
 
template<typename TargetPointCloud , typename SourcePointCloud , typename TargetTree , typename CorrespondenceRejector , typename TerminationCriteria , typename Reduction , typename Factor , typename GeneralFactor >
RegistrationResult optimize (const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const CorrespondenceRejector &rejector, const TerminationCriteria &criteria, Reduction &reduction, const Eigen::Isometry3d &init_T, std::vector< Factor > &factors, GeneralFactor &general_factor) const
 

Public Attributes

bool verbose
 If true, print debug messages. More...
 
int max_iterations
 Max number of optimization iterations. More...
 
double lambda
 Damping factor (Increasing this makes optimization slow but stable) More...
 

Detailed Description

GaussNewton optimizer.

Constructor & Destructor Documentation

◆ GaussNewtonOptimizer()

small_gicp::GaussNewtonOptimizer::GaussNewtonOptimizer ( )
inline

Member Function Documentation

◆ optimize()

template<typename TargetPointCloud , typename SourcePointCloud , typename TargetTree , typename CorrespondenceRejector , typename TerminationCriteria , typename Reduction , typename Factor , typename GeneralFactor >
RegistrationResult small_gicp::GaussNewtonOptimizer::optimize ( const TargetPointCloud &  target,
const SourcePointCloud &  source,
const TargetTree &  target_tree,
const CorrespondenceRejector &  rejector,
const TerminationCriteria criteria,
Reduction &  reduction,
const Eigen::Isometry3d &  init_T,
std::vector< Factor > &  factors,
GeneralFactor &  general_factor 
) const
inline

Member Data Documentation

◆ lambda

double small_gicp::GaussNewtonOptimizer::lambda

Damping factor (Increasing this makes optimization slow but stable)

◆ max_iterations

int small_gicp::GaussNewtonOptimizer::max_iterations

Max number of optimization iterations.

◆ verbose

bool small_gicp::GaussNewtonOptimizer::verbose

If true, print debug messages.


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