Classes | Typedefs | Enumerations | Functions
Mp2p_icp_grp

Classes

struct  mp2p_icp::color_mode_t
 
class  mp2p_icp::ICP
 
class  mp2p_icp::ICP_LibPointmatcher
 
class  mp2p_icp::LogRecord
 
struct  mp2p_icp::MatchContext
 
struct  mp2p_icp::matched_line_t
 
struct  mp2p_icp::matched_plane_t
 
class  mp2p_icp::Matcher
 
class  mp2p_icp::Matcher_Point2Line
 
class  mp2p_icp::Matcher_Point2Plane
 
class  mp2p_icp::Matcher_Points_Base
 
class  mp2p_icp::Matcher_Points_DistanceThreshold
 
class  mp2p_icp::Matcher_Points_InlierRatio
 
class  mp2p_icp::metric_map_t
 Generic container of pointcloud(s), extracted features and other maps. More...
 
struct  mp2p_icp::OptimalTF_GN_Parameters
 
struct  mp2p_icp::OptimalTF_Result
 
struct  mp2p_icp::OutlierIndices
 
struct  mp2p_icp::Pairings
 
struct  mp2p_icp::pairings_render_params_t
 
struct  mp2p_icp::PairWeights
 
struct  mp2p_icp::Parameters
 
struct  mp2p_icp::plane_patch_t
 
struct  mp2p_icp::point_line_pair_t
 
struct  mp2p_icp::point_plane_pair_t
 
struct  mp2p_icp::pointcloud_bitfield_t
 
class  mp2p_icp::QualityEvaluator
 
class  mp2p_icp::QualityEvaluator_PairedRatio
 
class  mp2p_icp::QualityEvaluator_RangeImageSimilarity
 
class  mp2p_icp::QualityEvaluator_Voxels
 
struct  mp2p_icp::render_params_lines_t
 
struct  mp2p_icp::render_params_pairings_pt2ln_t
 
struct  mp2p_icp::render_params_pairings_pt2pl_t
 
struct  mp2p_icp::render_params_pairings_pt2pt_t
 
struct  mp2p_icp::render_params_planes_t
 
struct  mp2p_icp::render_params_point_layer_t
 
struct  mp2p_icp::render_params_points_t
 
struct  mp2p_icp::render_params_t
 
struct  mp2p_icp::Results
 
class  mp2p_icp::Solver
 
class  mp2p_icp::Solver_GaussNewton
 
class  mp2p_icp::Solver_Horn
 
class  mp2p_icp::Solver_OLAE
 
struct  mp2p_icp::SolverContext
 
struct  mp2p_icp::VisitCorrespondencesStats
 
struct  mp2p_icp::WeightParameters
 

Typedefs

using mp2p_icp::layer_name_t = std::string
 
using mp2p_icp::MatchedLineList = std::vector< matched_line_t >
 
using mp2p_icp::MatchedPlaneList = std::vector< matched_plane_t >
 
using mp2p_icp::MatchedPointLineList = std::vector< point_line_pair_t >
 
using mp2p_icp::MatchedPointPlaneList = std::vector< point_plane_pair_t >
 

Enumerations

enum  mp2p_icp::Coordinate : uint8_t { mp2p_icp::Coordinate::X = 0, mp2p_icp::Coordinate::Y, mp2p_icp::Coordinate::Z }
 
enum  mp2p_icp::IterTermReason : uint8_t {
  mp2p_icp::IterTermReason::Undefined = 0, mp2p_icp::IterTermReason::NoPairings, mp2p_icp::IterTermReason::SolverError, mp2p_icp::IterTermReason::MaxIterations,
  mp2p_icp::IterTermReason::Stalled
}
 

Functions

mrpt::math::CMatrixDouble66 mp2p_icp::covariance (const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
 
mrpt::math::CVectorFixedDouble< 4 > mp2p_icp::error_line2line (const mp2p_icp::matched_line_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 4, 12 >> jacobian=std::nullopt)
 
mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_plane2plane (const mp2p_icp::matched_plane_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
 
mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2line (const mp2p_icp::point_line_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
 
mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2plane (const mp2p_icp::point_plane_pair_t &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
 
mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2point (const mrpt::tfest::TMatchingPair &pairing, const mrpt::poses::CPose3D &relativePose, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >> jacobian=std::nullopt)
 
PointCloudEigen mp2p_icp::estimate_points_eigen (const float *xs, const float *ys, const float *zs, mrpt::optional_ref< const std::vector< size_t >> indices, std::optional< size_t > totalCount=std::nullopt)
 
std::tuple< mrpt::math::TPoint3D, mrpt::math::TPoint3D > mp2p_icp::eval_centroids_robust (const Pairings &in, const OutlierIndices &outliers)
 
std::tuple< mp2p_icp::ICP::Ptr, mp2p_icp::Parametersmp2p_icp::icp_pipeline_from_yaml (const mrpt::containers::yaml &config, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
 
mrpt::maps::CSimplePointsMap::Ptr mp2p_icp::load_xyz_file (const std::string &fil)
 
mrpt::serialization::CArchive & mp2p_icp::operator<< (mrpt::serialization::CArchive &out, const Pairings &obj)
 
mrpt::serialization::CArchive & mp2p_icp::operator<< (mrpt::serialization::CArchive &out, const Results &obj)
 
mrpt::serialization::CArchive & mp2p_icp::operator>> (mrpt::serialization::CArchive &in, Pairings &obj)
 
mrpt::serialization::CArchive & mp2p_icp::operator>> (mrpt::serialization::CArchive &in, Results &obj)
 
bool mp2p_icp::optimal_tf_gauss_newton (const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
 
bool mp2p_icp::optimal_tf_olae (const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
 
Pairings mp2p_icp::run_matchers (const matcher_list_t &matchers, const metric_map_t &pcGlobal, const metric_map_t &pcLocal, const mrpt::poses::CPose3D &local_wrt_global, const MatchContext &mc, const mrpt::optional_ref< MatchState > &userProvidedMS=std::nullopt)
 
template<class LAMBDA , class LAMBDA2 >
void mp2p_icp::visit_correspondences (const Pairings &in, const WeightParameters &wp, const mrpt::math::TPoint3D &ct_local, const mrpt::math::TPoint3D &ct_global, OutlierIndices &in_out_outliers, LAMBDA lambda_each_pair, LAMBDA2 lambda_final, bool normalize_relative_point_vectors, const mrpt::optional_ref< VisitCorrespondencesStats > &outStats=std::nullopt)
 

Detailed Description

Typedef Documentation

◆ layer_name_t

using mp2p_icp::layer_name_t = typedef std::string

Definition at line 22 of file layer_name_t.h.

◆ MatchedLineList

using mp2p_icp::MatchedLineList = typedef std::vector<matched_line_t>

Definition at line 49 of file Pairings.h.

◆ MatchedPlaneList

using mp2p_icp::MatchedPlaneList = typedef std::vector<matched_plane_t>

Definition at line 40 of file Pairings.h.

◆ MatchedPointLineList

using mp2p_icp::MatchedPointLineList = typedef std::vector<point_line_pair_t>

Definition at line 85 of file Pairings.h.

◆ MatchedPointPlaneList

Definition at line 66 of file Pairings.h.

Enumeration Type Documentation

◆ Coordinate

enum mp2p_icp::Coordinate : uint8_t
strong
Enumerator

Definition at line 53 of file render_params.h.

◆ IterTermReason

enum mp2p_icp::IterTermReason : uint8_t
strong

Reason of iterating termination.

Enumerator
Undefined 
NoPairings 
SolverError 
MaxIterations 
Stalled 

Definition at line 18 of file IterTermReason.h.

Function Documentation

◆ covariance()

mrpt::math::CMatrixDouble66 mp2p_icp::covariance ( const Pairings finalPairings,
const mrpt::poses::CPose3D &  finalAlignSolution,
const CovarianceParameters p 
)

Covariance estimation methods for an ICP result.

Definition at line 22 of file covariance.cpp.

◆ error_line2line()

mrpt::math::CVectorFixedDouble< 4 > mp2p_icp::error_line2line ( const mp2p_icp::matched_line_t pairing,
const mrpt::poses::CPose3D &  relativePose,
mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 4, 12 >>  jacobian = std::nullopt 
)

Definition at line 167 of file errorTerms.cpp.

◆ error_plane2plane()

mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_plane2plane ( const mp2p_icp::matched_plane_t pairing,
const mrpt::poses::CPose3D &  relativePose,
mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >>  jacobian = std::nullopt 
)

Definition at line 337 of file errorTerms.cpp.

◆ error_point2line()

mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2line ( const mp2p_icp::point_line_pair_t pairing,
const mrpt::poses::CPose3D &  relativePose,
mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >>  jacobian = std::nullopt 
)

Definition at line 61 of file errorTerms.cpp.

◆ error_point2plane()

mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2plane ( const mp2p_icp::point_plane_pair_t pairing,
const mrpt::poses::CPose3D &  relativePose,
mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >>  jacobian = std::nullopt 
)

Definition at line 109 of file errorTerms.cpp.

◆ error_point2point()

mrpt::math::CVectorFixedDouble< 3 > mp2p_icp::error_point2point ( const mrpt::tfest::TMatchingPair &  pairing,
const mrpt::poses::CPose3D &  relativePose,
mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 3, 12 >>  jacobian = std::nullopt 
)

Definition at line 28 of file errorTerms.cpp.

◆ estimate_points_eigen()

mp2p_icp::PointCloudEigen mp2p_icp::estimate_points_eigen ( const float *  xs,
const float *  ys,
const float *  zs,
mrpt::optional_ref< const std::vector< size_t >>  indices,
std::optional< size_t >  totalCount = std::nullopt 
)

Calculate mean, covariance, eigenvectors, and eigenvalues from a set of points.

It is mandatory to provide one and only one of these two parameters:

  • indices: only the points with these indices will be considered.
  • totalCount: all points will be used, ignoring indices.
Parameters
xs[in]Input x coordinate vector.
ys[in]Input y coordinate vector.
zs[in]Input z coordinate vector.
indices[in]0-based indices of points to consider from the vectors.
totalCount[in]Total number of points in the vectors.
Exceptions
std::exceptionIf less than 3 points are provided.

Definition at line 19 of file estimate_points_eigen.cpp.

◆ eval_centroids_robust()

std::tuple< mrpt::math::TPoint3D, mrpt::math::TPoint3D > mp2p_icp::eval_centroids_robust ( const Pairings in,
const OutlierIndices outliers 
)

Evaluates the centroids [ct_local, ct_global] for point-to-point correspondences only, taking into account the current guess for outliers

Definition at line 59 of file Pairings.cpp.

◆ icp_pipeline_from_yaml()

std::tuple< mp2p_icp::ICP::Ptr, mp2p_icp::Parameters > mp2p_icp::icp_pipeline_from_yaml ( const mrpt::containers::yaml &  config,
const mrpt::system::VerbosityLevel &  vLevel = mrpt::system::LVL_INFO 
)

Sets up an ICP pipeline from a YAML configuration file.

The basic structure of the YAML configuration block is (see also example YAML files):

class_name: mp2p_icp::ICP
# See: mp2p_icp::Parameter
params:
maxIterations: 100
# ...
solvers:
params:
maxIterations: 10
# Sequence of one or more pairs (class, params) defining mp2p_icp::Matcher
# instances to pair geometric entities between pointclouds.
matchers:
params:
threshold: 0.20
maxLocalPointsPerLayer: 500
quality:
params:
thresholdDistance: 0.1

Definition at line 18 of file icp_pipeline_from_yaml.cpp.

◆ load_xyz_file()

mrpt::maps::CSimplePointsMap::Ptr mp2p_icp::load_xyz_file ( const std::string &  fil)

Loads a pointcloud from an ASCII "XYZ file", storing an Nx3 matrix (each row is a point). If the filename extension ends in ".gz", it is uncompressed automatically.

Definition at line 21 of file load_xyz_file.cpp.

◆ operator<<() [1/2]

mrpt::serialization::CArchive & mp2p_icp::operator<< ( mrpt::serialization::CArchive &  out,
const Pairings obj 
)

Definition at line 44 of file Pairings.cpp.

◆ operator<<() [2/2]

mrpt::serialization::CArchive & mp2p_icp::operator<< ( mrpt::serialization::CArchive &  out,
const Results obj 
)

Definition at line 36 of file Results.cpp.

◆ operator>>() [1/2]

mrpt::serialization::CArchive & mp2p_icp::operator>> ( mrpt::serialization::CArchive &  in,
Pairings obj 
)

Definition at line 51 of file Pairings.cpp.

◆ operator>>() [2/2]

mrpt::serialization::CArchive & mp2p_icp::operator>> ( mrpt::serialization::CArchive &  in,
Results obj 
)

Definition at line 43 of file Results.cpp.

◆ optimal_tf_gauss_newton()

bool mp2p_icp::optimal_tf_gauss_newton ( const Pairings in,
OptimalTF_Result result,
const OptimalTF_GN_Parameters gnParams = OptimalTF_GN_Parameters() 
)

Gauss-Newton non-linear, iterative optimizer to find the SE(3) optimal transformation between a set of correspondences.

This method requires a linearization point in OptimalTF_GN_Parameters::linearizationPoint.

Returns
false If the number of pairings is too small for a unique solution, true on success.

Definition at line 22 of file optimal_tf_gauss_newton.cpp.

◆ optimal_tf_olae()

bool mp2p_icp::optimal_tf_olae ( const Pairings in,
const WeightParameters wp,
OptimalTF_Result result 
)

OLAE algorithm to find the SE(3) optimal transformation given a set of correspondences between points-points, lines-lines, planes-planes. Refer to technical report: Jose-Luis Blanco-Claraco. OLAE-ICP: Robust and fast alignment of geometric features with the optimal linear attitude estimator, Arxiv 2019.

Returns
false If the number of pairings is too small for a unique solution, true on success.

Definition at line 233 of file optimal_tf_olae.cpp.

◆ run_matchers()

Pairings mp2p_icp::run_matchers ( const matcher_list_t matchers,
const metric_map_t pcGlobal,
const metric_map_t pcLocal,
const mrpt::poses::CPose3D &  local_wrt_global,
const MatchContext mc,
const mrpt::optional_ref< MatchState > &  userProvidedMS = std::nullopt 
)

Runs a sequence of matcher between two metric_map_t objects.

This is normally invoked by mp2p_icp::ICP, but users can use it as a standalone module as needed.

Definition at line 37 of file mp2p_icp/src/Matcher.cpp.

◆ visit_correspondences()

template<class LAMBDA , class LAMBDA2 >
void mp2p_icp::visit_correspondences ( const Pairings in,
const WeightParameters wp,
const mrpt::math::TPoint3D &  ct_local,
const mrpt::math::TPoint3D &  ct_global,
OutlierIndices in_out_outliers,
LAMBDA  lambda_each_pair,
LAMBDA2  lambda_final,
bool  normalize_relative_point_vectors,
const mrpt::optional_ref< VisitCorrespondencesStats > &  outStats = std::nullopt 
)

Visit each correspondence

Definition at line 31 of file visit_correspondences.h.

mp2p_icp::Solver_GaussNewton
Definition: Solver_GaussNewton.h:24
mp2p_icp::Matcher_Points_DistanceThreshold
Definition: Matcher_Points_DistanceThreshold.h:30
mp2p_icp::QualityEvaluator_PairedRatio
Definition: QualityEvaluator_PairedRatio.h:23
mp2p_icp::ICP
Definition: ICP.h:51


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04