49 #ifdef SYSTEM_YAML_CPP 50 #include "yaml-cpp/yaml.h" 53 #endif // HAVE_YAML_CPP 59 InvalidModuleType::InvalidModuleType(
const std::string& reason):
66 prefilteredReadingPtsCount(0),
67 prefilteredReferencePtsCount(0),
68 maxNumIterationsReached(false)
108 this->
matcher = std::make_shared<typename MatchersImpl<T>::KDTreeMatcher>();
109 this->
errorMinimizer = std::make_shared<PointToPlaneErrorMinimizer<T> >();
112 this->
inspector = std::make_shared<typename InspectorsImpl<T>::NullInspector>();
124 typedef set<string> StringSet;
125 StringSet usedModuleTypes;
145 if (
nodeVal(
"errorMinimizer", doc) !=
"PointToPointSimilarityErrorMinimizer")
161 moduleTypeIt.first() >> moduleType;
162 if (usedModuleTypes.find(moduleType) == usedModuleTypes.end())
164 (boost::format(
"Module type %1% does not exist") % moduleType).str()
202 modules.push_back(registrar.createFromYAML(module));
217 module = registrar.createFromYAML(*reg);
250 return this->compute(readingIn, referenceIn, identity);
260 return this->compute(readingIn, referenceIn, initialTransformationParameters);
272 throw runtime_error(
"You must setup a matcher before running ICP");
274 throw runtime_error(
"You must setup an error minimizer before running ICP");
276 throw runtime_error(
"You must setup an inspector before running ICP");
291 const int nbPtsReference = reference.features.cols();
292 const Vector meanReference = reference.features.rowwise().sum() / nbPtsReference;
294 T_refIn_refMean.block(0,
dim-1,
dim-1, 1) = meanReference.head(
dim-1);
299 reference.features.topRows(
dim-1).colwise() -= meanReference.head(
dim-1);
302 this->
matcher->init(reference);
307 this->
inspector->addStat(
"ReferencePointCount", reference.features.cols());
311 return computeWithTransformedReference(readingIn, reference, T_refIn_refMean, T_refIn_dataIn);
325 if (T_refIn_dataIn.cols() != T_refIn_dataIn.rows()) {
326 throw runtime_error(
"The initial transformation matrix must be squared.");
328 if (
dim != T_refIn_dataIn.cols()) {
329 throw runtime_error(
"The shape of initial transformation matrix must be NxN. " 330 "Where N is the number of rows in the read/reference scans.");
346 T_refMean_dataIn = T_refIn_refMean.inverse() * T_refIn_dataIn;
360 size_t iterationCount(0);
386 this->
matcher->findClosests(stepReading)
395 assert(outlierWeights.rows() ==
matches.ids.rows());
396 assert(outlierWeights.cols() ==
matches.ids.cols());
412 stepReading, reference, outlierWeights,
matches) * T_iter;
432 this->
inspector->addStat(
"IterationsCount", iterationCount);
433 this->
inspector->addStat(
"PointCountTouched", this->
matcher->getVisitCount());
434 this->
matcher->resetVisitCount();
439 LOG_INFO_STREAM(
"PointMatcher::icp - " << iterationCount <<
" iterations took " << t.
elapsed() <<
" [s]");
448 return (T_refIn_refMean * T_iter * T_refMean_dataIn);
459 return (mapPointCloud.features.cols() != 0);
468 throw runtime_error(
"You must setup a matcher before running ICP");
470 throw runtime_error(
"You must setup an inspector before running ICP");
474 const int ptCount(inputCloud.
features.cols());
486 mapPointCloud = inputCloud;
490 const Vector meanMap = mapPointCloud.
features.rowwise().sum() / ptCount;
491 T_refIn_refMean = Matrix::Identity(
dim,
dim);
492 T_refIn_refMean.block(0,
dim-1,
dim-1, 1) = meanMap.head(
dim-1);
497 mapPointCloud.features.topRows(
dim-1).colwise() -= meanMap.head(
dim-1);
503 this->
matcher->init(mapPointCloud);
514 const int dim(mapPointCloud.features.rows());
515 T_refIn_refMean = Matrix::Identity(
dim,
dim);
524 if(mapPointCloud.getNbPoints() > 0)
526 this->
matcher->init(mapPointCloud);
535 if(mapPointCloud.getNbPoints() > 0)
537 this->
matcher->init(mapPointCloud);
548 const int dim(mapPointCloud.features.rows());
549 const Vector meanMapNonHomo(T_refIn_refMean.block(0,
dim-1,
dim-1, 1));
550 globalMap.
features.topRows(
dim-1).colwise() += meanMapNonHomo;
566 return mapPointCloud;
582 return this->compute(cloudIn, identity);
590 return this->compute(cloudIn, T_dataInOld_dataInNew);
603 return Matrix::Identity(
dim,
dim);
608 return this->computeWithTransformedReference(cloudIn, mapPointCloud, T_refIn_refMean, T_refIn_dataIn);
Matrix OutlierWeights
Weights of the associations between the points in Matches and the points in the reference.
const DataPoints getPrefilteredMap() const
Return the map, in global coordinates (slow)
A matcher links points in the reading to points in the reference.
#define LOG_INFO_STREAM(args)
The logger interface, used to output warnings and informations.
bool hasMap() const
Return whether the object currently holds a valid map.
virtual void setDefault()
Construct an ICP algorithm that works in most of the cases.
PM::DataPoints DataPoints
boost::mutex loggerMutex
mutex to protect access to logging
bool setMap(const DataPoints &map)
Set the map using inputCloud.
virtual void setDefault()
Construct an ICP algorithm that works in most of the cases.
DataPointsFilters referenceDataPointsFilters
filters for reference
TransformationParameters operator()(const DataPoints &cloudIn)
Apply ICP to cloud cloudIn, with identity as initial guess.
bool maxNumIterationsReached
store if we reached the maximum number of iterations last time compute was called ...
TransformationParameters compute(const DataPoints &cloudIn, const TransformationParameters &initialTransformationParameters)
Apply ICP to cloud cloudIn, with initial guess.
TransformationCheckers transformationCheckers
transformation checkers
virtual void loadAdditionalYAMLContent(PointMatcherSupport::YAML::Node &doc)
Hook to load addition subclass-specific content from the YAML file.
OutlierWeights compute(const DataPoints &filteredReading, const DataPoints &filteredReference, const Matches &input)
Apply outlier-detection chain.
An error minimizer will compute a transformation matrix such as to minimize the error between the rea...
const DataPoints & getPrefilteredInternalMap() const
Return the map, in internal coordinates (fast)
DataPointsFilters readingDataPointsFilters
filters for reading, applied once
std::map< std::string, Parameter > Parameters
Parameters stored as a map of string->string.
Functions and classes that are not dependant on scalar type are defined in this namespace.
An inspector allows to log data at the different steps, for analysis.
An exception thrown when one tries to use a module type that does not exist.
void getNameParamsFromYAML(const YAML::Node &module, std::string &name, Parametrizable::Parameters ¶ms)
Retrieve name and parameters from a yaml node.
TransformationParameters operator()(const DataPoints &readingIn, const DataPoints &referenceIn)
Perform ICP and return optimised transformation matrix.
Functions and classes that are dependant on scalar type are defined in this templatized class...
OutlierFilters outlierFilters
outlier filters
static const PointMatcher & get()
Return instances.
bool GetNextDocument(Node &document)
Result of the data-association step (Matcher::findClosests), before outlier rejection.
std::string nodeVal(const std::string ®Name, const PointMatcherSupport::YAML::Node &doc)
Get the value of a field in a node.
A data filter takes a point cloud as input, transforms it, and produces another point cloud as output...
std::shared_ptr< ErrorMinimizer > errorMinimizer
error minimizer
An outlier filter removes or weights links between points in reading and their matched points in refe...
::RandomSamplingDataPointsFilter< T > RandomSamplingDataPointsFilter
TransformationParameters compute(const DataPoints &readingIn, const DataPoints &referenceIn, const TransformationParameters &initialTransformationParameters)
Perform ICP from initial guess and return optimised transformation matrix.
#define LOG_WARNING_STREAM(args)
virtual void loadFromYaml(std::istream &in)
Construct an ICP algorithm from a YAML file.
ICPChainBase()
Protected contstructor, to prevent the creation of this object.
std::shared_ptr< Matcher > matcher
matcher
const std::string & createModulesFromRegistrar(const std::string ®Name, const PointMatcherSupport::YAML::Node &doc, const R ®istrar, std::vector< std::shared_ptr< typename R::TargetType > > &modules)
Instantiate modules if their names are in the YAML file.
TransformationParameters computeWithTransformedReference(const DataPoints &readingIn, const DataPoints &reference, const TransformationParameters &T_refIn_refMean, const TransformationParameters &initialTransformationParameters)
Perferm ICP using an already-transformed reference and with an already-initialized matcher...
std::shared_ptr< Inspector > inspector
inspector
Transformations transformations
transformations
unsigned prefilteredReadingPtsCount
remaining number of points after prefiltering but before the iterative process
const Node * FindValue(const T &key) const
bool getMaxNumIterationsReached() const
Return the flag that informs if we reached the maximum number of iterations during the last iterative...
void apply(DataPoints &cloud)
Apply this chain to cloud, mutates cloud.
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
::SamplingSurfaceNormalDataPointsFilter< T > SamplingSurfaceNormalDataPointsFilter
Matrix features
features of points in the cloud
virtual ~ICPChainBase()
virtual desctructor
DataPointsFilters readingStepDataPointsFilters
filters for reading, applied at each step
std::shared_ptr< Logger > logger
the current logger
Stuff common to all ICP algorithms.
unsigned getPrefilteredReadingPtsCount() const
Return the remaining number of points in reading after prefiltering but before the iterative process...
unsigned getPrefilteredReferencePtsCount() const
Return the remaining number of points in the reference after prefiltering but before the iterative pr...
Matrix TransformationParameters
A matrix holding the parameters a transformation.
void clearMap()
Clear the map (reset to same state as after the object is created)
virtual void loadFromYaml(std::istream &in)
Construct an ICP algorithm from a YAML file.
unsigned prefilteredReferencePtsCount
remaining number of points after prefiltering but before the iterative process
void init()
Init the chain.
void cleanup()
Clean chain up, empty all filters and delete associated objects.
const std::string & createModuleFromRegistrar(const std::string ®Name, const PointMatcherSupport::YAML::Node &doc, const R ®istrar, std::shared_ptr< typename R::TargetType > &module)
Instantiate a module if its name is in the YAML file.