pypoint_matcher_helper.h
Go to the documentation of this file.
1 #ifndef PYTHON_PYPOINT_MATCHER_HELPER_H
2 #define PYTHON_PYPOINT_MATCHER_HELPER_H
3 
4 #include <pybind11/pybind11.h>
5 #include <pybind11/eigen.h>
6 #include <pybind11/stl.h>
7 #include <pybind11/stl_bind.h>
8 
10 
11 namespace py = pybind11;
12 namespace pms = PointMatcherSupport;
13 
14 // PointMatcher aliases
32 using ICPChaineBase = PM::ICPChainBase;
33 using ICP = PM::ICP;
35 
36 // PointMatcherSupport aliases
52 
53 // Eigen and nabo-based types aliases
62 using Array = PM::Array;
65 
66 PYBIND11_MAKE_OPAQUE(std::vector<std::string>) // StringVector
67 PYBIND11_MAKE_OPAQUE(std::map<std::string, std::map<std::string, std::string>>) // Bibliography
68 PYBIND11_MAKE_OPAQUE(std::map<std::string, unsigned>) // BibIndices
69 PYBIND11_MAKE_OPAQUE(std::vector<ParameterDoc>) // ParametersDoc
70 PYBIND11_MAKE_OPAQUE(std::map<std::string, std::string>) // Parameters, StringMap
71 PYBIND11_MAKE_OPAQUE(std::map<std::string, std::vector<std::string>>) // CsvElements
72 PYBIND11_MAKE_OPAQUE(std::vector<Label>) // Labels
73 PYBIND11_MAKE_OPAQUE(std::vector<DataPointsFilter>) // DataPointsFilters
74 PYBIND11_MAKE_OPAQUE(std::vector<Transformation>) // Transformations
75 PYBIND11_MAKE_OPAQUE(std::vector<OutlierFilter>) // OutlierFilters
76 PYBIND11_MAKE_OPAQUE(std::vector<TransformationChecker>) // TransformationCheckers
77 
78 #endif //PYTHON_PYPOINT_MATCHER_HELPER_H
PM::Transformations Transformations
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
Definition: PointMatcher.h:397
std::vector< Vector, Eigen::aligned_allocator< Vector > > VectorVector
A vector of vector over ScalarType, not a matrix.
Definition: PointMatcher.h:163
PM::Transformation Transformation
public interface
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
Definition: PointMatcher.h:533
DataPoints::Label Label
The logger interface, used to output warnings and informations.
Definition: PointMatcher.h:104
A factor for subclasses of Interface.
Definition: Registrar.h:76
PM::OutlierWeights OutlierWeights
pms::Parametrizable Parametrizable
PM::QuaternionVector QuaternionVector
Eigen::Quaternion< float > Quaternion
A quaternion over ScalarType.
Definition: PointMatcher.h:165
PM::DataPoints DataPoints
::std::string string
Definition: gtest.h:1979
PM::ICPChainBase ICPChaineBase
PM::Inspector Inspector
PM::Quaternion Quaternion
PM::IntMatrix IntMatrix
PM::Array Array
PM::ICPSequence ICPSequence
Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic > IntMatrix
A dense integer matrix.
Definition: PointMatcher.h:171
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
Definition: PointMatcher.h:530
The name for a certain number of dim.
Definition: PointMatcher.h:221
A function that transforms points and their descriptors given a transformation matrix.
Definition: PointMatcher.h:404
PM::ErrorMinimizer ErrorMinimizer
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
PM::Matrix Matrix
Parametrizable::Parameter Parameter
Parametrizable::ParameterDoc ParameterDoc
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
PointMatcherSupport::Parametrizable::ParametersDoc ParametersDoc
float ScalarType
The scalar type.
Definition: PointMatcher.h:159
Functions and classes that are not dependant on scalar type are defined in this namespace.
DataPoints::Labels Labels
PM::Int64Matrix Int64Matrix
PM::Parameters Parameters
pms::Logger Logger
PM::VectorVector VectorVector
std::vector< Quaternion, Eigen::aligned_allocator< Quaternion > > QuaternionVector
A vector of quaternions over ScalarType.
Definition: PointMatcher.h:167
PM::TransformationCheckers TransformationCheckers
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
Definition: PointMatcher.h:173
The documentation of a parameter.
PM::TransformationChecker TransformationChecker
The superclass of classes that are constructed using generic parameters. This class provides the para...
An exception thrown when one tries to fetch the value of an unexisting parameter. ...
std::vector< ParameterDoc > ParametersDoc
The documentation of all parameters.
Parametrizable::InvalidParameter InvalidParameter
PM::ICP ICP
PM::Vector Vector
Eigen::Array< float, Eigen::Dynamic, Eigen::Dynamic > Array
A dense array over ScalarType.
Definition: PointMatcher.h:175
Eigen::Matrix< float, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
PM::TransformationParameters TransformationParameters
PM::OutlierFilters OutlierFilters
PM::Matches Matches
PM::DataPointsFilter DataPointsFilter
PM::ScalarType ScalarType
Matrix TransformationParameters
A matrix holding the parameters a transformation.
Definition: PointMatcher.h:182
PM::OutlierFilter OutlierFilter
PM::Matcher Matcher
PM::DataPointsFilters DataPointsFilters
ErrorMinimizer::ErrorElements ErrorElements


libpointmatcher
Author(s):
autogenerated on Sat May 27 2023 02:38:03