Namespaces | Classes | Typedefs | Enumerations | Functions
mp2p_icp Namespace Reference

Namespaces

 internal
 

Classes

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

Typedefs

using layer_name_t = std::string
 
using MatchedLineList = std::vector< matched_line_t >
 
using MatchedPlaneList = std::vector< matched_plane_t >
 
using MatchedPointLineList = std::vector< point_line_pair_t >
 
using MatchedPointPlaneList = std::vector< point_plane_pair_t >
 
using matcher_list_t = std::vector< mp2p_icp::Matcher::Ptr >
 
using robust_sqrt_weight_func_t = std::function< double(double)>
 

Enumerations

enum  Coordinate : uint8_t { Coordinate::X = 0, Coordinate::Y, Coordinate::Z }
 
enum  IterTermReason : uint8_t {
  IterTermReason::Undefined = 0, IterTermReason::NoPairings, IterTermReason::SolverError, IterTermReason::MaxIterations,
  IterTermReason::Stalled, IterTermReason::QualityCheckpointFailed, IterTermReason::HookRequest
}
 
enum  RobustKernel : uint8_t { RobustKernel::None = 0, RobustKernel::GemanMcClure, RobustKernel::Cauchy }
 

Functions

void AttachToParameterSource (Parameterizable &o, ParameterSource &source)
 
template<typename T >
void AttachToParameterSource (std::vector< std::shared_ptr< T >> &setObjects, ParameterSource &source)
 
mrpt::math::CMatrixDouble66 covariance (const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
 
robust_sqrt_weight_func_t create_robust_kernel (const RobustKernel kernel, const double kernelParam)
 
mrpt::math::CVectorFixedDouble< 4 > 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 > 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 > 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 > 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 > 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 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 > eval_centroids_robust (const Pairings &in, const OutlierIndices &outliers)
 
std::tuple< mp2p_icp::ICP::Ptr, mp2p_icp::Parametersicp_pipeline_from_yaml (const mrpt::containers::yaml &config, const mrpt::system::VerbosityLevel &vLevel=mrpt::system::LVL_INFO)
 
mrpt::maps::CSimplePointsMap::Ptr load_xyz_file (const std::string &fil)
 
const mrpt::maps::NearestNeighborsCapable * MapToNN (const mrpt::maps::CMetricMap &map, bool throwIfNotImplemented)
 
const mrpt::maps::CPointsMap * MapToPointsMap (const mrpt::maps::CMetricMap &map)
 
mrpt::maps::CPointsMap * MapToPointsMap (mrpt::maps::CMetricMap &map)
 
mrpt::serialization::CArchive & operator<< (mrpt::serialization::CArchive &out, const Pairings &obj)
 
mrpt::serialization::CArchive & operator<< (mrpt::serialization::CArchive &out, const Results &obj)
 
mrpt::serialization::CArchive & operator>> (mrpt::serialization::CArchive &in, Pairings &obj)
 
mrpt::serialization::CArchive & operator>> (mrpt::serialization::CArchive &in, Results &obj)
 
bool optimal_tf_gauss_newton (const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
 
bool optimal_tf_horn (const mp2p_icp::Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
 
bool optimal_tf_olae (const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
 
bool pointcloud_sanity_check (const mrpt::maps::CPointsMap &pc, bool printWarnings=true)
 
Pairings pt2ln_pl_to_pt2pt (const Pairings &in, const SolverContext &sc)
 
Pairings 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)
 
void vector_of_points_to_xyz (const std::vector< mrpt::math::TPoint3Df > &pts, std::vector< float > &xs, std::vector< float > &ys, std::vector< float > &zs)
 
template<class LAMBDA , class LAMBDA2 >
void 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)
 

Typedef Documentation

◆ matcher_list_t

using mp2p_icp::matcher_list_t = typedef std::vector<mp2p_icp::Matcher::Ptr>

Definition at line 103 of file Matcher.h.

◆ robust_sqrt_weight_func_t

using mp2p_icp::robust_sqrt_weight_func_t = typedef std::function<double(double )>

Definition at line 37 of file robust_kernels.h.

Enumeration Type Documentation

◆ RobustKernel

enum mp2p_icp::RobustKernel : uint8_t
strong

Type to select a robust kernel. Support mrpt::typemeta::TEnumType to get/set from strings.

Enumerator
None 

None: plain least-squares.

GemanMcClure 

Generalized GemanMcClure kernel (Zhang97ivc, Agarwal15phd).

Cauchy 

Cauchy kernel (Lee2013IROS).

Definition at line 25 of file robust_kernels.h.

Function Documentation

◆ AttachToParameterSource() [1/2]

void mp2p_icp::AttachToParameterSource ( Parameterizable o,
ParameterSource source 
)
inline

Attach a single object to the given source. Provided for syntax consistency between single and vectors of objects.

Definition at line 154 of file Parameterizable.h.

◆ AttachToParameterSource() [2/2]

template<typename T >
void mp2p_icp::AttachToParameterSource ( std::vector< std::shared_ptr< T >> &  setObjects,
ParameterSource source 
)
inline

Attach a vector of objects to the given source

Definition at line 140 of file Parameterizable.h.

◆ create_robust_kernel()

robust_sqrt_weight_func_t mp2p_icp::create_robust_kernel ( const RobustKernel  kernel,
const double  kernelParam 
)
inline

Creates a functor with the sqrt of the weight function of a given kernel, or an empty functor if non-robust kernel is selected.

Implemented as inline to try to make the compiler to optimize.

Parameters
kernelSelected kernel type.
kernelParamParameter of the kernel.
Returns
A functor.

We must return the sqrt of the weight function:

sqrt(w(x))=( ∂ρ(x)/∂x )/x = c²/(e²+c)²

with the loss function ρ(x) = (x²/2)/(c²+x²)

We must return the sqrt of the weight function:

sqrt(w(x))=( ∂ρ(x)/∂x )/x = c²/(e²+c²)

with the loss function ρ(x) = 0.5 c² log(1+x²/c²)

Definition at line 49 of file robust_kernels.h.

◆ optimal_tf_horn()

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

Classic Horn's solution for optimal SE(3) transformation, modified to accept point-to-point, line-to-line, plane-to-plane pairings. If you need point-to-line or point-to-plane pairings, use the wrapper mp2p_icp::Solver_Horn.

Note
On MRPT naming convention: "this"=global; "other"=local.
Returns
false If the number of pairings is too small for a unique solution, true on success.

Definition at line 199 of file optimal_tf_horn.cpp.

◆ pt2ln_pl_to_pt2pt()

Pairings mp2p_icp::pt2ln_pl_to_pt2pt ( const Pairings in,
const SolverContext sc 
)

Returns a copy of the input pairings, adding new pt2pt pairings for those pt2ln and pt2pl pairings.

Definition at line 39 of file pt2ln_pl_to_pt2pt.cpp.

◆ vector_of_points_to_xyz()

void mp2p_icp::vector_of_points_to_xyz ( const std::vector< mrpt::math::TPoint3Df > &  pts,
std::vector< float > &  xs,
std::vector< float > &  ys,
std::vector< float > &  zs 
)

Auxiliary function that can be used to convert a vector of TPoint3Df into the format expected by estimate_points_eigen()

Definition at line 116 of file estimate_points_eigen.cpp.



mp2p_icp
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Wed Jun 26 2024 02:47:10