Hi,
I am installing the latest version on Ubuntu 16 with ROS kinetic installed. I am source installing the rtabmap library. The libpointmatcher library was previously installed following instructions given on page below https://libpointmatcher.readthedocs.io/en/latest/Compilation/ ~/rtabmap/build$ cmake .. -- The imported target "vtkRenderingPythonTkWidgets" references the file "/usr/lib/x86_64-linux-gnu/libvtkRenderingPythonTkWidgets.so" but this file does not exist. Possible reasons include: * The file was deleted, renamed, or moved to another location. * An install or uninstall procedure did not complete successfully. * The installation package was faulty and contained "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake" but not all the files it references. -- The imported target "vtk" references the file "/usr/bin/vtk" but this file does not exist. Possible reasons include: * The file was deleted, renamed, or moved to another location. * An install or uninstall procedure did not complete successfully. * The installation package was faulty and contained "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake" but not all the files it references. -- PCL definitions don't contain "-march=native", make sure all libraries using Eigen are also compiled without that flag to avoid some segmentation faults (with gdb referring to some Eigen functions). -- Found Sqlite3: /usr/include /usr/lib/x86_64-linux-gnu/libsqlite3.so -- Found OpenMP -- Found OpenCV: /opt/ros/kinetic/include/opencv-3.3.1-dev;/opt/ros/kinetic/include/opencv-3.3.1-dev/opencv -- Found PCL: /usr/include/pcl-1.7;/usr/include/eigen3;/usr/include;/usr/include/ni;/usr/include/openni2;/usr/include/vtk-6.2;/usr/include/x86_64-linux-gnu;/usr/include/tcl;/usr/include/hdf5/openmpi;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent/include;/usr/lib/openmpi/include;/usr/lib/openmpi/include/openmpi;/usr/include/jsoncpp;/usr/include/freetype2;/usr/include/x86_64-linux-gnu/freetype2;/usr/include/python2.7;/usr/include/libxml2 -- Found ZLIB: /usr/include -- VTK_RENDERING_BACKEND=OpenGL -- Found Freenect: /opt/ros/kinetic/include/libfreenect -- Found OpenNI2: /usr/include/openni2 -- Found DC1394: /usr/include/dc1394 -- Old g2o version detected with c++03 interface (config file: /opt/ros/kinetic/include/g2o/config.h). -- Found g2o: /opt/ros/kinetic/include;/usr/include/suitesparse;/usr/include/suitesparse -- GTSAM include directory: /usr/local/lib/cmake/GTSAM/../../../include;/usr/include;/usr/local/include/gtsam/3rdparty/Eigen/ -- Found cvsba: /usr/local/include -- Found libpointmatcher: /usr/local/include;/usr/include;/usr/include/eigen3;/usr/include/eigen3;/usr/local/include;/home/arav/extra_lib/libpointmatcher/pointmatcher;/home/arav/extra_lib/libpointmatcher/pointmatcher/DataPointsFilters;/home/arav/extra_lib/libpointmatcher/pointmatcher/DataPointsFilters/utils -- Using CATKIN_DEVEL_PREFIX: /home/arav/rtabmap/build/devel -- Using CMAKE_PREFIX_PATH: /home/arav/catkin_ws_isolated/devel_isolated/plotjuggler;/home/arav/catkin_ws/devel;/opt/ros/kinetic;/home/arav/catkin_ws_isolated/devel_isolated/mrpt1 -- This workspace overlays: /home/arav/catkin_ws_isolated/devel_isolated/plotjuggler;/home/arav/catkin_ws/devel;/opt/ros/kinetic -- Using PYTHON_EXECUTABLE: /usr/bin/python -- Using Debian Python package layout -- Using empy: /usr/bin/empy -- Using CATKIN_ENABLE_TESTING: ON -- Call enable_testing() -- Using CATKIN_TEST_RESULTS_DIR: /home/arav/rtabmap/build/test_results -- Found gmock sources under '/usr/src/gmock': gmock will be built CMake Warning (dev) at /usr/src/gmock/CMakeLists.txt:40 (project): Policy CMP0048 is not set: project() command manages VERSION variables. Run "cmake --help-policy CMP0048" for policy details. Use the cmake_policy command to set the policy and suppress this warning. The following variable(s) would be set to empty: PROJECT_VERSION PROJECT_VERSION_MAJOR PROJECT_VERSION_MINOR PROJECT_VERSION_PATCH This warning is for project developers. Use -Wno-dev to suppress it. CMake Warning (dev) at /usr/src/gtest/CMakeLists.txt:42 (project): Policy CMP0048 is not set: project() command manages VERSION variables. Run "cmake --help-policy CMP0048" for policy details. Use the cmake_policy command to set the policy and suppress this warning. The following variable(s) would be set to empty: PROJECT_VERSION PROJECT_VERSION_MAJOR PROJECT_VERSION_MINOR PROJECT_VERSION_PATCH This warning is for project developers. Use -Wno-dev to suppress it. -- Found gtest sources under '/usr/src/gmock': gtests will be built -- Using Python nosetests: /usr/bin/nosetests-2.7 -- catkin 0.7.14 -- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy -- Found loam_velodyne: /home/arav/catkin_ws/src/loam_velodyne/include;/usr/include/eigen3;/usr/include/pcl-1.7;/usr/include;/usr/include/ni;/usr/include/openni2;/usr/include/vtk-6.2;/usr/include/x86_64-linux-gnu;/usr/include/tcl;/usr/include/hdf5/openmpi;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent;/usr/lib/openmpi/include/openmpi/opal/mca/event/libevent2021/libevent/include;/usr/lib/openmpi/include;/usr/lib/openmpi/include/openmpi;/usr/include/jsoncpp;/usr/include/freetype2;/usr/include/x86_64-linux-gnu/freetype2;/usr/include/python2.7;/usr/include/libxml2;/opt/ros/kinetic/include;/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp -- Found RealSense: /opt/ros/kinetic/include -- Found octomap 1.8.1: /opt/ros/kinetic/include -- Found libfovis: /home/arav/catkin_ws/src/libfovis/libfovis -- Found libviso2: /home/arav/catkin_ws/src/viso2/libviso2/libviso2/src -- Found Pthreads -- -------------------------------------------- -- Info : -- Version : 0.17.7 -- CMAKE_INSTALL_PREFIX = /usr/local -- CMAKE_BUILD_TYPE = Release -- CMAKE_INSTALL_LIBDIR = lib -- BUILD_APP = ON -- BUILD_TOOLS = ON -- BUILD_EXAMPLES = ON -- BUILD_SHARED_LIBS = ON -- CMAKE_CXX_FLAGS = -fmessage-length=0 -fopenmp -std=c++14 -- PCL_DEFINITIONS = -DEIGEN_USE_NEW_STDVECTOR;-DEIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET;-DFLANN_STATIC;-Dqh_QHpointer -- Optional dependencies ('*' affects some default parameters) : -- *With OpenCV 3 xfeatures2d module (SIFT/SURF/BRIEF/FREAK) = YES (License: Non commercial) -- With external SQLite3 = YES (License: Public Domain) -- With Freenect = YES (License: Apache v2 and/or GPLv2) -- With OpenNI2 = YES (License: Apache v2) -- With Freenect2 = NO (libfreenect2 not found) -- With Kinect for Windows 2 = NO (Kinect for Windows 2 SDK not found) -- With dc1394 = YES (License: LGPL) -- With FlyCapture2/Triclops = NO (Point Grey SDK not found) -- With TORO = YES (License: Creative Commons [Attribution-NonCommercial-ShareAlike]) -- *With g2o = YES (License: BSD) -- *With GTSAM = YES (License: BSD) -- With VERTIGO = YES (License: GPLv3) -- With cvsba = YES (License: GPLv2) -- *With libpointmatcher = YES (License: BSD) -- With loam_velodyne = YES (License: BSD) -- With ZED = NO (ZED sdk not found) -- With RealSense = YES (License: Apache-2) -- With RealSenseSlam = NO (WITH_REALSENSE_SLAM=OFF) -- With RealSense2 = NO (librealsense2 not found) -- With OCTOMAP = YES (License: BSD) -- With CPUTSDF = NO (CPUTSDF not found) -- With OpenChisel = NO (open_chisel not found) -- With libfovis = YES (License: GPLv2) -- With libviso2 = YES (License: GPLv3) -- With dvo_core = NO (dvo_core not found) -- With okvis = NO (okvis not found) -- With msckf_vio = NO (WITH_MSCKF_VIO=OFF) -- With ORB_SLAM2 = NO (WITH_G2O should be OFF as ORB_SLAM2 uses its own g2o version) -- With Qt5 = YES (License: Open Source or Commercial) -- -------------------------------------------- -- Configuring done -- Generating done -- Build files have been written to: /home/arav/rtabmap/build Invoking Make inside the build command gives the following errors associated with libpointmatcher ~/rtabmap/build$ make -j4 [ 4%] Built target rtabmap_utilite [ 5%] Built target res_tool [ 6%] Built target imagesJoiner [ 6%] Built target extractObject [ 6%] Building CXX object corelib/src/CMakeFiles/rtabmap_core.dir/Odometry.cpp.o [ 6%] Building CXX object corelib/src/CMakeFiles/rtabmap_core.dir/RegistrationIcp.cpp.o [ 7%] Building CXX object corelib/src/CMakeFiles/rtabmap_core.dir/odometry/OdometryF2M.cpp.o [ 7%] Building CXX object corelib/src/CMakeFiles/rtabmap_core.dir/OdometryThread.cpp.o [ 7%] Building CXX object corelib/src/CMakeFiles/rtabmap_core.dir/odometry/OdometryMono.cpp.o /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp: In member function ‘virtual void rtabmap::RegistrationIcp::parseParameters(const ParametersMap&)’: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:471:81: error: no matching function for call to ‘std::shared_ptr<PointMatcher<float>::Matcher>::reset(std::shared_ptr<PointMatcher<float>::Matcher>)’ icp->matcher.reset(PM::get().MatcherRegistrar.create("KDTreeMatcher", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate: void std::__shared_ptr<_Tp, _Lp>::reset() [with _Tp = PointMatcher<float>::Matcher; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset() noexcept ^ /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate expects 0 arguments, 1 provided /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: candidate: template<class _Tp1> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*) [with _Tp1 = _Tp1; _Tp = PointMatcher<float>::Matcher; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p) // _Tp1 must be complete. ^ /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:471:81: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::Matcher>’ icp->matcher.reset(PM::get().MatcherRegistrar.create("KDTreeMatcher", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: candidate: template<class _Tp1, class _Deleter> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Tp = PointMatcher<float>::Matcher; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:471:81: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::Matcher>’ icp->matcher.reset(PM::get().MatcherRegistrar.create("KDTreeMatcher", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: candidate: template<class _Tp1, class _Deleter, class _Alloc> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter, _Alloc) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Alloc = _Alloc; _Tp = PointMatcher<float>::Matcher; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d, _Alloc __a) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:471:81: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::Matcher>’ icp->matcher.reset(PM::get().MatcherRegistrar.create("KDTreeMatcher", params)); ^ /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:485:109: error: no matching function for call to ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>::reset(std::shared_ptr<PointMatcher<float>::ErrorMinimizer>)’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPlaneErrorMinimizer", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate: void std::__shared_ptr<_Tp, _Lp>::reset() [with _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset() noexcept ^ /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate expects 0 arguments, 1 provided /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: candidate: template<class _Tp1> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*) [with _Tp1 = _Tp1; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p) // _Tp1 must be complete. ^ /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:485:109: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPlaneErrorMinimizer", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: candidate: template<class _Tp1, class _Deleter> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:485:109: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPlaneErrorMinimizer", params)); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: candidate: template<class _Tp1, class _Deleter, class _Alloc> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter, _Alloc) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Alloc = _Alloc; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d, _Alloc __a) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:485:109: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPlaneErrorMinimizer", params)); ^ /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:490:101: error: no matching function for call to ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>::reset(std::shared_ptr<PointMatcher<float>::ErrorMinimizer>)’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate: void std::__shared_ptr<_Tp, _Lp>::reset() [with _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset() noexcept ^ /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate expects 0 arguments, 1 provided /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: candidate: template<class _Tp1> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*) [with _Tp1 = _Tp1; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p) // _Tp1 must be complete. ^ /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:490:101: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: candidate: template<class _Tp1, class _Deleter> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:490:101: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: candidate: template<class _Tp1, class _Deleter, class _Alloc> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter, _Alloc) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Alloc = _Alloc; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d, _Alloc __a) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:490:101: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icp->errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp: In member function ‘virtual rtabmap::Transform rtabmap::RegistrationIcp::computeTransformationImpl(rtabmap::Signature&, rtabmap::Signature&, rtabmap::Transform, rtabmap::RegistrationInfo&) const’: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:964:107: error: no matching function for call to ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>::reset(std::shared_ptr<PointMatcher<float>::ErrorMinimizer>)’ icpTmp.errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate: void std::__shared_ptr<_Tp, _Lp>::reset() [with _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset() noexcept ^ /usr/include/c++/5/bits/shared_ptr_base.h:1021:7: note: candidate expects 0 arguments, 1 provided /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: candidate: template<class _Tp1> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*) [with _Tp1 = _Tp1; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p) // _Tp1 must be complete. ^ /usr/include/c++/5/bits/shared_ptr_base.h:1026:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:964:107: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icpTmp.errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: candidate: template<class _Tp1, class _Deleter> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1035:2: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:964:107: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icpTmp.errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ In file included from /usr/include/c++/5/bits/shared_ptr.h:52:0, from /usr/include/c++/5/memory:82, from /usr/include/boost/config/no_tr1/memory.hpp:21, from /usr/include/boost/smart_ptr/shared_ptr.hpp:23, from /usr/include/boost/shared_ptr.hpp:17, from /usr/include/pcl-1.7/pcl/PCLPointField.h:11, from /usr/include/pcl-1.7/pcl/point_traits.h:48, from /usr/include/pcl-1.7/pcl/register_point_struct.h:57, from /usr/include/pcl-1.7/pcl/point_types.h:44, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Signature.h:32, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/Registration.h:34, from /home/arav/rtabmap/corelib/src/../include/rtabmap/core/RegistrationIcp.h:33, from /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:29: /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: candidate: template<class _Tp1, class _Deleter, class _Alloc> void std::__shared_ptr<_Tp, _Lp>::reset(_Tp1*, _Deleter, _Alloc) [with _Tp1 = _Tp1; _Deleter = _Deleter; _Alloc = _Alloc; _Tp = PointMatcher<float>::ErrorMinimizer; __gnu_cxx::_Lock_policy _Lp = (__gnu_cxx::_Lock_policy)2u] reset(_Tp1* __p, _Deleter __d, _Alloc __a) ^ /usr/include/c++/5/bits/shared_ptr_base.h:1040:9: note: template argument deduction/substitution failed: /home/arav/rtabmap/corelib/src/RegistrationIcp.cpp:964:107: note: mismatched types ‘_Tp1*’ and ‘std::shared_ptr<PointMatcher<float>::ErrorMinimizer>’ icpTmp.errorMinimizer.reset(PM::get().ErrorMinimizerRegistrar.create("PointToPointErrorMinimizer")); ^ corelib/src/CMakeFiles/rtabmap_core.dir/build.make:1435: recipe for target 'corelib/src/CMakeFiles/rtabmap_core.dir/RegistrationIcp.cpp.o' failed make[2]: *** [corelib/src/CMakeFiles/rtabmap_core.dir/RegistrationIcp.cpp.o] Error 1 make[2]: *** Waiting for unfinished jobs.... CMakeFiles/Makefile2:2386: recipe for target 'corelib/src/CMakeFiles/rtabmap_core.dir/all' failed make[1]: *** [corelib/src/CMakeFiles/rtabmap_core.dir/all] Error 2 Makefile:160: recipe for target 'all' failed make: *** [all] Error 2 How do I rectify this? Thanks
------
Alex
|
Administrator
|
My libpointmatcher version was still on v1.2.3. I updated to latest version and fixed the compilation errors (they refactored how the pointers are created, returning directly a shared pointer instead of a normal pointer).
cheers, Mathieu |
Hi Mathieu,
Thanks a lot. The latest pull solved the problem. Thanks for your fast response. Can you describe how exactly is libpointmatcher used in the rtabmap and is it possible to use velodyne to make 3d maps using the pointmatcher and bow from the rtabmap. I also plan to use a vertical lidar or a nodding lidar to combine 2d scans into 3d point cloud. Do you have an example as to how to implement this. Thanks a lot.
------
Alex
|
Administrator
|
Hi Alex,
libpointmatcher is enabled when setting Icp/PM parameter to true. Instead of using PCL for icp, libpointmatcher will be used instead. Parameters specific to libpointmatcher: $ rtabmap -params | grep /PM Param: Icp/PM = "false" [Use libpointmatcher for ICP registration instead of PCL's implementation.] Param: Icp/PMConfig = "" [Configuration file (*.yaml) used by libpointmatcher. Note that data filters set for libpointmatcher are done after filtering done by rtabmap (i.e., Icp/VoxelSize, Icp/DownsamplingStep), so make sure to disable those in rtabmap if you want to use only those from libpointmatcher. Parameters Icp/Iterations, Icp/Epsilon and Icp/MaxCorrespondenceDistance are also ignored if configuration file is set.] Param: Icp/PMMatcherEpsilon = "0.0" [KDTreeMatcher/epsilon: approximation to use for the nearest-neighbor search. For convenience when configuration file is not set.] Param: Icp/PMMatcherKnn = "1" [KDTreeMatcher/knn: number of nearest neighbors to consider it the reference. For convenience when configuration file is not set.] Param: Icp/PMOutlierRatio = "0.95" [TrimmedDistOutlierFilter/ratio: For convenience when configuration file is not set. For kinect-like point cloud, use 0.65.] Overall usage of lidar with rtabmap can be found in the paper "RTAB-Map as an Open-Source Lidar and Visual SLAM Library for Large-Scale and Long-Term Online Operation". libpointmatcher is used for all ICP stuff (see all Icp/* parameters) when a lidar is used. I don't have examples in ROS for 3D lidar mapping. With the standalone or with this tool, we can process the KITTI sequences with the velodyne. For the KITTI dataset, parameters specific to lidar (HDL_64E) are: Reg/Strategy 1 Icp/MaxTranslation 2 Icp/Epsilon 0.0001 Icp/MaxCorrespondenceDistance 1.5 ICP/CorrespondenceRatio 0.01 Icp/PM true Icp/PMOutlierRatio 0.7 Icp/PMMatcherKnn 3 Icp/PMMatcherEpsilon 1 Mem/LaserScanVoxelSize 0.5 # If point 2 plane: Mem/LaserScanNormalK 10 Icp/PointToPlane true Icp/Iterations 5 Odom/ScanKeyFrameThr 0.6 #if point 2 point: Icp/PointToPlane false Icp/Iterations 10 Odom/ScanKeyFrameThr 0.8 I will get my hand on a velodyne in the next months. I'll be able to create an example of usage under ROS. If you need more help, I would need more information on the application, sensor specifications and maybe a rosbag example. cheers, Mathieu |
Free forum by Nabble | Edit this page |