Classes | Typedefs | Enumerations | Functions
mp2p_icp Namespace Reference

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_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
 
struct  Parameters
 
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 >
 

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
}
 

Functions

mrpt::math::CMatrixDouble66 covariance (const Pairings &finalPairings, const mrpt::poses::CPose3D &finalAlignSolution, const CovarianceParameters &p)
 
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)
 
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)
 
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)
 
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 98 of file Matcher.h.

Function Documentation

◆ 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.



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