Go to the documentation of this file.
17 #include <mrpt/containers/yaml.h>
18 #include <mrpt/math/TLine3D.h>
19 #include <mrpt/serialization/CSerializable.h>
20 #include <mrpt/tfest/TMatchingPair.h>
21 #include <mrpt/typemeta/TTypeName.h>
60 const mrpt::math::TLine3D& l_global,
61 const mrpt::math::TPoint3D& p_local)
119 virtual size_t size()
const;
130 virtual void serializeTo(mrpt::serialization::CArchive&
out)
const;
131 virtual void serializeFrom(mrpt::serialization::CArchive& in);
143 const mrpt::poses::CPose3D& localWrtGlobal,
145 ->
std::shared_ptr<
mrpt::opengl::CSetOfObjects>;
149 mrpt::opengl::CSetOfObjects& o,
150 const
mrpt::poses::CPose3D& localWrtGlobal,
155 mrpt::opengl::CSetOfObjects& o,
156 const
mrpt::poses::CPose3D& localWrtGlobal,
161 mrpt::opengl::CSetOfObjects& o,
162 const
mrpt::poses::CPose3D& localWrtGlobal,
169 mrpt::serialization::CArchive& operator<<(
172 mrpt::serialization::CArchive& operator>>(
188 return point2point.empty() && line2line.empty() && plane2plane.empty();
190 inline std::size_t
size()
const
192 return point2point.size() + line2line.size() + plane2plane.size();
200 const Pairings& in,
const OutlierIndices& outliers);
MatchedLineList paired_ln2ln
virtual std::string contents_summary() const
virtual void get_visualization_pt2ln(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2ln_t &p) const
mrpt::serialization::CArchive & operator>>(mrpt::serialization::CArchive &in, Pairings &obj)
std::vector< matched_plane_t > MatchedPlaneList
Defines point_plane_pair_t.
std::vector< matched_line_t > MatchedLineList
Render parameters for the different geometric entities.
virtual bool empty() const
std::vector< point_plane_pair_t > MatchedPointPlaneList
virtual void serializeFrom(mrpt::serialization::CArchive &in)
mrpt::math::TLine3D ln_global
virtual void get_visualization_pt2pt(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pt_t &p) const
uint64_t potential_pairings
std::vector< std::size_t > point2point
std::vector< std::size_t > line2line
std::vector< std::pair< std::size_t, double > > point_weights
mrpt::math::TLine3D ln_global
virtual size_t size() const
point_line_pair_t(const mrpt::math::TLine3D &l_global, const mrpt::math::TPoint3D &p_local)
virtual void serializeTo(mrpt::serialization::CArchive &out) const
virtual void push_back(const Pairings &o)
std::tuple< mrpt::math::TPoint3D, mrpt::math::TPoint3D > eval_centroids_robust(const Pairings &in, const OutlierIndices &outliers)
MatchedPlaneList paired_pl2pl
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 >
point_line_pair_t()=default
mrpt::serialization::CArchive & operator<<(mrpt::serialization::CArchive &out, const Pairings &obj)
mrpt::math::TPoint3D pt_local
virtual void get_visualization_pt2pl(mrpt::opengl::CSetOfObjects &o, const mrpt::poses::CPose3D &localWrtGlobal, const render_params_pairings_pt2pl_t &p) const
MatchedPointLineList paired_pt2ln
std::vector< point_line_pair_t > MatchedPointLineList
matched_plane_t()=default
mrpt::math::TLine3D ln_local
mrpt::tfest::TMatchingPairList paired_pt2pt
std::vector< std::size_t > plane2plane
MatchedPointPlaneList paired_pt2pl
matched_plane_t(const plane_patch_t &pl_this, const plane_patch_t &pl_other)
mp2p_icp
Author(s):
autogenerated on Thu Dec 26 2024 03:48:12