1 #ifndef PYTHON_PYPOINT_MATCHER_HELPER_H 2 #define PYTHON_PYPOINT_MATCHER_HELPER_H 4 #include <pybind11/pybind11.h> 5 #include <pybind11/eigen.h> 6 #include <pybind11/stl.h> 7 #include <pybind11/stl_bind.h> 11 namespace py = pybind11;
66 PYBIND11_MAKE_OPAQUE(std::vector<std::string>)
67 PYBIND11_MAKE_OPAQUE(std::map<
std::string, std::map<std::string, std::string>>)
68 PYBIND11_MAKE_OPAQUE(
std::map<
std::
string,
unsigned>)
70 PYBIND11_MAKE_OPAQUE(
std::map<
std::
string,
std::
string>)
71 PYBIND11_MAKE_OPAQUE(
std::map<
std::
string,
std::vector<
std::
string>>)
72 PYBIND11_MAKE_OPAQUE(
std::vector<
Label>)
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.
std::vector< Vector, Eigen::aligned_allocator< Vector > > VectorVector
A vector of vector over ScalarType, not a matrix.
PM::Transformation Transformation
A structure holding data ready for minimization. The data are "normalized", for instance there are no...
The logger interface, used to output warnings and informations.
A factor for subclasses of Interface.
PM::OutlierWeights OutlierWeights
pms::Parametrizable Parametrizable
PM::QuaternionVector QuaternionVector
Eigen::Quaternion< float > Quaternion
A quaternion over ScalarType.
PM::DataPoints DataPoints
PM::ICPChainBase ICPChaineBase
PM::Quaternion Quaternion
PM::ICPSequence ICPSequence
Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic > IntMatrix
A dense integer matrix.
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
The name for a certain number of dim.
PM::ErrorMinimizer ErrorMinimizer
Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
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.
Functions and classes that are not dependant on scalar type are defined in this namespace.
DataPoints::Labels Labels
PM::Int64Matrix Int64Matrix
PM::Parameters Parameters
PM::VectorVector VectorVector
std::vector< Quaternion, Eigen::aligned_allocator< Quaternion > > QuaternionVector
A vector of quaternions over ScalarType.
PM::TransformationCheckers TransformationCheckers
std::string Parameter
alias
Eigen::Matrix< std::int64_t, Eigen::Dynamic, Eigen::Dynamic > Int64Matrix
A dense signed 64-bits matrix.
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
Eigen::Array< float, Eigen::Dynamic, Eigen::Dynamic > Array
A dense array over ScalarType.
Eigen::Matrix< float, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
PM::TransformationParameters TransformationParameters
PM::OutlierFilters OutlierFilters
PM::DataPointsFilter DataPointsFilter
PM::ScalarType ScalarType
Matrix TransformationParameters
A matrix holding the parameters a transformation.
PM::OutlierFilter OutlierFilter
PM::DataPointsFilters DataPointsFilters
ErrorMinimizer::ErrorElements ErrorElements