List of all members
mp2p_icp::Pairings Struct Reference

#include <Pairings.h>

Public Member Functions

Methods
virtual bool empty () const
 
virtual size_t size () const
 
virtual std::string contents_summary () const
 
virtual void push_back (const Pairings &o)
 
virtual void push_back (Pairings &&o)
 
virtual void serializeTo (mrpt::serialization::CArchive &out) const
 
virtual void serializeFrom (mrpt::serialization::CArchive &in)
 
virtual auto get_visualization (const mrpt::poses::CPose3D &localWrtGlobal, const pairings_render_params_t &p=pairings_render_params_t()) const -> std::shared_ptr< mrpt::opengl::CSetOfObjects >
 
virtual void get_visualization_pt2pt (mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pt_t &p) const
 
virtual void get_visualization_pt2pl (mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pl_t &p) const
 
virtual void get_visualization_pt2ln (mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2ln_t &p) const
 

Public Attributes

Data fields
mrpt::tfest::TMatchingPairList paired_pt2pt
 
MatchedPointLineList paired_pt2ln
 
MatchedPointPlaneList paired_pt2pl
 
MatchedLineList paired_ln2ln
 
MatchedPlaneList paired_pl2pl
 
std::vector< std::pair< std::size_t, double > > point_weights
 

Detailed Description

Common pairing input data for OLAE, Horn's, and other solvers. Planes and lines must have unit director and normal vectors, respectively.

Pairings are between a "global" (or "this") and a "local" (or "other") pointcloud, while we are searching for the relative pose of "local" wrt "global", such that "relative_pose \oplus localPoint = globalPoint".

Definition at line 94 of file Pairings.h.

Member Function Documentation

◆ contents_summary()

std::string Pairings::contents_summary ( ) const
virtual

Returns a string summarizing all the paired elements

Definition at line 152 of file Pairings.cpp.

◆ empty()

virtual bool mp2p_icp::Pairings::empty ( ) const
inlinevirtual

Definition at line 118 of file Pairings.h.

◆ get_visualization()

auto Pairings::get_visualization ( const mrpt::poses::CPose3D &  localWrtGlobal,
const pairings_render_params_t p = pairings_render_params_t() 
) const -> std::shared_ptr<mrpt::opengl::CSetOfObjects>
virtual

Gets a renderizable view of all geometric entities.

See render_params_t for options to show/hide the different geometric entities and point layers.

Note
If deriving user classes inheriting from metric_map_t, remember to reimplement this method and call this base class method to render common elements.

Definition at line 168 of file Pairings.cpp.

◆ get_visualization_pt2ln()

void Pairings::get_visualization_pt2ln ( mrpt::opengl::CSetOfObjects &  o,
const mrpt::poses::CPose3D &  localWrtGlobal,
const render_params_pairings_pt2ln_t p 
) const
virtual

Used inside get_visualization(), renders pt-to-ln pairings only.

Definition at line 239 of file Pairings.cpp.

◆ get_visualization_pt2pl()

void Pairings::get_visualization_pt2pl ( mrpt::opengl::CSetOfObjects &  o,
const mrpt::poses::CPose3D &  localWrtGlobal,
const render_params_pairings_pt2pl_t p 
) const
virtual

Used inside get_visualization(), renders pt-to-pl pairings only.

Definition at line 203 of file Pairings.cpp.

◆ get_visualization_pt2pt()

void Pairings::get_visualization_pt2pt ( mrpt::opengl::CSetOfObjects &  o,
const mrpt::poses::CPose3D &  localWrtGlobal,
const render_params_pairings_pt2pt_t p 
) const
virtual

Used inside get_visualization(), renders pt-to-pt pairings only.

Definition at line 184 of file Pairings.cpp.

◆ push_back() [1/2]

void Pairings::push_back ( const Pairings o)
virtual

Copy and append pairings from another container.

Definition at line 117 of file Pairings.cpp.

◆ push_back() [2/2]

void Pairings::push_back ( Pairings &&  o)
virtual

Move pairings from another container.

Definition at line 126 of file Pairings.cpp.

◆ serializeFrom()

void Pairings::serializeFrom ( mrpt::serialization::CArchive &  in)
virtual

Definition at line 34 of file Pairings.cpp.

◆ serializeTo()

void Pairings::serializeTo ( mrpt::serialization::CArchive &  out) const
virtual

Definition at line 26 of file Pairings.cpp.

◆ size()

size_t Pairings::size ( ) const
virtual

Overall number of element-to-element pairings (points, lines, planes)

Definition at line 135 of file Pairings.cpp.

Member Data Documentation

◆ paired_ln2ln

MatchedLineList mp2p_icp::Pairings::paired_ln2ln

Definition at line 104 of file Pairings.h.

◆ paired_pl2pl

MatchedPlaneList mp2p_icp::Pairings::paired_pl2pl

Definition at line 105 of file Pairings.h.

◆ paired_pt2ln

MatchedPointLineList mp2p_icp::Pairings::paired_pt2ln

Definition at line 102 of file Pairings.h.

◆ paired_pt2pl

MatchedPointPlaneList mp2p_icp::Pairings::paired_pt2pl

Definition at line 103 of file Pairings.h.

◆ paired_pt2pt

mrpt::tfest::TMatchingPairList mp2p_icp::Pairings::paired_pt2pt

We reuse MRPT struct to allow using their matching functions.

Note
on MRPT naming convention: "this"=global; "other"=local.

Definition at line 101 of file Pairings.h.

◆ point_weights

std::vector<std::pair<std::size_t, double> > mp2p_icp::Pairings::point_weights

Individual weights for paired_pt2pt: each entry specifies how many points have the given (mapped second value) weight, in the same order as stored in paired_pt2pt. If empty, all points will have equal weights.

Definition at line 111 of file Pairings.h.


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


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