C++ API

Solver API

teaser/registration.h defines the core registration solver API which provides users with the ability to solve 3D registration problems given correspondences.

Registration Solution

struct teaser::RegistrationSolution

Struct to hold solution to a registration problem

Public Members

bool valid = true
double scale
Eigen::Vector3d translation
Eigen::Matrix3d rotation

7-DoF Solver

class teaser::RobustRegistrationSolver

Solve registration problems robustly.

For more information, please refer to: H. Yang, J. Shi, and L. Carlone, “TEASER: Fast and Certifiable Point Cloud Registration,” arXiv:2001.07715 [cs, math], Jan. 2020.

Public Types

enum ROTATION_ESTIMATION_ALGORITHM

An enum class representing the available GNC rotation estimation algorithms.

GNC_TLS: see H. Yang, P. Antonante, V. Tzoumas, and L. Carlone, “Graduated Non-Convexity for Robust Spatial Perception: From Non-Minimal Solvers to Global Outlier Rejection,” arXiv:1909.08605 [cs, math], Sep. 2019.

FGR: see Q.-Y. Zhou, J. Park, and V. Koltun, “Fast Global Registration,” in Computer Vision – ECCV 2016, Cham, 2016, vol. 9906, pp. 766–782. and H. Yang, P. Antonante, V. Tzoumas, and L. Carlone, “Graduated Non-Convexity for Robust Spatial Perception: From Non-Minimal Solvers to Global Outlier Rejection,” arXiv:1909.08605 [cs, math], Sep. 2019.

Values:

enumerator GNC_TLS = 0
enumerator FGR = 1
enum INLIER_SELECTION_MODE

Enum representing the type of graph-based inlier selection algorithm to use

PMC_EXACT: Use PMC to find exact clique from the inlier graph PMC_HEU: Use PMC’s heuristic finder to find approximate max clique KCORE_HEU: Use k-core heuristic to select inliers NONE: No inlier selection

Values:

enumerator PMC_EXACT = 0
enumerator PMC_HEU = 1
enumerator KCORE_HEU = 2
enumerator NONE = 3
enum INLIER_GRAPH_FORMULATION

Enum representing the formulation of the TIM graph after maximum clique filtering.

CHAIN: formulate TIMs by only calculating the TIMs for consecutive measurements COMPLETE: formulate a fully connected TIM graph

Values:

enumerator CHAIN = 0
enumerator COMPLETE = 1

Public Functions

RobustRegistrationSolver(const Params &params)

A constructor that takes in parameters and initialize the estimators accordingly.

This is the preferred way of initializing the different estimators, instead of setting each estimator one by one.

Parameters
  • params:

Eigen::Matrix<double, 3, Eigen::Dynamic> computeTIMs(const Eigen::Matrix<double, 3, Eigen::Dynamic> &v, Eigen::Matrix<int, 2, Eigen::Dynamic> *map)

Given a 3-by-N matrix representing points, return Translation Invariant Measurements (TIMs)

Return

a 3-by-(N-1)*N matrix representing TIMs

Parameters
  • v: a 3-by-N matrix

RegistrationSolution solve(const teaser::PointCloud &src_cloud, const teaser::PointCloud &dst_cloud, const std::vector<std::pair<int, int>> correspondences)

Solve for scale, translation and rotation.

Parameters
  • src_cloud: source point cloud (to be transformed)

  • dst_cloud: target point cloud (after transformation)

  • correspondences: A vector of tuples representing the correspondences between pairs of points in the two clouds

RegistrationSolution solve(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst)

Solve for scale, translation and rotation. Assumes v2 is v1 after transformation.

Parameters
  • v1:

  • v2:

double solveForScale(const Eigen::Matrix<double, 3, Eigen::Dynamic> &v1, const Eigen::Matrix<double, 3, Eigen::Dynamic> &v2)

Solve for scale. Assume v2 = s * R * v1, this function estimates s.

Parameters
  • v1:

  • v2:

Eigen::Vector3d solveForTranslation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &v1, const Eigen::Matrix<double, 3, Eigen::Dynamic> &v2)

Solve for translation.

Parameters
  • v1:

  • v2:

Eigen::Matrix3d solveForRotation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &v1, const Eigen::Matrix<double, 3, Eigen::Dynamic> &v2)

Solve for rotation. Assume v2 = R * v1, this function estimates find R.

Parameters
  • v1:

  • v2:

double getGNCRotationCostAtTermination()

Return the cost at termination of the GNC rotation solver. Can be used to assess the quality of the solution.

Return

cost at termination of the GNC solver. Undefined if run before running the solver.

RegistrationSolution getSolution()

Return the solution to the registration problem.

Return

void setScaleEstimator(std::unique_ptr<AbstractScaleSolver> estimator)

Set the scale estimator used

Parameters
  • estimator:

void setRotationEstimator(std::unique_ptr<GNCRotationSolver> estimator)

Set the rotation estimator used.

Note: due to the fact that rotation estimator takes in a noise bound that is dependent on the estimated scale, make sure to set the correct params before calling solve.

Parameters
  • estimator:

void setTranslationEstimator(std::unique_ptr<AbstractTranslationSolver> estimator)

Set the translation estimator used.

Parameters
  • estimator:

Eigen::Matrix<bool, 1, Eigen::Dynamic> getScaleInliersMask()

Return a boolean Eigen row vector indicating whether specific measurements are inliers according to scales.

Return

a 1-by-(number of TIMs) boolean Eigen matrix

Eigen::Matrix<int, 2, Eigen::Dynamic> getScaleInliersMap()

Return the index map for scale inliers (equivalent to the index map for TIMs).

Return

a 2-by-(number of TIMs) Eigen matrix. Entries in one column represent the indices of the two measurements used to calculate the corresponding TIM.

std::vector<std::tuple<int, int>> getScaleInliers()

Return inlier TIMs from scale estimation

Return

a vector of tuples. Entries in each tuple represent the indices of the two measurements used to calculate the corresponding TIM: measurement at indice 0 minus measurement at indice 1.

Eigen::Matrix<bool, 1, Eigen::Dynamic> getRotationInliersMask()

Return a boolean Eigen row vector indicating whether specific measurements are inliers according to the rotation solver.

Return

a 1-by-(size of TIMs used in rotation estimation) boolean Eigen matrix. It is equivalent to a binary mask on the TIMs used in rotation estimation, with true representing that the measurement is an inlier after rotation estimation.

Eigen::Matrix<int, 1, Eigen::Dynamic> getRotationInliersMap()

Return the index map for translation inliers (equivalent to max clique). /TODO: This is obsolete now. Remove or update

Return

a 1-by-(size of max clique) Eigen matrix. Entries represent the indices of the original measurements.

std::vector<int> getRotationInliers()

Return inliers from rotation estimation

Return

a vector of indices of TIMs passed to rotation estimator deemed as inliers by rotation estimation. Note that depending on the rotation_tim_graph parameter, number of TIMs passed to rotation estimation will be different.

Eigen::Matrix<bool, 1, Eigen::Dynamic> getTranslationInliersMask()

Return a boolean Eigen row vector indicating whether specific measurements are inliers according to translation measurements.

Return

a 1-by-(size of max clique) boolean Eigen matrix. It is equivalent to a binary mask on the inlier max clique, with true representing that the measurement is an inlier after translation estimation.

Eigen::Matrix<int, 1, Eigen::Dynamic> getTranslationInliersMap()

Return the index map for translation inliers (equivalent to max clique).

Return

a 1-by-(size of max clique) Eigen matrix. Entries represent the indices of the original measurements.

std::vector<int> getTranslationInliers()

Return inliers from rotation estimation

Return

a vector of indices of measurements deemed as inliers by rotation estimation

std::vector<int> getInlierMaxClique()

Return a boolean Eigen row vector indicating whether specific measurements are inliers according to translation measurements.

Return

Eigen::Matrix<double, 3, Eigen::Dynamic> getSrcTIMs()

Get TIMs built from source point cloud.

Return

Eigen::Matrix<double, 3, Eigen::Dynamic> getDstTIMs()

Get TIMs built from target point cloud.

Return

Eigen::Matrix<double, 3, Eigen::Dynamic> getMaxCliqueSrcTIMs()

Get src TIMs built after max clique pruning.

Return

Eigen::Matrix<double, 3, Eigen::Dynamic> getMaxCliqueDstTIMs()

Get dst TIMs built after max clique pruning.

Return

Eigen::Matrix<int, 2, Eigen::Dynamic> getSrcTIMsMap()

Get the index map of the TIMs built from source point cloud.

Return

Eigen::Matrix<int, 2, Eigen::Dynamic> getDstTIMsMap()

Get the index map of the TIMs built from target point cloud.

Return

Eigen::Matrix<int, 2, Eigen::Dynamic> getSrcTIMsMapForRotation()

Get the index map of the TIMs used in rotation estimation.

Return

Eigen::Matrix<int, 2, Eigen::Dynamic> getDstTIMsMapForRotation()

Get the index map of the TIMs used in rotation estimation.

Return

void reset(const Params &params)

Reset the solver using the provided params

Parameters

Params getParams()

Return the params

Return

a Params truct

struct Params

A struct representing params for initializing the RobustRegistrationSolver

Note: the default values needed to be changed accordingly for best performance.

Public Members

double noise_bound = 0.01

A bound on the noise of each provided measurement.

double cbar2 = 1

Square of the ratio between acceptable noise and noise bound. Usually set to 1.

bool estimate_scaling = true

Whether the scale is known. If set to False, the solver assumes no scale differences between the src and dst points. If set to True, the solver will first solve for scale.

When the solver does not estimate scale, it solves the registration problem much faster.

ROTATION_ESTIMATION_ALGORITHM rotation_estimation_algorithm = ROTATION_ESTIMATION_ALGORITHM::GNC_TLS

Which algorithm to use to estimate rotations.

double rotation_gnc_factor = 1.4

Factor to multiple/divide the control parameter in the GNC algorithm.

For FGR: the algorithm divides the control parameter by the factor every iteration. For GNC-TLS: the algorithm multiples the control parameter by the factor every iteration.

size_t rotation_max_iterations = 100

Maximum iterations allowed for the GNC rotation estimators.

double rotation_cost_threshold = 1e-6

Cost threshold for the GNC rotation estimators.

For FGR / GNC-TLS algorithm, the cost thresholds represent different meanings. For FGR: the cost threshold compares with the computed cost at each iteration For GNC-TLS: the cost threshold compares with the difference between costs of consecutive iterations.

INLIER_GRAPH_FORMULATION rotation_tim_graph = INLIER_GRAPH_FORMULATION::CHAIN

Type of TIM graph given to GNC rotation solver

INLIER_SELECTION_MODE inlier_selection_mode = INLIER_SELECTION_MODE::PMC_EXACT

Type of the inlier selection.

double kcore_heuristic_threshold = 0.5

The threshold ratio for determining whether to skip max clique and go straightly to GNC rotation estimation. Set this to 1 to always use exact max clique selection, 0 to always skip exact max clique selection.

Attention

Note that the use_max_clique option takes precedence. In other words, if use_max_clique is set to false, then kcore_heuristic_threshold will be ignored. If use_max_clique is set to true, then the following will happen: if the max core number of the inlier graph is lower than the kcore_heuristic_threshold as a percentage of the total nodes in the inlier graph, then the code will preceed to call the max clique finder. Otherwise, the graph will be directly fed to the GNC rotation solver.

bool use_max_clique = true

bool max_clique_exact_solution = true

double max_clique_time_limit = 3600

Time limit on running the max clique algorithm (in seconds).

Translation Solver

class teaser::TLSTranslationSolver : public teaser::AbstractTranslationSolver

Perform translation estimation using truncated least-squares (TLS)

Public Functions

void solveForTranslation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, Eigen::Vector3d *translation, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) override

Estimate translation between src and dst points. Assume dst = src + t.

Parameters
  • src:

  • dst:

  • translation: output parameter for the translation vector

  • inliers: output parameter for detected outliers

class teaser::AbstractTranslationSolver

Abstract virtual class for decoupling specific translation estimation method implementations with interfaces.

Subclassed by teaser::TLSTranslationSolver

Public Functions

void solveForTranslation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, Eigen::Vector3d *translation, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) = 0

Pure virtual method for solving translation. Different implementations may have different assumptions about input data.

Return

estimated translation vector

Parameters
  • src:

  • dst:

Rotation Solver

class teaser::GNCTLSRotationSolver : public teaser::GNCRotationSolver

Use GNC-TLS to solve rotation estimation problems.

For more information, please refer to: H. Yang, P. Antonante, V. Tzoumas, and L. Carlone, “Graduated Non-Convexity for Robust Spatial Perception: From Non-Minimal Solvers to Global Outlier Rejection,” arXiv:1909.08605 [cs, math], Sep. 2019.

Public Functions

GNCTLSRotationSolver(Params params)

Parametrized constructor

Parameters
  • params:

void solveForRotation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, Eigen::Matrix3d *rotation, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) override

Estimate rotation between src & dst using GNC-TLS method

Parameters
  • src:

  • dst:

  • rotation:

  • inliers:

class teaser::FastGlobalRegistrationSolver : public teaser::GNCRotationSolver

Use Fast Global Registration to solve for pairwise registration problems

For more information, please see the original paper on FGR: Q.-Y. Zhou, J. Park, and V. Koltun, “Fast Global Registration,” in Computer Vision – ECCV 2016, Cham, 2016, vol. 9906, pp. 766–782. Notice that our implementation differ from the paper on the estimation of T matrix. We only estimate rotation, instead of rotation and translation.

Public Functions

FastGlobalRegistrationSolver() = delete

Remove default constructor

FastGlobalRegistrationSolver(Params params)

Parametrized constructor

Parameters
  • params:

  • rotation_only:

void solveForRotation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, Eigen::Matrix3d *rotation, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) override

Solve a pairwise registration problem given two sets of points. Notice that we assume no scale difference between v1 & v2.

Return

a RegistrationSolution struct.

Parameters
  • src:

  • dst:

class teaser::AbstractRotationSolver

Abstract virtual class for decoupling specific rotation estimation method implementations with interfaces.

Subclassed by teaser::GNCRotationSolver

Public Functions

void solveForRotation(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, Eigen::Matrix3d *rotation, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) = 0

Pure virtual method for solving rotation. Different implementations may have different assumptions about input data.

Return

estimated rotation matrix (R)

Parameters
  • src:

  • dst:

Scale Solver

class teaser::TLSScaleSolver : public teaser::AbstractScaleSolver

Perform scale estimation using truncated least-squares (TLS)

Public Functions

void solveForScale(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, double *scale, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) override

Use TLS (adaptive voting) to solve for scale. Assume dst = s * R * src

Return

a double indicating the estimated scale

Parameters
  • src:

  • dst:

class teaser::ScaleInliersSelector : public teaser::AbstractScaleSolver

Perform outlier pruning / inlier selection based on scale. This class does not perform scale estimation. Rather, it estimates outliers based on the assumption that there is no scale difference between the two provided vector of points.

Public Functions

void solveForScale(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, double *scale, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) override

Assume dst = src + noise. The scale output will always be set to 1.

Parameters
  • src: [in] a vector of points

  • dst: [in] a vector of points

  • scale: [out] a constant of 1

  • inliers: [out] a row vector of booleans indicating whether a measurement is an inlier

class teaser::AbstractScaleSolver

Abstract virtual class for decoupling specific scale estimation methods with interfaces.

Subclassed by teaser::ScaleInliersSelector, teaser::TLSScaleSolver

Public Functions

void solveForScale(const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, double *scale, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers) = 0

Pure virtual method for solving scale. Different implementations may have different assumptions about input data.

Return

estimated scale (s)

Parameters
  • src:

  • dst:

TLS Estimator

class teaser::ScalarTLSEstimator

Performs scalar truncated least squares estimation

Public Functions

void estimate(const Eigen::RowVectorXd &X, const Eigen::RowVectorXd &ranges, double *estimate, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers)

Use truncated least squares method to estimate true x given measurements X TODO: call measurements Z or Y to avoid confusion with x TODO: specify which type/size is x and X in the comments

Copyright 2020, Massachusetts Institute of Technology, Cambridge, MA 02139 All Rights Reserved Authors: Jingnan Shi, et al. (see THANKS for the full author list) See LICENSE for the license information

Parameters
  • X: Available measurements

  • ranges: Maximum admissible errors for measurements X

  • estimate: (output) pointer to a double holding the estimate

  • inliers: (output) pointer to a Eigen row vector of inliers

void estimate_tiled(const Eigen::RowVectorXd &X, const Eigen::RowVectorXd &ranges, const int &s, double *estimate, Eigen::Matrix<bool, 1, Eigen::Dynamic> *inliers)

A slightly different implementation of TLS estimate. Use loop tiling to achieve potentially faster performance.

Parameters
  • X: Available measurements

  • ranges: Maximum admissible errors for measurements X

  • s: scale for tiling

  • estimate: (output) pointer to a double holding the estimate

  • inliers: (output) pointer to a Eigen row vector of inliers

Certifier API

teaser/certification.h defines the core certification API which provides users with the ability to certify a rotation solution provided by a GNC-TLS rotation solver.

Certification Result

struct teaser::CertificationResult

Public Members

bool is_optimal = false
double best_suboptimality = -1
std::vector<double> suboptimality_traj

Rotation Certifier

class teaser::DRSCertifier : public teaser::AbstractRotationCertifier

A rotation registration certifier using Douglas–Rachford Splitting (DRS)

Please refer to: [1] H. Yang, J. Shi, and L. Carlone, “TEASER: Fast and Certifiable Point Cloud Registration,” arXiv:2001.07715 [cs, math], Jan. 2020.

Public Types

enum EIG_SOLVER_TYPE

For most cases, the default solvers in Eigen should be used. For extremely large matrices, it may make sense to use Spectra instead.

Solver for eigendecomposition solver / spectral decomposition.

Values:

enumerator EIGEN = 0

Use solvers in the Eigen library.

enumerator SPECTRA = 1

Use solvers in the Spectra library.

Public Functions

DRSCertifier(const Params &params)

Constructor for DRSCertifier that takes in a parameter struct

Parameters
  • params: [in] struct holding all parameters

DRSCertifier(double noise_bound, double cbar2)

Constructor for DRSCertifier

Parameters
  • noise_bound: [in] bound on the noise

  • cbar2: [in] maximal allowed residual^2 to noise bound^2 ratio, usually set to 1

CertificationResult certify(const Eigen::Matrix3d &R_solution, const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, const Eigen::Matrix<bool, 1, Eigen::Dynamic> &theta) override

Main certification function

Copyright (c) 2020, Massachusetts Institute of Technology, Cambridge, MA 02139 All Rights Reserved Authors: Jingnan Shi, et al. (see THANKS for the full author list) See LICENSE for the license information

Return

relative sub-optimality gap

Parameters
  • R_solution: [in] a feasible rotation solution

  • src: [in] vectors under rotation

  • dst: [in] vectors after rotation

  • theta: [in] binary (1 vs. 0) vector indicating inliers vs. outliers

CertificationResult certify(const Eigen::Matrix3d &R_solution, const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, const Eigen::Matrix<double, 1, Eigen::Dynamic> &theta)

Main certification function

Return

relative sub-optimality gap

Parameters
  • R_solution: [in] a feasible rotation solution

  • src: [in] vectors under rotation

  • dst: [in] vectors after rotation

  • theta: [in] binary (1 vs. -1) vector indicating inliers vs. outliers

double computeSubOptimalityGap(const Eigen::MatrixXd &M, double mu, int N)

Compute sub-optimality gap

Return

Parameters
  • M:

  • mu:

  • N:

Eigen::Matrix4d getOmega1(const Eigen::Quaterniond &q)

Get the Omega_1 matrix given a quaternion

Parameters
  • q: an Eigen quaternion

  • omega1: 4-by-4 omega_1 matrix

void getBlockDiagOmega(int Npm, const Eigen::Quaterniond &q, Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> *D_omega)

Get a 4-by-4 block diagonal matrix with each block represents omega_1

Parameters
  • q:

  • theta:

  • D_omega:

void getQCost(const Eigen::Matrix<double, 3, Eigen::Dynamic> &v1, const Eigen::Matrix<double, 3, Eigen::Dynamic> &v2, Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> *Q)

Get Q cost matrix (see Proposition 10 in [1])

Parameters
  • v1: vectors under rotation

  • v2: vectors after rotation

void getOptimalDualProjection(const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> &W, const Eigen::Matrix<double, 1, Eigen::Dynamic> &theta_prepended, const SparseMatrix &A_inv, Eigen::MatrixXd *W_dual)

Given an arbitrary matrix W, project W to the correct dual structure (1) off-diagonal blocks must be skew-symmetric (2) diagonal blocks must satisfy W_00 = - sum(W_ii) (3) W_dual must also satisfy complementary slackness (because M_init satisfies complementary slackness) This projection is optimal in the sense of minimum Frobenious norm

void getLambdaGuess(const Eigen::Matrix<double, 3, 3> &R, const Eigen::Matrix<double, 1, Eigen::Dynamic> &theta, const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, SparseMatrix *lambda_guess)

Generate an initial guess (see Appendix U of [1]).

The initial guess satisfies:

  1. KKT complementary slackness

  2. diagonal blocks of (Q - Lambda_guess) is PSD (except the first diagonal block)

Parameters
  • R: [in] rotation matrix

  • theta: [in] a binary (1 & -1) vector indicating inliers vs. outliers

  • src: [in]

  • dst: [in]

  • lambda_guess: [out]

void getLinearProjection(const Eigen::Matrix<double, 1, Eigen::Dynamic> &theta_prepended, SparseMatrix *A_inv)

Calculate the inverse of the linear projection matrix A mentioned in Theorem 35 of our TEASER paper [1].

Parameters
  • theta_prepended: [in] a binary (1 & -1) vector indicating inliers vs. outliers, with 1 prepended

  • A_inv: [out] inverse of A

struct Params

Parameter struct for DRSCertifier

Public Members

double noise_bound = 0.01

Noise bound for the vectors used for certification

double cbar2 = 1

Square of the ratio between acceptable noise and noise bound. Usually set to 1.

double sub_optimality = 1e-3

Suboptimality gap

This is not a percentage. Multiply by 100 to get a percentage.

double max_iterations = 2e2

Maximum iterations allowed

double gamma_tau = 1.999999

Gamma value (refer to [1] for details)

EIG_SOLVER_TYPE eig_decomposition_solver = EIG_SOLVER_TYPE::EIGEN

Solver for eigendecomposition / spectral decomposition

class teaser::AbstractRotationCertifier

Abstract virtual class representing certification of registration results

Subclassed by teaser::DRSCertifier

Public Functions

CertificationResult certify(const Eigen::Matrix3d &rotation_solution, const Eigen::Matrix<double, 3, Eigen::Dynamic> &src, const Eigen::Matrix<double, 3, Eigen::Dynamic> &dst, const Eigen::Matrix<bool, 1, Eigen::Dynamic> &theta) = 0

Abstract function for certifying rotation estimation results

Return

relative sub-optimality gap

Parameters
  • rotation_solution: [in] a solution to the rotatoin registration problem

  • src: [in] Assume dst = R * src

  • dst: [in] Assume dst = R * src

  • theta: [in] a binary vector indicating inliers vs. outliers