create() provides an std::shared_ptr instead of a ptr. --- aicp_core/src/utils/icpMonitor.cpp.orig 2019-05-05 17:52:19.000000000 +0200 +++ aicp_core/src/utils/icpMonitor.cpp 2020-01-24 19:24:13.338056526 +0100 @@ -26,7 +26,7 @@ params["knn"] = toParam(1); // for Hausdorff distance, we only need the first closest point params["epsilon"] = toParam(0); - PM::Matcher* matcherHausdorff = PM::get().MatcherRegistrar.create("KDTreeMatcher", params); + auto matcherHausdorff = PM::get().MatcherRegistrar.create("KDTreeMatcher", params); float quantile = 0.60; @@ -102,7 +102,7 @@ params["knn"] = toParam(1); // for Hausdorff distance, we only need the first closest point params["epsilon"] = toParam(0); - PM::Matcher* matcher = PM::get().MatcherRegistrar.create("KDTreeMatcher", params); + auto matcher = PM::get().MatcherRegistrar.create("KDTreeMatcher", params); // from reading to reference matcher->init(A); --- aicp_core/src/registration/pointmatcher_registration.cpp.orig 2019-05-05 17:52:19.000000000 +0200 +++ aicp_core/src/registration/pointmatcher_registration.cpp 2020-01-24 19:24:44.765800055 +0100 @@ -72,7 +72,7 @@ { PM::TransformationParameters init_transform = parseTransformationDeg(params_.pointmatcher.initialTransform, 3); - PM::Transformation* rigid_transform = PM::get().REG(Transformation).create("RigidTransformation"); + auto rigid_transform = PM::get().REG(Transformation).create("RigidTransformation"); if (!rigid_transform->checkParameters(init_transform)) { cerr << endl