From 89e3e10d8933815cee6857665b05c6184742a83d Mon Sep 17 00:00:00 2001
From: matlabbe <matlabbe@gmail.com>
Date: Sun, 12 Feb 2023 16:18:01 -0800
Subject: [PATCH] Refactoring RTABMapConfig.cmake with targets (#904)

* Config: Using cmake targets

* fixed RTABMAP_DEPRECATED build error

* fixed melodic build

* cleanup

* Fixed qhull exported library error

* Update svg depend private

* removed g2o from public interface

* Fixed Windows with external project

* removed some required dep

* Fixed nsis error (also fixed unspecified components)

* updated workflow rules
---
 .github/workflows/cmake-ros.yml               |   6 +-
 .github/workflows/cmake.yml                   |   2 +-
 CMakeLists.txt                                | 188 ++++++-------
 RTABMapConfig.cmake.in                        | 153 +++++------
 RTABMapConfigVersion.cmake.in                 |  11 -
 app/src/CMakeLists.txt                        |  49 +---
 corelib/include/rtabmap/core/BayesFilter.h    |   4 +-
 corelib/include/rtabmap/core/Camera.h         |   4 +-
 corelib/include/rtabmap/core/CameraModel.h    |   6 +-
 corelib/include/rtabmap/core/CameraThread.h   |   9 +-
 corelib/include/rtabmap/core/Compression.h    |  26 +-
 corelib/include/rtabmap/core/DBDriver.h       |   4 +-
 .../include/rtabmap/core/DBDriverSqlite3.h    |   4 +-
 corelib/include/rtabmap/core/DBReader.h       |   4 +-
 .../include/rtabmap/core/EpipolarGeometry.h   |   4 +-
 corelib/include/rtabmap/core/Features2d.h     |  38 +--
 corelib/include/rtabmap/core/FlannIndex.h     |   4 +-
 .../include/rtabmap/core/GainCompensator.h    |   4 +-
 corelib/include/rtabmap/core/GeodeticCoords.h |   4 +-
 corelib/include/rtabmap/core/Graph.h          |  84 +++---
 corelib/include/rtabmap/core/IMUThread.h      |   4 +-
 corelib/include/rtabmap/core/Landmark.h       |   5 +-
 corelib/include/rtabmap/core/LaserScan.h      |  14 +-
 corelib/include/rtabmap/core/Link.h           |   4 +-
 corelib/include/rtabmap/core/MarkerDetector.h |   7 +-
 corelib/include/rtabmap/core/Memory.h         |   4 +-
 corelib/include/rtabmap/core/OccupancyGrid.h  |   4 +-
 corelib/include/rtabmap/core/OctoMap.h        |   4 +-
 corelib/include/rtabmap/core/Odometry.h       |   7 +-
 corelib/include/rtabmap/core/OdometryThread.h |   4 +-
 corelib/include/rtabmap/core/Optimizer.h      |   4 +-
 corelib/include/rtabmap/core/Parameters.h     |   4 +-
 corelib/include/rtabmap/core/Recovery.h       |   4 +-
 corelib/include/rtabmap/core/Registration.h   |   4 +-
 .../include/rtabmap/core/RegistrationIcp.h    |   4 +-
 .../include/rtabmap/core/RegistrationVis.h    |   4 +-
 corelib/include/rtabmap/core/Rtabmap.h        |   9 +-
 corelib/include/rtabmap/core/RtabmapExp.h     |  50 ----
 corelib/include/rtabmap/core/RtabmapThread.h  |   4 +-
 corelib/include/rtabmap/core/SensorData.h     |  16 +-
 corelib/include/rtabmap/core/Signature.h      |   4 +-
 corelib/include/rtabmap/core/Statistics.h     |   7 +-
 corelib/include/rtabmap/core/Stereo.h         |   6 +-
 .../include/rtabmap/core/StereoCameraModel.h  |   4 +-
 corelib/include/rtabmap/core/StereoDense.h    |   4 +-
 corelib/include/rtabmap/core/Transform.h      |  11 +-
 corelib/include/rtabmap/core/VWDictionary.h   |   4 +-
 corelib/include/rtabmap/core/VisualWord.h     |   4 +-
 .../rtabmap/core/camera/CameraDepthAI.h       |   4 +-
 .../rtabmap/core/camera/CameraFreenect.h      |   4 +-
 .../rtabmap/core/camera/CameraFreenect2.h     |   4 +-
 .../rtabmap/core/camera/CameraImages.h        |   4 +-
 .../include/rtabmap/core/camera/CameraK4A.h   |   4 +-
 .../include/rtabmap/core/camera/CameraK4W2.h  |   4 +-
 .../rtabmap/core/camera/CameraMyntEye.h       |   4 +-
 .../rtabmap/core/camera/CameraOpenNI2.h       |   4 +-
 .../rtabmap/core/camera/CameraOpenNICV.h      |   4 +-
 .../rtabmap/core/camera/CameraOpenni.h        |   4 +-
 .../rtabmap/core/camera/CameraRGBDImages.h    |   2 +-
 .../rtabmap/core/camera/CameraRealSense.h     |   5 +-
 .../rtabmap/core/camera/CameraRealSense2.h    |   4 +-
 .../rtabmap/core/camera/CameraStereoDC1394.h  |   4 +-
 .../core/camera/CameraStereoFlyCapture2.h     |   4 +-
 .../rtabmap/core/camera/CameraStereoImages.h  |   3 +-
 .../rtabmap/core/camera/CameraStereoTara.h    |   4 +-
 .../rtabmap/core/camera/CameraStereoVideo.h   |   4 +-
 .../rtabmap/core/camera/CameraStereoZed.h     |   4 +-
 .../rtabmap/core/camera/CameraStereoZedOC.h   |   4 +-
 .../include/rtabmap/core/camera/CameraVideo.h |   4 +-
 .../clams/discrete_depth_distortion_model.h   |   6 +-
 .../rtabmap/core/clams/frame_projector.h      |   3 +-
 .../rtabmap/core/clams/slam_calibrator.h      |   4 +-
 .../rtabmap/core/odometry/OdometryDVO.h       |   2 +-
 .../rtabmap/core/odometry/OdometryF2F.h       |   2 +-
 .../rtabmap/core/odometry/OdometryF2M.h       |   2 +-
 .../rtabmap/core/odometry/OdometryFLOAM.h     |   2 +-
 .../rtabmap/core/odometry/OdometryFovis.h     |   2 +-
 .../rtabmap/core/odometry/OdometryLOAM.h      |   2 +-
 .../rtabmap/core/odometry/OdometryMSCKF.h     |   2 +-
 .../rtabmap/core/odometry/OdometryMono.h      |   2 +-
 .../rtabmap/core/odometry/OdometryORBSLAM.h   |   2 +-
 .../rtabmap/core/odometry/OdometryOkvis.h     |   2 +-
 .../rtabmap/core/odometry/OdometryOpen3D.h    |   2 +-
 .../rtabmap/core/odometry/OdometryOpenVINS.h  |   2 +-
 .../rtabmap/core/odometry/OdometryVINS.h      |   2 +-
 .../rtabmap/core/odometry/OdometryViso2.h     |   2 +-
 .../rtabmap/core/optimizer/OptimizerCVSBA.h   |   4 +-
 .../rtabmap/core/optimizer/OptimizerCeres.h   |   4 +-
 .../rtabmap/core/optimizer/OptimizerG2O.h     |   4 +-
 .../rtabmap/core/optimizer/OptimizerGTSAM.h   |   4 +-
 .../rtabmap/core/optimizer/OptimizerTORO.h    |   4 +-
 .../include/rtabmap/core/stereo/StereoBM.h    |   4 +-
 .../include/rtabmap/core/stereo/StereoSGBM.h  |   4 +-
 corelib/include/rtabmap/core/util2d.h         |  52 ++--
 corelib/include/rtabmap/core/util3d.h         | 156 +++++------
 .../rtabmap/core/util3d_correspondences.h     |  22 +-
 .../include/rtabmap/core/util3d_features.h    |  14 +-
 .../include/rtabmap/core/util3d_filtering.h   | 255 +++++++++---------
 corelib/include/rtabmap/core/util3d_mapping.h |  36 +--
 .../rtabmap/core/util3d_motion_estimation.h   |  10 +-
 .../rtabmap/core/util3d_registration.h        |  24 +-
 corelib/include/rtabmap/core/util3d_surface.h | 143 +++++-----
 .../include/rtabmap/core/util3d_transforms.h  |  44 +--
 corelib/src/CMakeLists.txt                    | 126 ++++++---
 corelib/src/Graph.cpp                         |   2 +-
 corelib/src/Statistics.cpp                    |   2 +-
 corelib/src/util3d.cpp                        |   4 +-
 corelib/src/util3d_filtering.cpp              |   2 +-
 examples/BOWMapping/CMakeLists.txt            |  35 +--
 examples/NoEventsExample/CMakeLists.txt       |  50 +---
 examples/RGBDMapping/CMakeLists.txt           |  72 +----
 examples/WifiMapping/CMakeLists.txt           |  66 +----
 guilib/include/rtabmap/gui/AboutDialog.h      |   4 +-
 .../include/rtabmap/gui/CalibrationDialog.h   |   4 +-
 guilib/include/rtabmap/gui/CameraViewer.h     |   4 +-
 guilib/include/rtabmap/gui/CloudViewer.h      |   4 +-
 .../rtabmap/gui/CloudViewerCellPicker.h       |   4 +-
 .../rtabmap/gui/CloudViewerInteractorStyle.h  |   4 +-
 guilib/include/rtabmap/gui/ConsoleWidget.h    |   4 +-
 .../gui/CreateSimpleCalibrationDialog.h       |   4 +-
 guilib/include/rtabmap/gui/DataRecorder.h     |   4 +-
 guilib/include/rtabmap/gui/DatabaseViewer.h   |   4 +-
 .../rtabmap/gui/DepthCalibrationDialog.h      |   4 +-
 .../rtabmap/gui/EditConstraintDialog.h        |   4 +-
 guilib/include/rtabmap/gui/EditDepthArea.h    |   4 +-
 guilib/include/rtabmap/gui/EditMapArea.h      |   4 +-
 .../include/rtabmap/gui/ExportBundlerDialog.h |   8 +-
 .../include/rtabmap/gui/ExportCloudsDialog.h  |   8 +-
 guilib/include/rtabmap/gui/ExportDialog.h     |   8 +-
 guilib/include/rtabmap/gui/GraphViewer.h      |   4 +-
 guilib/include/rtabmap/gui/ImageView.h        |   4 +-
 guilib/include/rtabmap/gui/KeypointItem.h     |   4 +-
 .../include/rtabmap/gui/LoopClosureViewer.h   |   4 +-
 guilib/include/rtabmap/gui/MainWindow.h       |   4 +-
 .../include/rtabmap/gui/MapVisibilityWidget.h |   4 +-
 .../rtabmap/gui/MultiSessionLocSubView.h      |   4 +-
 .../rtabmap/gui/MultiSessionLocWidget.h       |   4 +-
 guilib/include/rtabmap/gui/OdometryViewer.h   |   4 +-
 .../include/rtabmap/gui/ParametersToolBox.h   |   4 +-
 guilib/include/rtabmap/gui/PdfPlot.h          |   6 +-
 .../rtabmap/gui/PostProcessingDialog.h        |   4 +-
 .../include/rtabmap/gui/PreferencesDialog.h   |   4 +-
 guilib/include/rtabmap/gui/ProgressDialog.h   |   4 +-
 guilib/include/rtabmap/gui/RtabmapGuiExp.h    |  41 ---
 guilib/include/rtabmap/gui/StatsToolBox.h     |   6 +-
 guilib/include/rtabmap/utilite/UImageView.h   |   4 +-
 guilib/include/rtabmap/utilite/UPlot.h        |  18 +-
 guilib/src/CMakeLists.txt                     | 102 +++----
 package.xml                                   |   2 +-
 tools/Calibration/CMakeLists.txt              |  40 +--
 tools/Camera/CMakeLists.txt                   |  18 +-
 tools/CameraRGBD/CMakeLists.txt               |  40 +--
 tools/CleanupLocalGrids/CMakeLists.txt        |  26 +-
 tools/ConsoleApp/CMakeLists.txt               |  28 +-
 tools/DataRecorder/CMakeLists.txt             |  50 +---
 tools/DatabaseViewer/CMakeLists.txt           |  33 +--
 tools/DetectMoreLoopClosures/CMakeLists.txt   |  30 +--
 tools/EpipolarGeometry/CMakeLists.txt         |  31 +--
 tools/EurocDataset/CMakeLists.txt             |  24 +-
 tools/Export/CMakeLists.txt                   |  26 +-
 tools/ExtractObject/CMakeLists.txt            |  23 +-
 tools/GlobalBundleAdjustment/CMakeLists.txt   |  30 +--
 tools/ImagesJoiner/CMakeLists.txt             |  23 +-
 tools/Info/CMakeLists.txt                     |  30 +--
 tools/KittiDataset/CMakeLists.txt             |  32 +--
 tools/Matcher/CMakeLists.txt                  |  24 +-
 tools/OdometryViewer/CMakeLists.txt           |  50 +---
 tools/Recovery/CMakeLists.txt                 |  30 +--
 tools/Report/CMakeLists.txt                   |  40 +--
 tools/Reprocess/CMakeLists.txt                |  41 +--
 tools/RgbdDataset/CMakeLists.txt              |  49 +---
 tools/StereoEval/CMakeLists.txt               |  18 +-
 tools/VocabularyComparison/CMakeLists.txt     |  15 +-
 utilite/include/rtabmap/utilite/UConversion.h |  54 ++--
 utilite/include/rtabmap/utilite/UDestroyer.h  |   2 -
 utilite/include/rtabmap/utilite/UDirectory.h  |   4 +-
 utilite/include/rtabmap/utilite/UEvent.h      |   4 +-
 .../include/rtabmap/utilite/UEventsHandler.h  |   4 +-
 .../include/rtabmap/utilite/UEventsManager.h  |   4 +-
 .../include/rtabmap/utilite/UEventsSender.h   |   4 +-
 utilite/include/rtabmap/utilite/UFile.h       |   4 +-
 utilite/include/rtabmap/utilite/ULogger.h     |   4 +-
 utilite/include/rtabmap/utilite/UMath.h       |   2 -
 .../include/rtabmap/utilite/UProcessInfo.h    |   4 +-
 utilite/include/rtabmap/utilite/UThread.h     |   4 +-
 utilite/include/rtabmap/utilite/UTimer.h      |   6 +-
 utilite/include/rtabmap/utilite/UVariant.h    |   4 +-
 utilite/include/rtabmap/utilite/UtiLiteExp.h  |  46 ----
 .../include/rtabmap/utilite/Win32/UThreadC.h  |   5 +-
 .../include/rtabmap/utilite/Win32/UWin32.h    |   2 -
 utilite/src/CMakeLists.txt                    |  54 ++--
 191 files changed, 1151 insertions(+), 2200 deletions(-)
 delete mode 100644 RTABMapConfigVersion.cmake.in
 delete mode 100644 corelib/include/rtabmap/core/RtabmapExp.h
 delete mode 100644 guilib/include/rtabmap/gui/RtabmapGuiExp.h
 delete mode 100644 utilite/include/rtabmap/utilite/UtiLiteExp.h

diff --git a/.github/workflows/cmake-ros.yml b/.github/workflows/cmake-ros.yml
index da468c48ec..b5c58856f2 100644
--- a/.github/workflows/cmake-ros.yml
+++ b/.github/workflows/cmake-ros.yml
@@ -2,10 +2,10 @@ name: CMake-ROS
 
 on:
   push:
-    branches:
-      - '**'
+    branches: 
+      - master
   pull_request:
-    branches:
+    branches: 
       - '**'
 
 env:
diff --git a/.github/workflows/cmake.yml b/.github/workflows/cmake.yml
index d7bc879335..cfad708574 100644
--- a/.github/workflows/cmake.yml
+++ b/.github/workflows/cmake.yml
@@ -3,7 +3,7 @@ name: CMake
 on:
   push:
     branches: 
-      - '**'
+      - master
   pull_request:
     branches: 
       - '**'
diff --git a/CMakeLists.txt b/CMakeLists.txt
index eae5d07a9d..52cfc1f8c5 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -19,8 +19,8 @@ SET(CMAKE_MODULE_PATH "${PROJECT_SOURCE_DIR}/cmake_modules")
 # VERSION
 #######################
 SET(RTABMAP_MAJOR_VERSION 0)
-SET(RTABMAP_MINOR_VERSION 20)
-SET(RTABMAP_PATCH_VERSION 23)
+SET(RTABMAP_MINOR_VERSION 21)
+SET(RTABMAP_PATCH_VERSION 0)
 SET(RTABMAP_VERSION
   ${RTABMAP_MAJOR_VERSION}.${RTABMAP_MINOR_VERSION}.${RTABMAP_PATCH_VERSION})
   
@@ -296,10 +296,7 @@ IF(WITH_QT)
     # look for Qt5 (if vtk>5 is installed) before Qt4
     IF("${VTK_MAJOR_VERSION}" GREATER 5)
         if(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5")
-            FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui PrintSupport QUIET)
-            IF(Qt5_FOUND)
-                FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui PrintSupport OPTIONAL_COMPONENTS Svg)
-            ENDIF(Qt5_FOUND)
+            FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui PrintSupport OpenGL OPTIONAL_COMPONENTS Svg)
         ENDIF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5")
     ENDIF("${VTK_MAJOR_VERSION}" GREATER 5)
 
@@ -823,11 +820,6 @@ ENDIF(APPLE AND BUILD_AS_BUNDLE)
 
 ####### SOURCES (Projects) #######
 
-# CONF_DEPENDENCIES contains only dependencies not required by the headers
-SET(CONF_DEPENDENCIES 
-    ${ZLIB_LIBRARIES}
-)
-
 # OpenCV2 has nonfree if OPENCV_NONFREE_FOUND
 # OpenCV<=3.4.2 has nonfree if OPENCV_XFEATURES2D_FOUND
 # OpenCV>3.4.2 has nonfree if OPENCV_XFEATURES2D_FOUND and OPENCV_ENABLE_NONFREE is defined
@@ -848,15 +840,12 @@ IF(NOT G2O_FOUND)
    SET(G2O "//")
    SET(G2O_CPP_CONF "//")
 ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${G2O_LIBRARIES})
    IF(NOT G2O_CPP11)
-   SET(G2O_CPP_CONF "//")
+     SET(G2O_CPP_CONF "//")
    ENDIF(NOT G2O_CPP11)
 ENDIF()
 IF(NOT GTSAM_FOUND)
    SET(GTSAM "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${GTSAM_LIBRARIES})
 ENDIF()
 IF(NOT MRPT_FOUND)
    SET(MRPT "//")
@@ -872,8 +861,6 @@ IF(NOT WITH_VERTIGO)
 ENDIF(NOT WITH_VERTIGO)
 IF(NOT cvsba_FOUND)
    SET(CVSBA "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${cvsba_LIBRARIES})
 ENDIF()
 IF(NOT libpointmatcher_FOUND)
    SET(POINTMATCHER "//")
@@ -901,61 +888,61 @@ IF(NOT floam_FOUND)
 ENDIF(NOT floam_FOUND)
 IF(NOT Freenect_FOUND)
    SET(FREENECT "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${Freenect_LIBRARIES})
 ENDIF()
 IF(NOT freenect2_FOUND)
    SET(FREENECT2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${freenect2_LIBRARIES})
 ENDIF()
 IF(NOT KinectSDK2_FOUND)
    SET(K4W2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${KinectSDK2_LIBRARIES})
 ENDIF()
 IF(NOT k4a_FOUND)
    SET(K4A "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${k4a_LIBRARIES})
+   SET(CONF_WITH_K4A 0)
+ELSE()
+   SET(CONF_WITH_K4A 1)
+   IF(WIN32)
+      install(
+         FILES
+         "${CMAKE_CURRENT_SOURCE_DIR}/cmake_modules/FindK4A.cmake"
+         DESTINATION ${INSTALL_CMAKE_DIR}/Modules/.
+         COMPONENT devel
+      )
+   ENDIF(WIN32)
 ENDIF()
 IF(NOT OpenNI2_FOUND)
    SET(OPENNI2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${OpenNI2_LIBRARIES})
 ENDIF()
 IF(NOT DC1394_FOUND)
    SET(DC1394 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${DC1394_LIBRARIES})
 ENDIF()
 IF(NOT FlyCapture2_FOUND)
    SET(FLYCAPTURE2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${FlyCapture2_LIBRARIES})
 ENDIF()
 IF(NOT ZED_FOUND)
    SET(ZED "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${ZED_LIBRARIES} ${CUDA_LIBRARIES}) 
 ENDIF()
 IF(NOT ZEDOC_FOUND)
    SET(ZEDOC "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${ZEDOC_LIBRARIES}) 
 ENDIF()
 IF(NOT RealSense_FOUND)
    SET(REALSENSE "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${RealSense_LIBRARIES}) 
 ENDIF()
 IF(NOT RealSenseSlam_FOUND)
    SET(REALSENSESLAM "//")
 ENDIF(NOT RealSenseSlam_FOUND)
 IF(NOT realsense2_FOUND)
    SET(REALSENSE2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${realsense2_LIBRARIES}) 
+   SET(CONF_WITH_REALSENSE2 0)
+ELSE()
+   SET(CONF_WITH_REALSENSE2 1)
+   IF(WIN32)
+      install(
+         FILES
+         "${CMAKE_CURRENT_SOURCE_DIR}/cmake_modules/FindRealSense2.cmake"
+         DESTINATION ${INSTALL_CMAKE_DIR}/Modules/.
+         COMPONENT devel
+      )
+   ENDIF(WIN32)
 ENDIF()
 IF(NOT mynteye_FOUND)
    SET(MYNTEYE "//")
@@ -965,65 +952,45 @@ IF(NOT depthai_FOUND)
    SET(DEPTHAI "//")
 ELSE()
    SET(CONF_DEPTH_AI ON) 
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} depthai::core depthai::opencv) 
 ENDIF()
 IF(NOT octomap_FOUND)
    SET(OCTOMAP "//")
+   SET(CONF_WITH_OCTOMAP 0)
 ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${OCTOMAP_LIBRARIES}) 
+   SET(CONF_WITH_OCTOMAP 1)
 ENDIF()
 IF(NOT CPUTSDF_FOUND)
    SET(CPUTSDF "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${CPUTSDF_LIBRARIES}) 
 ENDIF()
 IF(NOT open_chisel_FOUND)
    SET(OPENCHISEL "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${open_chisel_LIBRARIES}) 
 ENDIF()
 IF(NOT AliceVision_FOUND)
    SET(ALICE_VISION "//")
 ENDIF(NOT AliceVision_FOUND)
 IF(NOT libfovis_FOUND)
    SET(FOVIS "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${libfovis_LIBRARIES}) 
 ENDIF()
 IF(NOT libviso2_FOUND)
    SET(VISO2 "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${libviso2_LIBRARIES}) 
 ENDIF()
 IF(NOT dvo_core_FOUND)
    SET(DVO "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${dvo_core_LIBRARIES}) 
 ENDIF()
 IF(NOT okvis_FOUND)
    SET(OKVIS "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${OKVIS_LIBRARIES}) 
 ENDIF()
 IF(NOT msckf_vio_FOUND)
    SET(MSCKF_VIO "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${msckf_vio_LIBRARIES}) 
 ENDIF()
 IF(NOT vins_FOUND)
    SET(VINS "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${vins_LIBRARIES}) 
 ENDIF()
 IF(NOT ov_msckf_FOUND)
    SET(OPENVINS "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${ov_msckf_LIBRARIES}) 
 ENDIF()
 IF(NOT ORB_SLAM_FOUND)
    SET(ORB_SLAM "//")
-ELSE()
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${ORB_SLAM_LIBRARIES})
 ENDIF()
 IF(NOT WITH_ORB_OCTREE)
    SET(ORB_OCTREE "//")
@@ -1036,22 +1003,16 @@ IF(NOT WITH_PYTHON OR NOT Python3_FOUND)
 ENDIF()
 IF(ADD_VTK_GUI_SUPPORT_QT_TO_CONF)
    SET(CONF_VTK_QT true)
-   IF("${VTK_MAJOR_VERSION}" GREATER 8)
-      SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} VTK::GUISupportQt)
-   ELSE()
-      SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} vtkGUISupportQt)
-   ENDIF()
 ELSE()
    SET(CONF_VTK_QT false)
 ENDIF()
-IF(VTK_USE_QVTK)
-   SET(CONF_DEPENDENCIES ${CONF_DEPENDENCIES} ${QVTK_LIBRARY}) 
-ENDIF(VTK_USE_QVTK)
 IF(NOT WITH_MADGWICK)
    SET(MADGWICK "//")
 ENDIF()
 
-CONFIGURE_FILE(Version.h.in ${CMAKE_CURRENT_BINARY_DIR}/corelib/include/${PROJECT_PREFIX}/core/Version.h)
+CONFIGURE_FILE(Version.h.in ${CMAKE_CURRENT_BINARY_DIR}/corelib/src/include/${PROJECT_PREFIX}/core/Version.h)
+
+include(GenerateExportHeader)
 
 ADD_SUBDIRECTORY( utilite )
 ADD_SUBDIRECTORY( corelib )
@@ -1088,18 +1049,9 @@ ADD_CUSTOM_TARGET(uninstall
   "${CMAKE_COMMAND}" -P "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake")
 
 ####
-# Setup RTABMapConfig.cmake
+# Global Export Target
 ####
-# Create the RTABMapConfig.cmake and RTABMapConfigVersion files
-file(RELATIVE_PATH REL_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/${INSTALL_CMAKE_DIR}" "${CMAKE_INSTALL_PREFIX}/${INSTALL_INCLUDE_DIR}")
-file(RELATIVE_PATH REL_LIB_DIR "${CMAKE_INSTALL_PREFIX}/${INSTALL_CMAKE_DIR}" "${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR}")
-   
-# ... for the build tree
-set(CONF_INCLUDE_DIRS "${PROJECT_BINARY_DIR}/corelib/include"
-                      "${PROJECT_SOURCE_DIR}/corelib/include" 
-                      "${PROJECT_SOURCE_DIR}/guilib/include" 
-                      "${PROJECT_SOURCE_DIR}/utilite/include")
-set(CONF_LIB_DIR "${CMAKE_ARCHIVE_OUTPUT_DIRECTORY} ${CMAKE_RUNTIME_OUTPUT_DIRECTORY}")
+add_library(rtabmap INTERFACE)
 IF(QT4_FOUND OR Qt5_FOUND)
    set(CONF_WITH_GUI ON)
    IF(QT4_FOUND)
@@ -1107,36 +1059,69 @@ IF(QT4_FOUND OR Qt5_FOUND)
    ELSE()
       set(CONF_QT_VERSION 5)
    ENDIF()
+   target_link_libraries(rtabmap INTERFACE rtabmap_utilite rtabmap_core rtabmap_gui)
 ELSE()
    set(CONF_WITH_GUI OFF)
+   target_link_libraries(rtabmap INTERFACE rtabmap_utilite rtabmap_core)
 ENDIF()
-configure_file(RTABMapConfig.cmake.in
-  "${PROJECT_BINARY_DIR}/RTABMapConfig.cmake" @ONLY)
-  
-# ... for the install tree
-set(CONF_INCLUDE_DIRS "\${RTABMap_CMAKE_DIR}/${REL_INCLUDE_DIR}")
-set(CONF_LIB_DIR "\${RTABMap_CMAKE_DIR}/${REL_LIB_DIR}")
-configure_file(RTABMapConfig.cmake.in
-  "${PROJECT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/RTABMapConfig.cmake" @ONLY)
+install(TARGETS rtabmap EXPORT rtabmapTargets)
+export(EXPORT rtabmapTargets
+  FILE "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Targets.cmake"
+)
+install(EXPORT rtabmapTargets
+  FILE
+    ${PROJECT_NAME}Targets.cmake
+  DESTINATION
+    ${INSTALL_CMAKE_DIR}
+  COMPONENT
+    devel
+)
+
+####
+# Setup RTABMapConfig.cmake
+####
+include(CMakePackageConfigHelpers)
+write_basic_package_version_file(
+  "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake"
+  VERSION ${PROJECT_VERSION}
+  COMPATIBILITY AnyNewerVersion
+)
+
+# Build tree:
+SET(CONF_MODULES_DIR "../cmake_modules")
+configure_file(
+  ${PROJECT_NAME}Config.cmake.in
+  "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}Config.cmake"
+  @ONLY
+)
+
+# Install tree:
+SET(CONF_MODULES_DIR "Modules")
+configure_file(
+  ${PROJECT_NAME}Config.cmake.in
+  "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}Config.cmake"
+  @ONLY
+)
+install(
+  FILES
+    "${CMAKE_CURRENT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/${PROJECT_NAME}Config.cmake"
+    "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}ConfigVersion.cmake"
+  DESTINATION
+    ${INSTALL_CMAKE_DIR}
+  COMPONENT
+    devel
+)
   
-# ... for both
-configure_file(RTABMapConfigVersion.cmake.in
-  "${PROJECT_BINARY_DIR}/RTABMapConfigVersion.cmake" @ONLY)
-
-# Install the RTABMapConfig.cmake and RTABMapConfigVersion.cmake
-install(FILES
-  "${PROJECT_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/RTABMapConfig.cmake"
-  "${PROJECT_BINARY_DIR}/RTABMapConfigVersion.cmake"
-  DESTINATION "${INSTALL_CMAKE_DIR}" COMPONENT devel)
 ####
 
 ### Install package.xml for catkin
-install(FILES package.xml DESTINATION "${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_PREFIX}")
+install(FILES package.xml DESTINATION "${CMAKE_INSTALL_DATAROOTDIR}/${PROJECT_PREFIX}" COMPONENT devel)
 
 #######################
 # CPACK (Packaging)
 #######################
 IF(BUILD_AS_BUNDLE)
+  SET(CMAKE_INSTALL_SYSTEM_RUNTIME_COMPONENT runtime)
   INCLUDE(InstallRequiredSystemLibraries)
 ENDIF(BUILD_AS_BUNDLE)
 
@@ -1153,6 +1138,7 @@ SET(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_VERSION_PATCH}")
 #SET(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}")
 SET(CPACK_PACKAGE_CONTACT "matlabbe@gmail.com")
 
+
 set(CPACK_SOURCE_IGNORE_FILES 
   "\\\\.svn/" 
   "\\\\.settings/" 
@@ -1557,7 +1543,11 @@ MESSAGE(STATUS "  With RealSense            = NO (librealsense not found)")
 ENDIF()
 
 IF(realsense2_FOUND)
+IF(WIN32)
+MESSAGE(STATUS "  With RealSense2           = YES (License: Apache-2)")
+ELSE()
 MESSAGE(STATUS "  With RealSense2 ${realsense2_VERSION}    = YES (License: Apache-2)")
+ENDIF()
 ELSEIF(NOT WITH_REALSENSE2)
 MESSAGE(STATUS "  With RealSense2           = NO (WITH_REALSENSE2=OFF)")
 ELSE()
diff --git a/RTABMapConfig.cmake.in b/RTABMapConfig.cmake.in
index da95aeecae..10dbaadbc5 100644
--- a/RTABMapConfig.cmake.in
+++ b/RTABMapConfig.cmake.in
@@ -1,99 +1,78 @@
-# - Config file for the RTABMap package
-# Components:
-#  core    (required)
-#  gui     (optional)
-#  utilite (required)
-# It defines the following variables
-#  RTABMap_INCLUDE_DIRS - include directories for RTABMap
-#  RTABMap_LIBRARIES    - libraries to link against
-#  RTABMap_CORE         - core library
-#  RTABMap_UTILITE      - utilite library
-#  RTABMap_GUI          - gui library (set if RTABMap is built with Qt)
+include(CMakeFindDependencyMacro)
+find_dependency(OpenCV)
+find_dependency(PCL 1.7)
 
-# Compute paths
-get_filename_component(RTABMap_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
-set(RTABMap_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@")
-
-#core lib
-find_library(RTABMap_CORE_RELEASE NAMES rtabmap_core NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
-find_library(RTABMap_CORE_DEBUG NAMES rtabmap_cored NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
-
-IF(RTABMap_CORE_DEBUG AND RTABMap_CORE_RELEASE)
-   SET(RTABMap_CORE
-      debug ${RTABMap_CORE_DEBUG}
-      optimized ${RTABMap_CORE_RELEASE}
-   )
-ELSEIF(RTABMap_CORE_DEBUG)
-   SET(RTABMap_CORE ${RTABMap_CORE_DEBUG})
-ELSE()
-   SET(RTABMap_CORE ${RTABMap_CORE_RELEASE})
+IF(EXISTS "${CMAKE_CURRENT_LIST_DIR}/@CONF_MODULES_DIR@")
+    list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/@CONF_MODULES_DIR@")
 ENDIF()
 
-#utilite lib
-find_library(RTABMap_UTILITE_RELEASE NAMES rtabmap_utilite NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
-find_library(RTABMap_UTILITE_DEBUG NAMES rtabmap_utilited NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
+IF(@CONF_WITH_REALSENSE2@)
+    IF(WIN32)
+        find_dependency(RealSense2)
+    ELSE()
+        find_dependency(realsense2)
+    ENDIF()
+ENDIF()
 
-IF(RTABMap_UTILITE_DEBUG AND RTABMap_UTILITE_RELEASE)
-   SET(RTABMap_UTILITE
-      debug ${RTABMap_UTILITE_DEBUG}
-      optimized ${RTABMap_UTILITE_RELEASE}
-   )
-ELSEIF(RTABMap_UTILITE_DEBUG)
-   SET(RTABMap_UTILITE ${RTABMap_UTILITE_DEBUG})
-ELSE()
-   SET(RTABMap_UTILITE ${RTABMap_UTILITE_RELEASE})
+IF(@CONF_WITH_K4A@)
+    IF(WIN32)
+        find_dependency(K4A)
+    ELSE()
+        find_dependency(k4a)
+        find_dependency(k4arecord)
+    ENDIF()
 ENDIF()
 
-set(RTABMap_LIBRARIES ${RTABMap_CORE} ${RTABMap_UTILITE})
+IF(@CONF_WITH_OCTOMAP@)
+  find_dependency(octomap)
+ENDIF()
 
-list(LENGTH RTABMap_FIND_COMPONENTS RTABMap_FIND_COMPONENTS_LENGTH)
-set(WITH_GUI ON)
-if(${RTABMap_FIND_COMPONENTS_LENGTH} GREATER 0)
-   list (FIND RTABMap_FIND_COMPONENTS "gui" _index)
-   if (${_index} EQUAL -1)
-      set(WITH_GUI OFF)
-   endif()
-endif(${RTABMap_FIND_COMPONENTS_LENGTH} GREATER 0)
+set(RTABMap_DEFINITIONS ${PCL_DEFINITIONS})
 
+# Provide those for backward compatibilities (e.g., catkin requires them to propagate dependencies)
+set(RTABMap_INCLUDE_DIRS "")
+set(RTABMap_LIBRARIES "")
 
-#gui lib (OFF if RTAB-Map is not built with Qt)
-if(@CONF_WITH_GUI@ AND ${WITH_GUI})
-   find_library(RTABMap_GUI_RELEASE NAMES rtabmap_gui NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
-   find_library(RTABMap_GUI_DEBUG NAMES rtabmap_guid NO_DEFAULT_PATH HINTS @CONF_LIB_DIR@)
-   
-   IF(RTABMap_GUI_DEBUG AND RTABMap_GUI_RELEASE)
-      SET(RTABMap_GUI
-         debug ${RTABMap_GUI_DEBUG}
-         optimized ${RTABMap_GUI_RELEASE}
-      )
-   ELSEIF(RTABMap_GUI_RELEASE)
-      SET(RTABMap_GUI ${RTABMap_GUI_RELEASE})
-   ELSEIF(RTABMap_GUI_DEBUG)
-      SET(RTABMap_GUI ${RTABMap_GUI_DEBUG})
-   ENDIF()
-   
-   set(RTABMap_LIBRARIES ${RTABMap_LIBRARIES} ${RTABMap_GUI})
-elseif(${WITH_GUI})
-   MESSAGE(WARNING "Asked for \"gui\" module but RTABMap hasn't been built with gui support.")
-endif()
+set(_RTABMap_supported_components utilite core gui)
 
-# Dependencies
-if(@CONF_VTK_QT@ AND ${WITH_GUI})
-   find_package(VTK COMPONENTS vtkGUISupportQt NO_MODULE) # to define vtkGUISupportQt target
-endif(@CONF_VTK_QT@ AND ${WITH_GUI})
-if(@CONF_DEPTH_AI@)
-   FIND_PACKAGE(depthai 2 QUIET REQUIRED)
-endif(@CONF_DEPTH_AI@)
-SET(RTABMap_LIBRARIES ${RTABMap_LIBRARIES} "@CONF_DEPENDENCIES@")
+foreach(_comp ${_RTABMap_supported_components})
+  if(EXISTS "${CMAKE_CURRENT_LIST_DIR}/RTABMap_${_comp}Targets.cmake")
+    if (${_comp} STREQUAL "gui")
+      if(@CONF_QT_VERSION@ EQUAL 5)
+        find_dependency(Qt5 COMPONENTS Widgets Core Gui PrintSupport OpenGL OPTIONAL_COMPONENTS Svg)
+      else() # Qt4
+        find_dependency(Qt4 COMPONENTS QtCore QtGui OPTIONAL_COMPONENTS QtSvg)
+      endif()
+      set(RTABMap_QT_VERSION @CONF_QT_VERSION@)
+    endif()
+    include("${CMAKE_CURRENT_LIST_DIR}/RTABMap_${_comp}Targets.cmake")
+    set(RTABMap_${_comp}_FOUND True)
+    get_target_property(RTABMap_${_comp}_INCLUDE_DIRS rtabmap_${_comp} INTERFACE_INCLUDE_DIRECTORIES)
+    get_target_property(RTABMap_${_comp}_LIBRARIES rtabmap_${_comp} INTERFACE_LINK_LIBRARIES)
+    set(RTABMap_INCLUDE_DIRS 
+      ${RTABMap_INCLUDE_DIRS}
+      ${RTABMap_${_comp}_INCLUDE_DIRS})
+    set(RTABMap_LIBRARIES 
+      ${RTABMap_LIBRARIES}
+      rtabmap_${_comp})
+    if(RTABMap_${_comp}_LIBRARIES)
+      set(RTABMap_LIBRARIES 
+        ${RTABMap_LIBRARIES}
+        ${RTABMap_${_comp}_LIBRARIES})
+    endif()
+  else()
+    set(RTABMap_${_comp}_FOUND False)
+  endif()
+endforeach()
 
-#backward compatibilities
-set(RTABMAP_CORE ${RTABMap_CORE})
-set(RTABMAP_UTILITE ${RTABMap_UTILITE})
-if(RTABMap_GUI)
-   set(RTABMAP_GUI ${RTABMap_GUI})
-   set(RTABMAP_QT_VERSION @CONF_QT_VERSION@)
-endif(RTABMap_GUI)
+include("${CMAKE_CURRENT_LIST_DIR}/RTABMapTargets.cmake")
 
-include(FindPackageHandleStandardArgs)
-find_package_handle_standard_args(RTABMap DEFAULT_MSG RTABMap_LIBRARIES RTABMap_INCLUDE_DIRS)
-mark_as_advanced(RTABMap_LIBRARIES RTABMap_INCLUDE_DIRS RTABMap_LIBRARY_DIRS)
\ No newline at end of file
+foreach(_comp ${RTABMap_FIND_COMPONENTS})
+  if (NOT ";${_RTABMap_supported_components};" MATCHES ";${_comp};")
+    set(RTABMap_${_comp}_FOUND False)
+    if(${RTABMap_FIND_REQUIRED_${_comp}})
+      set(RTABMap_FOUND False)
+      set(RTABMap_NOT_FOUND_MESSAGE "Unsupported or not found required component: ${_comp}")
+    endif()
+  endif()
+endforeach()
diff --git a/RTABMapConfigVersion.cmake.in b/RTABMapConfigVersion.cmake.in
deleted file mode 100644
index 4b0a3ae1f5..0000000000
--- a/RTABMapConfigVersion.cmake.in
+++ /dev/null
@@ -1,11 +0,0 @@
-set(PACKAGE_VERSION "@RTABMAP_VERSION@")
-
-# Check whether the requested PACKAGE_FIND_VERSION is compatible
-if("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}")
-  set(PACKAGE_VERSION_COMPATIBLE FALSE)
-else()
-  set(PACKAGE_VERSION_COMPATIBLE TRUE)
-  if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}")
-    set(PACKAGE_VERSION_EXACT TRUE)
-  endif()
-endif()
diff --git a/app/src/CMakeLists.txt b/app/src/CMakeLists.txt
index b20a07d42b..4e785afa93 100644
--- a/app/src/CMakeLists.txt
+++ b/app/src/CMakeLists.txt
@@ -3,32 +3,6 @@ SET(SRC_FILES
     main.cpp
 )
 
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${CMAKE_CURRENT_SOURCE_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-    ${QT_LIBRARIES} 
-    ${OpenCV_LIBS}
-    ${PCL_LIBRARIES}
-)
-
-# rc.exe has problems with these defintions... commented!
-#add_definitions(${PCL_DEFINITIONS})
-
-# Make sure the compiler can find include files from our library.
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 # For Apple set the icns file containing icons
 IF(APPLE AND BUILD_AS_BUNDLE)
   # set how it shows up in the Info.plist file
@@ -54,36 +28,29 @@ ENDIF(WIN32)
 
 # Add binary
 IF(APPLE AND BUILD_AS_BUNDLE)
-  ADD_EXECUTABLE(rtabmap MACOSX_BUNDLE ${SRC_FILES})
+  ADD_EXECUTABLE(rtabmap_app MACOSX_BUNDLE ${SRC_FILES})
 ELSEIF(MINGW)
-  ADD_EXECUTABLE(rtabmap WIN32 ${SRC_FILES})
+  ADD_EXECUTABLE(rtabmap_app WIN32 ${SRC_FILES})
 ELSE()
-  ADD_EXECUTABLE(rtabmap ${SRC_FILES})
+  ADD_EXECUTABLE(rtabmap_app ${SRC_FILES})
 ENDIF()
-TARGET_LINK_LIBRARIES(rtabmap rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
-IF(Qt5_FOUND)
-    IF(Qt5Svg_FOUND)
-        QT5_USE_MODULES(rtabmap Widgets Core Gui Svg PrintSupport)
-    ELSE()
-        QT5_USE_MODULES(rtabmap Widgets Core Gui PrintSupport)
-    ENDIF()
-ENDIF(Qt5_FOUND)
+TARGET_LINK_LIBRARIES(rtabmap_app rtabmap_gui)
 
 IF(APPLE AND BUILD_AS_BUNDLE)
-  SET_TARGET_PROPERTIES(rtabmap PROPERTIES
+  SET_TARGET_PROPERTIES(rtabmap_app PROPERTIES
     OUTPUT_NAME ${CMAKE_BUNDLE_NAME})
 ELSEIF(WIN32)
-  SET_TARGET_PROPERTIES(rtabmap PROPERTIES
+  SET_TARGET_PROPERTIES(rtabmap_app PROPERTIES
     OUTPUT_NAME ${PROJECT_NAME})
 ELSE()
-  SET_TARGET_PROPERTIES(rtabmap PROPERTIES
+  SET_TARGET_PROPERTIES(rtabmap_app PROPERTIES
     OUTPUT_NAME ${PROJECT_PREFIX})
 ENDIF()
 
 #---------------------------
 # Installation stuff
 #--------------------------- 
-INSTALL(TARGETS rtabmap
+INSTALL(TARGETS rtabmap_app
         RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" COMPONENT runtime
         BUNDLE DESTINATION "${CMAKE_BUNDLE_LOCATION}" COMPONENT runtime)
       
diff --git a/corelib/include/rtabmap/core/BayesFilter.h b/corelib/include/rtabmap/core/BayesFilter.h
index 01f4fe30bf..ac2533903b 100644
--- a/corelib/include/rtabmap/core/BayesFilter.h
+++ b/corelib/include/rtabmap/core/BayesFilter.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef BAYESFILTER_H_
 #define BAYESFILTER_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/core/core.hpp>
 #include <list>
@@ -41,7 +41,7 @@ namespace rtabmap {
 class Memory;
 class Signature;
 
-class RTABMAP_EXP BayesFilter
+class RTABMAP_CORE_EXPORT BayesFilter
 {
 public:
 	BayesFilter(const ParametersMap & parameters = ParametersMap());
diff --git a/corelib/include/rtabmap/core/Camera.h b/corelib/include/rtabmap/core/Camera.h
index 9ac879f4a9..9c324cd786 100644
--- a/corelib/include/rtabmap/core/Camera.h
+++ b/corelib/include/rtabmap/core/Camera.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/highgui/highgui.hpp>
 #include "rtabmap/core/SensorData.h"
@@ -47,7 +47,7 @@ namespace rtabmap
  * Class Camera
  *
  */
-class RTABMAP_EXP Camera
+class RTABMAP_CORE_EXPORT Camera
 {
 public:
 	virtual ~Camera();
diff --git a/corelib/include/rtabmap/core/CameraModel.h b/corelib/include/rtabmap/core/CameraModel.h
index ae36a37291..b24b971b4d 100644
--- a/corelib/include/rtabmap/core/CameraModel.h
+++ b/corelib/include/rtabmap/core/CameraModel.h
@@ -30,12 +30,12 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #include <opencv2/opencv.hpp>
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 #include "rtabmap/core/Transform.h"
 
 namespace rtabmap {
 
-class RTABMAP_EXP CameraModel
+class RTABMAP_CORE_EXPORT CameraModel
 {
 public:
 	/**
@@ -159,7 +159,7 @@ class RTABMAP_EXP CameraModel
 	Transform localTransform_;
 };
 
-RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const CameraModel& model);
+RTABMAP_CORE_EXPORT std::ostream& operator<<(std::ostream& os, const CameraModel& model);
 
 } /* namespace rtabmap */
 #endif /* CAMERAMODEL_H_ */
diff --git a/corelib/include/rtabmap/core/CameraThread.h b/corelib/include/rtabmap/core/CameraThread.h
index 78e6bcf0a1..8dd40469ce 100644
--- a/corelib/include/rtabmap/core/CameraThread.h
+++ b/corelib/include/rtabmap/core/CameraThread.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <rtabmap/core/Transform.h>
@@ -52,7 +52,7 @@ class IMUFilter;
  * Class CameraThread
  *
  */
-class RTABMAP_EXP CameraThread :
+class RTABMAP_CORE_EXPORT CameraThread :
 	public UThread,
 	public UEventsSender
 {
@@ -88,7 +88,8 @@ class RTABMAP_EXP CameraThread :
 	void enableIMUFiltering(int filteringStrategy=1, const ParametersMap & parameters = ParametersMap(), bool baseFrameConversion = false);
 	void disableIMUFiltering();
 
-	RTABMAP_DEPRECATED(void setScanParameters(
+	// Use new version of this function with groundNormalsUp=0.8 for forceGroundNormalsUp=True and groundNormalsUp=0.0 for forceGroundNormalsUp=False.
+	RTABMAP_DEPRECATED void setScanParameters(
 			bool fromDepth,
 			int downsampleStep, // decimation of the depth image in case the scan is from depth image
 			float rangeMin,
@@ -96,7 +97,7 @@ class RTABMAP_EXP CameraThread :
 			float voxelSize,
 			int normalsK,
 			int normalsRadius,
-			bool forceGroundNormalsUp) , "Use new version of this function with groundNormalsUp=0.8 for forceGroundNormalsUp=True and groundNormalsUp=0.0 for forceGroundNormalsUp=False.");
+			bool forceGroundNormalsUp);
 	void setScanParameters(
 			bool fromDepth,
 			int downsampleStep=1, // decimation of the depth image in case the scan is from depth image
diff --git a/corelib/include/rtabmap/core/Compression.h b/corelib/include/rtabmap/core/Compression.h
index dcab29dddd..9ff69a3a71 100644
--- a/corelib/include/rtabmap/core/Compression.h
+++ b/corelib/include/rtabmap/core/Compression.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef COMPRESSION_H_
 #define COMPRESSION_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UThread.h>
 #include <opencv2/opencv.hpp>
@@ -52,7 +52,7 @@ namespace rtabmap {
  *   ct.join();
  *   cv::Mat image = ct.getUncompressedData();
  */
-class RTABMAP_EXP CompressionThread : public UThread
+class RTABMAP_CORE_EXPORT CompressionThread : public UThread
 {
 public:
 	// format : ".png" ".jpg" "" (empty is general)
@@ -70,21 +70,21 @@ class RTABMAP_EXP CompressionThread : public UThread
 	bool compressMode_;
 };
 
-std::vector<unsigned char> RTABMAP_EXP compressImage(const cv::Mat & image, const std::string & format = ".png");
-cv::Mat RTABMAP_EXP compressImage2(const cv::Mat & image, const std::string & format = ".png");
+std::vector<unsigned char> RTABMAP_CORE_EXPORT compressImage(const cv::Mat & image, const std::string & format = ".png");
+cv::Mat RTABMAP_CORE_EXPORT compressImage2(const cv::Mat & image, const std::string & format = ".png");
 
-cv::Mat RTABMAP_EXP uncompressImage(const cv::Mat & bytes);
-cv::Mat RTABMAP_EXP uncompressImage(const std::vector<unsigned char> & bytes);
+cv::Mat RTABMAP_CORE_EXPORT uncompressImage(const cv::Mat & bytes);
+cv::Mat RTABMAP_CORE_EXPORT uncompressImage(const std::vector<unsigned char> & bytes);
 
-std::vector<unsigned char> RTABMAP_EXP compressData(const cv::Mat & data);
-cv::Mat RTABMAP_EXP compressData2(const cv::Mat & data);
+std::vector<unsigned char> RTABMAP_CORE_EXPORT compressData(const cv::Mat & data);
+cv::Mat RTABMAP_CORE_EXPORT compressData2(const cv::Mat & data);
 
-cv::Mat RTABMAP_EXP uncompressData(const cv::Mat & bytes);
-cv::Mat RTABMAP_EXP uncompressData(const std::vector<unsigned char> & bytes);
-cv::Mat RTABMAP_EXP uncompressData(const unsigned char * bytes, unsigned long size);
+cv::Mat RTABMAP_CORE_EXPORT uncompressData(const cv::Mat & bytes);
+cv::Mat RTABMAP_CORE_EXPORT uncompressData(const std::vector<unsigned char> & bytes);
+cv::Mat RTABMAP_CORE_EXPORT uncompressData(const unsigned char * bytes, unsigned long size);
 
-cv::Mat RTABMAP_EXP compressString(const std::string & str);
-std::string RTABMAP_EXP uncompressString(const cv::Mat & bytes);
+cv::Mat RTABMAP_CORE_EXPORT compressString(const std::string & str);
+std::string RTABMAP_CORE_EXPORT uncompressString(const cv::Mat & bytes);
 
 } /* namespace rtabmap */
 #endif /* COMPRESSION_H_ */
diff --git a/corelib/include/rtabmap/core/DBDriver.h b/corelib/include/rtabmap/core/DBDriver.h
index 7499189c62..1335189272 100644
--- a/corelib/include/rtabmap/core/DBDriver.h
+++ b/corelib/include/rtabmap/core/DBDriver.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef DBDRIVER_H_
 #define DBDRIVER_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <string>
 #include <list>
@@ -59,7 +59,7 @@ class VisualWord;
 //but never, never try to use the same connection simultaneously in
 //two or more threads."
 //
-class RTABMAP_EXP DBDriver : public UThreadNode
+class RTABMAP_CORE_EXPORT DBDriver : public UThreadNode
 {
 public:
 	static DBDriver * create(const ParametersMap & parameters = ParametersMap());
diff --git a/corelib/include/rtabmap/core/DBDriverSqlite3.h b/corelib/include/rtabmap/core/DBDriverSqlite3.h
index 56abb750df..463e916817 100644
--- a/corelib/include/rtabmap/core/DBDriverSqlite3.h
+++ b/corelib/include/rtabmap/core/DBDriverSqlite3.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef DBDRIVERSQLITE3_H_
 #define DBDRIVERSQLITE3_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 #include "rtabmap/core/DBDriver.h"
 #include <opencv2/features2d/features2d.hpp>
 
@@ -37,7 +37,7 @@ typedef struct sqlite3 sqlite3;
 
 namespace rtabmap {
 
-class RTABMAP_EXP DBDriverSqlite3: public DBDriver {
+class RTABMAP_CORE_EXPORT DBDriverSqlite3: public DBDriver {
 public:
 	DBDriverSqlite3(const ParametersMap & parameters = ParametersMap());
 	virtual ~DBDriverSqlite3();
diff --git a/corelib/include/rtabmap/core/DBReader.h b/corelib/include/rtabmap/core/DBReader.h
index 6fa1027937..f6fc97c00d 100644
--- a/corelib/include/rtabmap/core/DBReader.h
+++ b/corelib/include/rtabmap/core/DBReader.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef DBREADER_H_
 #define DBREADER_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UTimer.h>
 #include <rtabmap/core/Transform.h>
@@ -43,7 +43,7 @@ namespace rtabmap {
 
 class DBDriver;
 
-class RTABMAP_EXP DBReader : public Camera {
+class RTABMAP_CORE_EXPORT DBReader : public Camera {
 public:
 	DBReader(const std::string & databasePath,
 			 float frameRate = 0.0f, // -1 = use Database stamps, 0 = inf
diff --git a/corelib/include/rtabmap/core/EpipolarGeometry.h b/corelib/include/rtabmap/core/EpipolarGeometry.h
index 7f13c734be..e9408cd83c 100644
--- a/corelib/include/rtabmap/core/EpipolarGeometry.h
+++ b/corelib/include/rtabmap/core/EpipolarGeometry.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 #include "rtabmap/core/Parameters.h"
 #include "rtabmap/utilite/UStl.h"
 #include <opencv2/core/core.hpp>
@@ -42,7 +42,7 @@ namespace rtabmap
 
 class Signature;
 
-class RTABMAP_EXP EpipolarGeometry
+class RTABMAP_CORE_EXPORT EpipolarGeometry
 {
 public:
 	EpipolarGeometry(const ParametersMap & parameters = ParametersMap());
diff --git a/corelib/include/rtabmap/core/Features2d.h b/corelib/include/rtabmap/core/Features2d.h
index 0d9d838f57..81ac630d72 100644
--- a/corelib/include/rtabmap/core/Features2d.h
+++ b/corelib/include/rtabmap/core/Features2d.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef FEATURES2D_H_
 #define FEATURES2D_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/core/core.hpp>
@@ -103,7 +103,7 @@ class CV_ORB;
 #endif
 
 // Feature2D
-class RTABMAP_EXP Feature2D {
+class RTABMAP_CORE_EXPORT Feature2D {
 public:
 	enum Type {kFeatureUndef=-1,
 		kFeatureSurf=0,
@@ -247,7 +247,7 @@ class RTABMAP_EXP Feature2D {
 };
 
 //SURF
-class RTABMAP_EXP SURF : public Feature2D
+class RTABMAP_CORE_EXPORT SURF : public Feature2D
 {
 public:
 	SURF(const ParametersMap & parameters = ParametersMap());
@@ -274,7 +274,7 @@ class RTABMAP_EXP SURF : public Feature2D
 };
 
 //SIFT
-class RTABMAP_EXP SIFT : public Feature2D
+class RTABMAP_CORE_EXPORT SIFT : public Feature2D
 {
 public:
 	SIFT(const ParametersMap & parameters = ParametersMap());
@@ -298,7 +298,7 @@ class RTABMAP_EXP SIFT : public Feature2D
 };
 
 //ORB
-class RTABMAP_EXP ORB : public Feature2D
+class RTABMAP_CORE_EXPORT ORB : public Feature2D
 {
 public:
 	ORB(const ParametersMap & parameters = ParametersMap());
@@ -329,7 +329,7 @@ class RTABMAP_EXP ORB : public Feature2D
 };
 
 //FAST
-class RTABMAP_EXP FAST : public Feature2D
+class RTABMAP_CORE_EXPORT FAST : public Feature2D
 {
 public:
 	FAST(const ParametersMap & parameters = ParametersMap());
@@ -365,7 +365,7 @@ class RTABMAP_EXP FAST : public Feature2D
 };
 
 //FAST_BRIEF
-class RTABMAP_EXP FAST_BRIEF : public FAST
+class RTABMAP_CORE_EXPORT FAST_BRIEF : public FAST
 {
 public:
 	FAST_BRIEF(const ParametersMap & parameters = ParametersMap());
@@ -384,7 +384,7 @@ class RTABMAP_EXP FAST_BRIEF : public FAST
 };
 
 //FAST_FREAK
-class RTABMAP_EXP FAST_FREAK : public FAST
+class RTABMAP_CORE_EXPORT FAST_FREAK : public FAST
 {
 public:
 	FAST_FREAK(const ParametersMap & parameters = ParametersMap());
@@ -406,7 +406,7 @@ class RTABMAP_EXP FAST_FREAK : public FAST
 };
 
 //GFTT
-class RTABMAP_EXP GFTT : public Feature2D
+class RTABMAP_CORE_EXPORT GFTT : public Feature2D
 {
 public:
 	GFTT(const ParametersMap & parameters = ParametersMap());
@@ -428,7 +428,7 @@ class RTABMAP_EXP GFTT : public Feature2D
 };
 
 //GFTT_BRIEF
-class RTABMAP_EXP GFTT_BRIEF : public GFTT
+class RTABMAP_CORE_EXPORT GFTT_BRIEF : public GFTT
 {
 public:
 	GFTT_BRIEF(const ParametersMap & parameters = ParametersMap());
@@ -447,7 +447,7 @@ class RTABMAP_EXP GFTT_BRIEF : public GFTT
 };
 
 //GFTT_FREAK
-class RTABMAP_EXP GFTT_FREAK : public GFTT
+class RTABMAP_CORE_EXPORT GFTT_FREAK : public GFTT
 {
 public:
 	GFTT_FREAK(const ParametersMap & parameters = ParametersMap());
@@ -469,7 +469,7 @@ class RTABMAP_EXP GFTT_FREAK : public GFTT
 };
 
 //SURF_FREAK
-class RTABMAP_EXP SURF_FREAK : public SURF
+class RTABMAP_CORE_EXPORT SURF_FREAK : public SURF
 {
 public:
 	SURF_FREAK(const ParametersMap & parameters = ParametersMap());
@@ -491,7 +491,7 @@ class RTABMAP_EXP SURF_FREAK : public SURF
 };
 
 //GFTT_ORB
-class RTABMAP_EXP GFTT_ORB : public GFTT
+class RTABMAP_CORE_EXPORT GFTT_ORB : public GFTT
 {
 public:
 	GFTT_ORB(const ParametersMap & parameters = ParametersMap());
@@ -508,7 +508,7 @@ class RTABMAP_EXP GFTT_ORB : public GFTT
 };
 
 //BRISK
-class RTABMAP_EXP BRISK : public Feature2D
+class RTABMAP_CORE_EXPORT BRISK : public Feature2D
 {
 public:
 	BRISK(const ParametersMap & parameters = ParametersMap());
@@ -530,7 +530,7 @@ class RTABMAP_EXP BRISK : public Feature2D
 };
 
 //KAZE
-class RTABMAP_EXP KAZE : public Feature2D
+class RTABMAP_CORE_EXPORT KAZE : public Feature2D
 {
 public:
 	KAZE(const ParametersMap & parameters = ParametersMap());
@@ -557,7 +557,7 @@ class RTABMAP_EXP KAZE : public Feature2D
 };
 
 //ORB OCTREE
-class RTABMAP_EXP ORBOctree : public Feature2D
+class RTABMAP_CORE_EXPORT ORBOctree : public Feature2D
 {
 public:
 	ORBOctree(const ParametersMap & parameters = ParametersMap());
@@ -583,7 +583,7 @@ class RTABMAP_EXP ORBOctree : public Feature2D
 };
 
 //SuperPointTorch
-class RTABMAP_EXP SuperPointTorch : public Feature2D
+class RTABMAP_CORE_EXPORT SuperPointTorch : public Feature2D
 {
 public:
 	SuperPointTorch(const ParametersMap & parameters = ParametersMap());
@@ -606,7 +606,7 @@ class RTABMAP_EXP SuperPointTorch : public Feature2D
 };
 
 //GFTT_DAISY
-class RTABMAP_EXP GFTT_DAISY : public GFTT
+class RTABMAP_CORE_EXPORT GFTT_DAISY : public GFTT
 {
 public:
 	GFTT_DAISY(const ParametersMap & parameters = ParametersMap());
@@ -630,7 +630,7 @@ class RTABMAP_EXP GFTT_DAISY : public GFTT
 };
 
 //SURF_DAISY
-class RTABMAP_EXP SURF_DAISY : public SURF
+class RTABMAP_CORE_EXPORT SURF_DAISY : public SURF
 {
 public:
 	SURF_DAISY(const ParametersMap & parameters = ParametersMap());
diff --git a/corelib/include/rtabmap/core/FlannIndex.h b/corelib/include/rtabmap/core/FlannIndex.h
index 6552a07109..3634dfcf99 100644
--- a/corelib/include/rtabmap/core/FlannIndex.h
+++ b/corelib/include/rtabmap/core/FlannIndex.h
@@ -28,13 +28,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef CORELIB_SRC_FLANNINDEX_H_
 #define CORELIB_SRC_FLANNINDEX_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 #include <list>
 #include <opencv2/opencv.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP FlannIndex
+class RTABMAP_CORE_EXPORT FlannIndex
 {
 public:
 	FlannIndex();
diff --git a/corelib/include/rtabmap/core/GainCompensator.h b/corelib/include/rtabmap/core/GainCompensator.h
index 27602344d0..ee4e3c6482 100644
--- a/corelib/include/rtabmap/core/GainCompensator.h
+++ b/corelib/include/rtabmap/core/GainCompensator.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef CORELIB_SRC_GAINCOMPENSATOR_H_
 #define CORELIB_SRC_GAINCOMPENSATOR_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -41,7 +41,7 @@ namespace rtabmap {
 /**
  * Works like cv::GainCompensator but with point clouds
  */
-class RTABMAP_EXP GainCompensator {
+class RTABMAP_CORE_EXPORT GainCompensator {
 public:
 	GainCompensator(double maxCorrespondenceDistance = 0.02, double minOverlap = 0.0, double alpha = 0.01, double beta = 10);
 	virtual ~GainCompensator();
diff --git a/corelib/include/rtabmap/core/GeodeticCoords.h b/corelib/include/rtabmap/core/GeodeticCoords.h
index 6234dd00a1..d2c67c59ec 100644
--- a/corelib/include/rtabmap/core/GeodeticCoords.h
+++ b/corelib/include/rtabmap/core/GeodeticCoords.h
@@ -43,13 +43,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef GEODETICCOORDS_H_
 #define GEODETICCOORDS_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP GeodeticCoords
+class RTABMAP_CORE_EXPORT GeodeticCoords
 {
 public:
 	GeodeticCoords();
diff --git a/corelib/include/rtabmap/core/Graph.h b/corelib/include/rtabmap/core/Graph.h
index f2d76acd4a..1d53fd0d44 100644
--- a/corelib/include/rtabmap/core/Graph.h
+++ b/corelib/include/rtabmap/core/Graph.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef GRAPH_H_
 #define GRAPH_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <map>
 #include <list>
@@ -46,7 +46,7 @@ namespace graph {
 // Graph utilities
 ////////////////////////////////////////////
 
-bool RTABMAP_EXP exportPoses(
+bool RTABMAP_CORE_EXPORT exportPoses(
 		const std::string & filePath,
 		int format, // 0=Raw (*.txt), 1=RGBD-SLAM motion capture (*.txt) (10=without change of coordinate frame, 11=10+ID), 2=KITTI (*.txt), 3=TORO (*.graph), 4=g2o (*.g2o)
 		const std::map<int, Transform> & poses,
@@ -54,14 +54,14 @@ bool RTABMAP_EXP exportPoses(
 		const std::map<int, double> & stamps = std::map<int, double>(),  // required for format 1
 		const ParametersMap & parameters = ParametersMap()); // optional for formats 3 and 4
 
-bool RTABMAP_EXP importPoses(
+bool RTABMAP_CORE_EXPORT importPoses(
 		const std::string & filePath,
 		int format, // 0=Raw, 1=RGBD-SLAM motion capture (10=without change of coordinate frame, 11=10+ID), 2=KITTI, 3=TORO, 4=g2o, 5=NewCollege(t,x,y), 6=Malaga Urban GPS, 7=St Lucia INS, 8=Karlsruhe, 9=EuRoC MAV
 		std::map<int, Transform> & poses,
 		std::multimap<int, Link> * constraints = 0, // optional for formats 3 and 4
 		std::map<int, double> * stamps = 0); // optional for format 1 and 9
 
-bool RTABMAP_EXP exportGPS(
+bool RTABMAP_CORE_EXPORT exportGPS(
 		const std::string & filePath,
 		const std::map<int, GPS> & gpsValues,
 		unsigned int rgba = 0xFFFFFFFF);
@@ -74,7 +74,7 @@ bool RTABMAP_EXP exportGPS(
  * @param t_err, Output translation error (%)
  * @param r_err, Output rotation error (deg/m)
  */
-void RTABMAP_EXP calcKittiSequenceErrors(
+void RTABMAP_CORE_EXPORT calcKittiSequenceErrors(
 		const std::vector<Transform> &poses_gt,
 		const std::vector<Transform> &poses_result,
 		float & t_err,
@@ -87,7 +87,7 @@ void RTABMAP_EXP calcKittiSequenceErrors(
  * @param t_err, Output translation error (m)
  * @param r_err, Output rotation error (deg)
  */
-void RTABMAP_EXP calcRelativeErrors (
+void RTABMAP_CORE_EXPORT calcRelativeErrors (
 		const std::vector<Transform> &poses_gt,
 		const std::vector<Transform> &poses_result,
 		float & t_err,
@@ -101,7 +101,7 @@ void RTABMAP_EXP calcRelativeErrors (
  * @param poses, Estimated poses
  * @return Gt to Map transform
  */
-Transform RTABMAP_EXP calcRMSE(
+Transform RTABMAP_CORE_EXPORT calcRMSE(
 		const std::map<int, Transform> &groundTruth,
 		const std::map<int, Transform> &poses,
 		float & translational_rmse,
@@ -117,7 +117,7 @@ Transform RTABMAP_EXP calcRMSE(
 		float & rotational_min,
 		float & rotational_max);
 
-void RTABMAP_EXP computeMaxGraphErrors(
+void RTABMAP_CORE_EXPORT computeMaxGraphErrors(
 		const std::map<int, Transform> & poses,
 		const std::multimap<int, Link> & links,
 		float & maxLinearErrorRatio,
@@ -128,53 +128,53 @@ void RTABMAP_EXP computeMaxGraphErrors(
 		const Link ** maxAngularErrorLink = 0,
 		bool for3DoF = false);
 
-std::vector<double> RTABMAP_EXP getMaxOdomInf(const std::multimap<int, Link> & links);
+std::vector<double> RTABMAP_CORE_EXPORT getMaxOdomInf(const std::multimap<int, Link> & links);
 
-std::multimap<int, Link>::iterator RTABMAP_EXP findLink(
+std::multimap<int, Link>::iterator RTABMAP_CORE_EXPORT findLink(
 		std::multimap<int, Link> & links,
 		int from,
 		int to,
 		bool checkBothWays = true,
 		Link::Type type = Link::kUndef);
-std::multimap<int, int>::iterator RTABMAP_EXP findLink(
+std::multimap<int, int>::iterator RTABMAP_CORE_EXPORT findLink(
 		std::multimap<int, int> & links,
 		int from,
 		int to,
 		bool checkBothWays = true);
-std::multimap<int, Link>::const_iterator RTABMAP_EXP findLink(
+std::multimap<int, Link>::const_iterator RTABMAP_CORE_EXPORT findLink(
 		const std::multimap<int, Link> & links,
 		int from,
 		int to,
 		bool checkBothWays = true,
 		Link::Type type = Link::kUndef);
-std::multimap<int, int>::const_iterator RTABMAP_EXP findLink(
+std::multimap<int, int>::const_iterator RTABMAP_CORE_EXPORT findLink(
 		const std::multimap<int, int> & links,
 		int from,
 		int to,
 		bool checkBothWays = true);
-std::list<Link> RTABMAP_EXP findLinks(
+std::list<Link> RTABMAP_CORE_EXPORT findLinks(
 		const std::multimap<int, Link> & links,
 		int from);
 
-std::multimap<int, Link> RTABMAP_EXP filterDuplicateLinks(
+std::multimap<int, Link> RTABMAP_CORE_EXPORT filterDuplicateLinks(
 		const std::multimap<int, Link> & links);
 /**
  * Return links not of type "filteredType". If inverted=true, return links of type "filteredType".
  */
-std::multimap<int, Link> RTABMAP_EXP filterLinks(
+std::multimap<int, Link> RTABMAP_CORE_EXPORT filterLinks(
 		const std::multimap<int, Link> & links,
 		Link::Type filteredType,
 		bool inverted = false);
 /**
  * Return links not of type "filteredType". If inverted=true, return links of type "filteredType".
  */
-std::map<int, Link> RTABMAP_EXP filterLinks(
+std::map<int, Link> RTABMAP_CORE_EXPORT filterLinks(
 		const std::map<int, Link> & links,
 		Link::Type filteredType,
 		bool inverted = false);
 
 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
-std::map<int, Transform> RTABMAP_EXP frustumPosesFiltering(
+std::map<int, Transform> RTABMAP_CORE_EXPORT frustumPosesFiltering(
 		const std::map<int, Transform> & poses,
 		const Transform & cameraPose,
 		float horizontalFOV = 45.0f, // in degrees, xfov = atan((image_width/2)/fx)*2
@@ -191,7 +191,7 @@ std::map<int, Transform> RTABMAP_EXP frustumPosesFiltering(
  * @param keepLatest keep the latest node if true, otherwise the oldest node is kept
  * @return A map containing only most recent or older poses in the the defined radius
  */
-std::map<int, Transform> RTABMAP_EXP radiusPosesFiltering(
+std::map<int, Transform> RTABMAP_CORE_EXPORT radiusPosesFiltering(
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle,
@@ -204,7 +204,7 @@ std::map<int, Transform> RTABMAP_EXP radiusPosesFiltering(
  * @param angle Maximum angle (rad, [0,PI]) of accepted neighbor nodes in the radius (0 means ignore angle)
  * @return A map between each pose id and its neighbors found in the radius
  */
-std::multimap<int, int> RTABMAP_EXP radiusPosesClustering(
+std::multimap<int, int> RTABMAP_CORE_EXPORT radiusPosesClustering(
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle);
@@ -224,7 +224,7 @@ void reduceGraph(
  * @param updateNewCosts Keep up-to-date costs while traversing the graph.
  * @return the path ids from id "from" to id "to" including initial and final nodes.
  */
-std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
+std::list<std::pair<int, Transform> > RTABMAP_CORE_EXPORT computePath(
 			const std::map<int, rtabmap::Transform> & poses,
 			const std::multimap<int, int> & links,
 			int from,
@@ -241,7 +241,7 @@ std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
  * @param useSameCostForAllLinks Ignore distance between nodes
  * @return the path ids from id "from" to id "to" including initial and final nodes.
  */
-std::list<int> RTABMAP_EXP computePath(
+std::list<int> RTABMAP_CORE_EXPORT computePath(
 			const std::multimap<int, Link> & links,
 			int from,
 			int to,
@@ -257,7 +257,7 @@ std::list<int> RTABMAP_EXP computePath(
  * @param updateNewCosts Keep up-to-date costs while traversing the graph.
  * @return the path ids from id "fromId" to id "toId" including initial and final nodes (Identity pose for the first node).
  */
-std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
+std::list<std::pair<int, Transform> > RTABMAP_CORE_EXPORT computePath(
 		int fromId,
 		int toId,
 		const Memory * memory,
@@ -273,7 +273,7 @@ std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
  * @param distance squared distance of the nearest node found (optional)
  * @return the node id.
  */
-int RTABMAP_EXP findNearestNode(
+int RTABMAP_CORE_EXPORT findNearestNode(
 		const std::map<int, rtabmap::Transform> & poses,
 		const rtabmap::Transform & targetPose,
 		float * distance = 0);
@@ -286,54 +286,56 @@ int RTABMAP_EXP findNearestNode(
  * @param k max nearest neighbors (0=all inside the radius)
  * @return the nodes with squared distance to query node.
  */
-std::map<int, float> RTABMAP_EXP findNearestNodes(
+std::map<int, float> RTABMAP_CORE_EXPORT findNearestNodes(
 		int nodeId,
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle = 0.0f,
 		int k=0);
-std::map<int, float> RTABMAP_EXP findNearestNodes(
+std::map<int, float> RTABMAP_CORE_EXPORT findNearestNodes(
 		const Transform & targetPose,
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle = 0.0f,
 		int k=0);
-std::map<int, Transform> RTABMAP_EXP findNearestPoses(
+std::map<int, Transform> RTABMAP_CORE_EXPORT findNearestPoses(
 		int nodeId,
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle = 0.0f,
 		int k=0);
-std::map<int, Transform> RTABMAP_EXP findNearestPoses(
+std::map<int, Transform> RTABMAP_CORE_EXPORT findNearestPoses(
 		const Transform & targetPose,
 		const std::map<int, Transform> & poses,
 		float radius,
 		float angle = 0.0f,
 		int k=0);
 
-// typedef hack to avoid error with RTABMAP_DEPRECATED
-typedef std::map<int, float> _mapIntFloat;
-typedef std::map<int, Transform> _mapIntTransform;
-RTABMAP_DEPRECATED(_mapIntFloat RTABMAP_EXP findNearestNodes(const std::map<int, rtabmap::Transform> & nodes, const rtabmap::Transform & targetPose, int k), "Use new findNearestNodes() interface with radius=0, angle=0.");
-RTABMAP_DEPRECATED(_mapIntFloat RTABMAP_EXP getNodesInRadius(int nodeId, const std::map<int, Transform> & nodes, float radius), "Renamed to findNearestNodes()");
-RTABMAP_DEPRECATED(_mapIntFloat RTABMAP_EXP getNodesInRadius(const Transform & targetPose, const std::map<int, Transform> & nodes, float radius), "Renamed to findNearestNodes()");
-RTABMAP_DEPRECATED(_mapIntTransform RTABMAP_EXP getPosesInRadius(int nodeId, const std::map<int, Transform> & nodes, float radius, float angle = 0.0f), "Renamed to findNearestNodes()");
-RTABMAP_DEPRECATED(_mapIntTransform RTABMAP_EXP getPosesInRadius(const Transform & targetPose, const std::map<int, Transform> & nodes, float radius, float angle = 0.0f), "Renamed to findNearestNodes()");
-
-float RTABMAP_EXP computePathLength(
+// Use new findNearestNodes() interface with radius=0, angle=0.
+RTABMAP_DEPRECATED std::map<int, float> RTABMAP_CORE_EXPORT findNearestNodes(const std::map<int, rtabmap::Transform> & nodes, const rtabmap::Transform & targetPose, int k);
+// Renamed to findNearestNodes()
+RTABMAP_DEPRECATED std::map<int, float> RTABMAP_CORE_EXPORT getNodesInRadius(int nodeId, const std::map<int, Transform> & nodes, float radius);
+// Renamed to findNearestNodes()
+RTABMAP_DEPRECATED std::map<int, float> RTABMAP_CORE_EXPORT getNodesInRadius(const Transform & targetPose, const std::map<int, Transform> & nodes, float radius);
+// Renamed to findNearestNodes()
+RTABMAP_DEPRECATED std::map<int, Transform> RTABMAP_CORE_EXPORT getPosesInRadius(int nodeId, const std::map<int, Transform> & nodes, float radius, float angle = 0.0f);
+// Renamed to findNearestNodes()
+RTABMAP_DEPRECATED std::map<int, Transform> RTABMAP_CORE_EXPORT getPosesInRadius(const Transform & targetPose, const std::map<int, Transform> & nodes, float radius, float angle = 0.0f);
+
+float RTABMAP_CORE_EXPORT computePathLength(
 		const std::vector<std::pair<int, Transform> > & path,
 		unsigned int fromIndex = 0,
 		unsigned int toIndex = 0);
 
 // assuming they are all linked in map order
-float RTABMAP_EXP computePathLength(
+float RTABMAP_CORE_EXPORT computePathLength(
 		const std::map<int, Transform> & path);
 
-std::list<std::map<int, Transform> > RTABMAP_EXP getPaths(
+std::list<std::map<int, Transform> > RTABMAP_CORE_EXPORT getPaths(
 		std::map<int, Transform> poses,
 		const std::multimap<int, Link> & links);
 
-void RTABMAP_EXP computeMinMax(const std::map<int, Transform> & poses,
+void RTABMAP_CORE_EXPORT computeMinMax(const std::map<int, Transform> & poses,
 		cv::Vec3f & min,
 		cv::Vec3f & max);
 
diff --git a/corelib/include/rtabmap/core/IMUThread.h b/corelib/include/rtabmap/core/IMUThread.h
index 74d1872743..c2d912fb55 100644
--- a/corelib/include/rtabmap/core/IMUThread.h
+++ b/corelib/include/rtabmap/core/IMUThread.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Transform.h>
 #include <rtabmap/utilite/UThread.h>
@@ -43,7 +43,7 @@ namespace rtabmap
  * Class IMUThread
  *
  */
-class RTABMAP_EXP IMUThread :
+class RTABMAP_CORE_EXPORT IMUThread :
 	public UThread,
 	public UEventsSender
 {
diff --git a/corelib/include/rtabmap/core/Landmark.h b/corelib/include/rtabmap/core/Landmark.h
index d28be62ca4..8762a409a0 100644
--- a/corelib/include/rtabmap/core/Landmark.h
+++ b/corelib/include/rtabmap/core/Landmark.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef CORELIB_INCLUDE_RTABMAP_CORE_LANDMARK_H_
 #define CORELIB_INCLUDE_RTABMAP_CORE_LANDMARK_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 #include <rtabmap/core/Transform.h>
 #include <rtabmap/utilite/ULogger.h>
 #include <rtabmap/utilite/UMath.h>
@@ -59,7 +59,8 @@ class Landmark
         UASSERT_MSG(uIsFinite(covariance_.at<double>(4,4)) && covariance_.at<double>(4,4)>0, uFormat("Angular covariance should not be null! Value=%f (set to 9999 if unknown).", covariance_.at<double>(4,4)).c_str());
         UASSERT_MSG(uIsFinite(covariance_.at<double>(5,5)) && covariance_.at<double>(5,5)>0, uFormat("Angular covariance should not be null! Value=%f (set to 9999 if unknown).", covariance_.at<double>(5,5)).c_str());
     }
-    RTABMAP_DEPRECATED(Landmark(const int & id, const Transform & pose, const cv::Mat & covariance), "Use constructor with size=0 instead.");
+    // Use constructor with size=0 instead.
+    RTABMAP_DEPRECATED Landmark(const int & id, const Transform & pose, const cv::Mat & covariance);
 
 	virtual ~Landmark() {}
 
diff --git a/corelib/include/rtabmap/core/LaserScan.h b/corelib/include/rtabmap/core/LaserScan.h
index 9f661717de..33999a7b59 100644
--- a/corelib/include/rtabmap/core/LaserScan.h
+++ b/corelib/include/rtabmap/core/LaserScan.h
@@ -28,13 +28,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_
 #define CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Transform.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP LaserScan
+class RTABMAP_CORE_EXPORT LaserScan
 {
 public:
 	enum Format{kUnknown=0,
@@ -75,24 +75,26 @@ class RTABMAP_EXP LaserScan
 			int maxPoints,
 			float maxRange,
 			const Transform & localTransform = Transform::getIdentity());
-	RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
+	// Use version without \"format\" argument.
+	RTABMAP_DEPRECATED LaserScan(const LaserScan & data,
 			int maxPoints,
 			float maxRange,
 			Format format,
-			const Transform & localTransform = Transform::getIdentity()), "Use version without \"format\" argument.");
+			const Transform & localTransform = Transform::getIdentity());
 	LaserScan(const cv::Mat & data,
 			int maxPoints,
 			float maxRange,
 			Format format,
 			const Transform & localTransform = Transform::getIdentity());
-	RTABMAP_DEPRECATED(LaserScan(const LaserScan & data,
+	// Use version without \"format\" argument.
+	RTABMAP_DEPRECATED LaserScan(const LaserScan & data,
 			Format format,
 			float minRange,
 			float maxRange,
 			float angleMin,
 			float angleMax,
 			float angleIncrement,
-			const Transform & localTransform = Transform::getIdentity()), "Use version without \"format\" argument.");
+			const Transform & localTransform = Transform::getIdentity());
 	LaserScan(const LaserScan & data,
 			float minRange,
 			float maxRange,
diff --git a/corelib/include/rtabmap/core/Link.h b/corelib/include/rtabmap/core/Link.h
index 47c436b274..d876854a0c 100644
--- a/corelib/include/rtabmap/core/Link.h
+++ b/corelib/include/rtabmap/core/Link.h
@@ -28,14 +28,14 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef LINK_H_
 #define LINK_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Transform.h>
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP Link
+class RTABMAP_CORE_EXPORT Link
 {
 public:
 	enum Type {
diff --git a/corelib/include/rtabmap/core/MarkerDetector.h b/corelib/include/rtabmap/core/MarkerDetector.h
index ed8dc3837e..d628ca022d 100644
--- a/corelib/include/rtabmap/core/MarkerDetector.h
+++ b/corelib/include/rtabmap/core/MarkerDetector.h
@@ -56,19 +56,20 @@ class MarkerInfo {
     Transform pose_;
 };
 
-class RTABMAP_EXP MarkerDetector {
+class RTABMAP_CORE_EXPORT MarkerDetector {
     
 public:
 	MarkerDetector(const ParametersMap & parameters = ParametersMap());
 	virtual ~MarkerDetector();
 	void parseParameters(const ParametersMap & parameters);
 
-    RTABMAP_DEPRECATED(
+	// Use the other detect(), in which the returned map contains the length of each marker detected.
+    RTABMAP_DEPRECATED
     MapIdPose detect(const cv::Mat & image,
 			const CameraModel & model,
 			const cv::Mat & depth = cv::Mat(),
 			float * estimatedMarkerLength = 0,
-			cv::Mat * imageWithDetections = 0), "Use the other detect(), in which the returned map contains the length of each marker detected.");
+			cv::Mat * imageWithDetections = 0);
 
     std::map<int, MarkerInfo> detect(const cv::Mat & image,
 		    const std::vector<CameraModel> & models,
diff --git a/corelib/include/rtabmap/core/Memory.h b/corelib/include/rtabmap/core/Memory.h
index a9c6e743df..a0f86e89a3 100644
--- a/corelib/include/rtabmap/core/Memory.h
+++ b/corelib/include/rtabmap/core/Memory.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef MEMORY_H_
 #define MEMORY_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UEventsHandler.h"
 #include "rtabmap/core/Parameters.h"
@@ -60,7 +60,7 @@ class Stereo;
 class OccupancyGrid;
 class MarkerDetector;
 
-class RTABMAP_EXP Memory
+class RTABMAP_CORE_EXPORT Memory
 {
 public:
 	static const int kIdStart;
diff --git a/corelib/include/rtabmap/core/OccupancyGrid.h b/corelib/include/rtabmap/core/OccupancyGrid.h
index 8e247c33f2..04617c4bfe 100644
--- a/corelib/include/rtabmap/core/OccupancyGrid.h
+++ b/corelib/include/rtabmap/core/OccupancyGrid.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef CORELIB_SRC_OCCUPANCYGRID_H_
 #define CORELIB_SRC_OCCUPANCYGRID_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <pcl/point_cloud.h>
 #include <pcl/pcl_base.h>
@@ -37,7 +37,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP OccupancyGrid
+class RTABMAP_CORE_EXPORT OccupancyGrid
 {
 public:
 	inline static float logodds(double probability)
diff --git a/corelib/include/rtabmap/core/OctoMap.h b/corelib/include/rtabmap/core/OctoMap.h
index b6252df857..770177175f 100644
--- a/corelib/include/rtabmap/core/OctoMap.h
+++ b/corelib/include/rtabmap/core/OctoMap.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef SRC_OCTOMAP_H_
 #define SRC_OCTOMAP_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <octomap/ColorOcTree.h>
 #include <octomap/OcTreeKey.h>
@@ -171,7 +171,7 @@ class RtabmapColorOcTree : public octomap::OccupancyOcTreeBase <RtabmapColorOcTr
 
   };
 
-class RTABMAP_EXP OctoMap {
+class RTABMAP_CORE_EXPORT OctoMap {
 public:
 	OctoMap(const ParametersMap & parameters = ParametersMap());
 
diff --git a/corelib/include/rtabmap/core/Odometry.h b/corelib/include/rtabmap/core/Odometry.h
index e465802898..258be65836 100644
--- a/corelib/include/rtabmap/core/Odometry.h
+++ b/corelib/include/rtabmap/core/Odometry.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef ODOMETRY_H_
 #define ODOMETRY_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <rtabmap/core/Transform.h>
 #include <rtabmap/core/SensorData.h>
@@ -39,7 +39,7 @@ namespace rtabmap {
 class OdometryInfo;
 class ParticleFilter;
 
-class RTABMAP_EXP Odometry
+class RTABMAP_CORE_EXPORT Odometry
 {
 public:
 	enum Type {
@@ -75,7 +75,8 @@ class RTABMAP_EXP Odometry
 	//getters
 	const Transform & getPose() const {return _pose;}
 	bool isInfoDataFilled() const {return _fillInfoData;}
-	RTABMAP_DEPRECATED(const Transform & previousVelocityTransform() const, "Use getVelocityGuess() instead.");
+	// Use getVelocityGuess() instead.
+	RTABMAP_DEPRECATED const Transform & previousVelocityTransform() const;
 	const Transform & getVelocityGuess() const {return velocityGuess_;}
 	double previousStamp() const {return previousStamp_;}
 	unsigned int framesProcessed() const {return framesProcessed_;}
diff --git a/corelib/include/rtabmap/core/OdometryThread.h b/corelib/include/rtabmap/core/OdometryThread.h
index 01424134a7..159ee55f98 100644
--- a/corelib/include/rtabmap/core/OdometryThread.h
+++ b/corelib/include/rtabmap/core/OdometryThread.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef ODOMETRYTHREAD_H_
 #define ODOMETRYTHREAD_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 #include <rtabmap/core/SensorData.h>
 #include <rtabmap/utilite/UThread.h>
 #include <rtabmap/utilite/UEventsHandler.h>
@@ -38,7 +38,7 @@ namespace rtabmap {
 
 class Odometry;
 
-class RTABMAP_EXP OdometryThread : public UThread, public UEventsHandler {
+class RTABMAP_CORE_EXPORT OdometryThread : public UThread, public UEventsHandler {
 public:
 	// take ownership of Odometry
 	OdometryThread(Odometry * odometry, unsigned int dataBufferMaxSize = 1);
diff --git a/corelib/include/rtabmap/core/Optimizer.h b/corelib/include/rtabmap/core/Optimizer.h
index 32729d1468..aec3734ce5 100644
--- a/corelib/include/rtabmap/core/Optimizer.h
+++ b/corelib/include/rtabmap/core/Optimizer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZER_H_
 #define OPTIMIZER_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <map>
 #include <list>
@@ -58,7 +58,7 @@ class FeatureBA
 ////////////////////////////////////////////
 // Graph optimizers
 ////////////////////////////////////////////
-class RTABMAP_EXP Optimizer
+class RTABMAP_CORE_EXPORT Optimizer
 {
 public:
 	enum Type {
diff --git a/corelib/include/rtabmap/core/Parameters.h b/corelib/include/rtabmap/core/Parameters.h
index 58f9d77185..95c201a14f 100644
--- a/corelib/include/rtabmap/core/Parameters.h
+++ b/corelib/include/rtabmap/core/Parameters.h
@@ -29,7 +29,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #define PARAMETERS_H_
 
 // default parameters
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 #include "rtabmap/core/Version.h" // DLL export/import defines
 #include <rtabmap/utilite/UConversion.h>
 #include <opencv2/core/version.hpp>
@@ -167,7 +167,7 @@ typedef std::pair<std::string, std::string> ParametersPair;
  * @see getDefaultParameters()
  * TODO Add a detailed example with simple classes
  */
-class RTABMAP_EXP Parameters
+class RTABMAP_CORE_EXPORT Parameters
 {
     // Rtabmap parameters
     RTABMAP_PARAM(Rtabmap, PublishStats,                 bool, true,  "Publishing statistics.");
diff --git a/corelib/include/rtabmap/core/Recovery.h b/corelib/include/rtabmap/core/Recovery.h
index 6300332df3..2506167bdc 100644
--- a/corelib/include/rtabmap/core/Recovery.h
+++ b/corelib/include/rtabmap/core/Recovery.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RECOVERY_H_
 #define RECOVERY_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <string>
 
@@ -44,7 +44,7 @@ class ProgressState;
  * @param errorMsg error message if the function returns false
  * @param progressState A ProgressState object used to get status of the recovery process
  */
-bool RTABMAP_EXP databaseRecovery(
+bool RTABMAP_CORE_EXPORT databaseRecovery(
 		const std::string & corruptedDatabase,
 		bool keepCorruptedDatabase = true,
 		std::string * errorMsg = 0,
diff --git a/corelib/include/rtabmap/core/Registration.h b/corelib/include/rtabmap/core/Registration.h
index 7de6b10b30..6516b5ae32 100644
--- a/corelib/include/rtabmap/core/Registration.h
+++ b/corelib/include/rtabmap/core/Registration.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_REGISTRATION_H_
 #define RTABMAP_REGISTRATION_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <rtabmap/core/Signature.h>
@@ -36,7 +36,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP Registration
+class RTABMAP_CORE_EXPORT Registration
 {
 public:
 	enum Type {
diff --git a/corelib/include/rtabmap/core/RegistrationIcp.h b/corelib/include/rtabmap/core/RegistrationIcp.h
index ef13432d91..e5d512f381 100644
--- a/corelib/include/rtabmap/core/RegistrationIcp.h
+++ b/corelib/include/rtabmap/core/RegistrationIcp.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef REGISTRATIONICP_H_
 #define REGISTRATIONICP_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Registration.h>
 #include <rtabmap/core/Signature.h>
@@ -36,7 +36,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap {
 
 // Geometrical registration
-class RTABMAP_EXP RegistrationIcp : public Registration
+class RTABMAP_CORE_EXPORT RegistrationIcp : public Registration
 {
 public:
 	// take ownership of child
diff --git a/corelib/include/rtabmap/core/RegistrationVis.h b/corelib/include/rtabmap/core/RegistrationVis.h
index 02d7ac7fc1..51e3a19acb 100644
--- a/corelib/include/rtabmap/core/RegistrationVis.h
+++ b/corelib/include/rtabmap/core/RegistrationVis.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef REGISTRATIONVIS_H_
 #define REGISTRATIONVIS_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Registration.h>
 #include <rtabmap/core/Signature.h>
@@ -42,7 +42,7 @@ class PyMatcher;
 #endif
 
 // Visual registration
-class RTABMAP_EXP RegistrationVis : public Registration
+class RTABMAP_CORE_EXPORT RegistrationVis : public Registration
 {
 public:
 	// take ownership of child
diff --git a/corelib/include/rtabmap/core/Rtabmap.h b/corelib/include/rtabmap/core/Rtabmap.h
index c22088dfbe..1120b728c4 100644
--- a/corelib/include/rtabmap/core/Rtabmap.h
+++ b/corelib/include/rtabmap/core/Rtabmap.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_H_
 #define RTABMAP_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include "rtabmap/core/Parameters.h"
 #include "rtabmap/core/SensorData.h"
@@ -51,7 +51,7 @@ class Signature;
 class Optimizer;
 class PythonInterface;
 
-class RTABMAP_EXP Rtabmap
+class RTABMAP_CORE_EXPORT Rtabmap
 {
 public:
 	enum VhStrategy {kVhNone, kVhEpipolar, kVhUndef};
@@ -180,12 +180,13 @@ class RTABMAP_EXP Rtabmap
 	void deleteLastLocation();
 	void setOptimizedPoses(const std::map<int, Transform> & poses, const std::multimap<int, Link> & constraints);
 	Signature getSignatureCopy(int id, bool images, bool scan, bool userData, bool occupancyGrid, bool withWords, bool withGlobalDescriptors) const;
-	RTABMAP_DEPRECATED(
+	// Use getGraph() instead with withImages=true, withScan=true, withUserData=true and withGrid=true.
+	RTABMAP_DEPRECATED
 		void get3DMap(std::map<int, Signature> & signatures,
 				std::map<int, Transform> & poses,
 				std::multimap<int, Link> & constraints,
 				bool optimized,
-				bool global) const, "Use getGraph() instead with withImages=true, withScan=true, withUserData=true and withGrid=true.");
+				bool global) const;
 	void getGraph(std::map<int, Transform> & poses,
 			std::multimap<int, Link> & constraints,
 			bool optimized,
diff --git a/corelib/include/rtabmap/core/RtabmapExp.h b/corelib/include/rtabmap/core/RtabmapExp.h
deleted file mode 100644
index 440c8021fb..0000000000
--- a/corelib/include/rtabmap/core/RtabmapExp.h
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
-Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
-All rights reserved.
-
-Redistribution and use in source and binary forms, with or without
-modification, are permitted provided that the following conditions are met:
-    * Redistributions of source code must retain the above copyright
-      notice, this list of conditions and the following disclaimer.
-    * Redistributions in binary form must reproduce the above copyright
-      notice, this list of conditions and the following disclaimer in the
-      documentation and/or other materials provided with the distribution.
-    * Neither the name of the Universite de Sherbrooke nor the
-      names of its contributors may be used to endorse or promote products
-      derived from this software without specific prior written permission.
-
-THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
-ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
-WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
-DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
-DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
-(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
-ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
-(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
-SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-*/
-
-#ifndef RTABMAPEXP_H
-#define RTABMAPEXP_H
-
-#if defined(_WIN32)
-  #if defined(rtabmap_core_EXPORTS)
-    #define RTABMAP_EXP   __declspec( dllexport )
-  #else
-    #define RTABMAP_EXP   __declspec( dllimport )
-  #endif
-#else
-  #define RTABMAP_EXP
-#endif
-
-#ifdef __GNUC__
-#define RTABMAP_DEPRECATED(func, msg) func __attribute__ ((deprecated(msg)))
-#elif defined(_MSC_VER)
-#define RTABMAP_DEPRECATED(func, msg) __declspec(deprecated(msg)) func
-#else
-#pragma message("WARNING: You need to implement DEPRECATED for this compiler")
-#define RTABMAP_DEPRECATED(func, msg) func
-#endif
-
-#endif // RTABMAPEXP_H
diff --git a/corelib/include/rtabmap/core/RtabmapThread.h b/corelib/include/rtabmap/core/RtabmapThread.h
index 02b741aa5b..96fa214caf 100644
--- a/corelib/include/rtabmap/core/RtabmapThread.h
+++ b/corelib/include/rtabmap/core/RtabmapThread.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAPTHREAD_H_
 #define RTABMAPTHREAD_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UThreadNode.h>
 #include <rtabmap/utilite/UEventsHandler.h>
@@ -48,7 +48,7 @@ namespace rtabmap {
 
 class Rtabmap;
 
-class RTABMAP_EXP RtabmapThread :
+class RTABMAP_CORE_EXPORT RtabmapThread :
 	public UThreadNode,
 	public UEventsHandler
 {
diff --git a/corelib/include/rtabmap/core/SensorData.h b/corelib/include/rtabmap/core/SensorData.h
index 0cbe953194..57d7452ddf 100644
--- a/corelib/include/rtabmap/core/SensorData.h
+++ b/corelib/include/rtabmap/core/SensorData.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef SENSORDATA_H_
 #define SENSORDATA_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 #include <rtabmap/core/Transform.h>
 #include <rtabmap/core/CameraModel.h>
 #include <rtabmap/core/StereoCameraModel.h>
@@ -48,7 +48,7 @@ namespace rtabmap
 /**
  * An id is automatically generated if id=0.
  */
-class RTABMAP_EXP SensorData
+class RTABMAP_CORE_EXPORT SensorData
 {
 public:
 	// empty constructor
@@ -210,10 +210,14 @@ class RTABMAP_EXP SensorData
 	cv::Mat depthRaw() const {return _depthOrRightRaw.type()!=CV_8UC1?_depthOrRightRaw:cv::Mat();}
 	cv::Mat rightRaw() const {return _depthOrRightRaw.type()==CV_8UC1?_depthOrRightRaw:cv::Mat();}
 
-	RTABMAP_DEPRECATED(void setImageRaw(const cv::Mat & image), "Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.");
-	RTABMAP_DEPRECATED(void setDepthOrRightRaw(const cv::Mat & image), "Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.");
-	RTABMAP_DEPRECATED(void setLaserScanRaw(const LaserScan & scan), "Use setLaserScan() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.");
-	RTABMAP_DEPRECATED(void setUserDataRaw(const cv::Mat & data), "Use setUserData() or removeRawData() instead.");
+	// Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.
+	RTABMAP_DEPRECATED void setImageRaw(const cv::Mat & image);
+	// Use setRGBDImage() or setStereoImage() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.
+	RTABMAP_DEPRECATED void setDepthOrRightRaw(const cv::Mat & image);
+	// Use setLaserScan() with clearNotUpdated=false or removeRawData() instead. To be backward compatible, this function doesn't clear compressed data.
+	RTABMAP_DEPRECATED void setLaserScanRaw(const LaserScan & scan);
+	// Use setUserData() or removeRawData() instead.
+	RTABMAP_DEPRECATED void setUserDataRaw(const cv::Mat & data);
 
 	void uncompressData();
 	void uncompressData(
diff --git a/corelib/include/rtabmap/core/Signature.h b/corelib/include/rtabmap/core/Signature.h
index fdb850b4fa..1e393cb235 100644
--- a/corelib/include/rtabmap/core/Signature.h
+++ b/corelib/include/rtabmap/core/Signature.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <pcl/point_types.h>
 #include <opencv2/core/core.hpp>
@@ -45,7 +45,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP Signature
+class RTABMAP_CORE_EXPORT Signature
 {
 
 public:
diff --git a/corelib/include/rtabmap/core/Statistics.h b/corelib/include/rtabmap/core/Statistics.h
index 07fda8055a..743b46bf04 100644
--- a/corelib/include/rtabmap/core/Statistics.h
+++ b/corelib/include/rtabmap/core/Statistics.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef STATISTICS_H_
 #define STATISTICS_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/core/core.hpp>
 #include <opencv2/features2d/features2d.hpp>
@@ -50,7 +50,7 @@ namespace rtabmap {
 		}; \
 		Dummy##PREFIX##NAME dummy##PREFIX##NAME
 
-class RTABMAP_EXP Statistics
+class RTABMAP_CORE_EXPORT Statistics
 {
 	RTABMAP_STATS(Loop, Id,); // Combined loop or proximity detection
 	RTABMAP_STATS(Loop, RejectedHypothesis,);
@@ -236,7 +236,8 @@ class RTABMAP_EXP Statistics
 	void setProximityDetectionMapId(int id) {_proximiyDetectionMapId = id;}
 	void setStamp(double stamp) {_stamp = stamp;}
 
-	RTABMAP_DEPRECATED(void setLastSignatureData(const Signature & data), "Use addSignatureData() instead.");
+	// Use addSignatureData() instead.
+	RTABMAP_DEPRECATED void setLastSignatureData(const Signature & data);
 	void addSignatureData(const Signature & data) {_signaturesData.insert(std::make_pair(data.id(), data));}
 	void setSignaturesData(const std::map<int, Signature> & data) {_signaturesData = data;}
 
diff --git a/corelib/include/rtabmap/core/Stereo.h b/corelib/include/rtabmap/core/Stereo.h
index e0cfd94221..9c06e2a1dc 100644
--- a/corelib/include/rtabmap/core/Stereo.h
+++ b/corelib/include/rtabmap/core/Stereo.h
@@ -28,14 +28,14 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef STEREO_H_
 #define STEREO_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP Stereo {
+class RTABMAP_CORE_EXPORT Stereo {
 public:
 	static Stereo * create(const ParametersMap & parameters = ParametersMap());
 
@@ -67,7 +67,7 @@ class RTABMAP_EXP Stereo {
 	bool winSSD_;
 };
 
-class RTABMAP_EXP StereoOpticalFlow : public Stereo {
+class RTABMAP_CORE_EXPORT StereoOpticalFlow : public Stereo {
 public:
 	StereoOpticalFlow(const ParametersMap & parameters = ParametersMap());
 	virtual ~StereoOpticalFlow() {}
diff --git a/corelib/include/rtabmap/core/StereoCameraModel.h b/corelib/include/rtabmap/core/StereoCameraModel.h
index 4fbbd7228f..07cf2e77ad 100644
--- a/corelib/include/rtabmap/core/StereoCameraModel.h
+++ b/corelib/include/rtabmap/core/StereoCameraModel.h
@@ -32,7 +32,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP StereoCameraModel
+class RTABMAP_CORE_EXPORT StereoCameraModel
 {
 public:
 	StereoCameraModel() : leftSuffix_("left"), rightSuffix_("right") {}
@@ -140,7 +140,7 @@ class RTABMAP_EXP StereoCameraModel
 	cv::Mat F_;
 };
 
-RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const StereoCameraModel& model);
+RTABMAP_CORE_EXPORT std::ostream& operator<<(std::ostream& os, const StereoCameraModel& model);
 
 } // rtabmap
 
diff --git a/corelib/include/rtabmap/core/StereoDense.h b/corelib/include/rtabmap/core/StereoDense.h
index 2f77b124b6..fe37e52569 100644
--- a/corelib/include/rtabmap/core/StereoDense.h
+++ b/corelib/include/rtabmap/core/StereoDense.h
@@ -28,14 +28,14 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef STEREODENSE_H_
 #define STEREODENSE_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP StereoDense {
+class RTABMAP_CORE_EXPORT StereoDense {
 public:
 	enum Type {
 		kTypeBM = 0,
diff --git a/corelib/include/rtabmap/core/Transform.h b/corelib/include/rtabmap/core/Transform.h
index 542229a445..f973c6398d 100644
--- a/corelib/include/rtabmap/core/Transform.h
+++ b/corelib/include/rtabmap/core/Transform.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef TRANSFORM_H_
 #define TRANSFORM_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 #include <vector>
 #include <string>
 #include <map>
@@ -38,7 +38,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP Transform
+class RTABMAP_CORE_EXPORT Transform
 {
 public:
 
@@ -168,16 +168,17 @@ class RTABMAP_EXP Transform
 	static Transform getTransform(
 				const std::map<double, Transform> & tfBuffer,
 				const double & stamp);
-	RTABMAP_DEPRECATED(static Transform getClosestTransform(
+	// Use Transform::getTransform() instead to get always accurate transforms.
+	RTABMAP_DEPRECATED static Transform getClosestTransform(
 				const std::map<double, Transform> & tfBuffer,
 				const double & stamp,
-				double * stampDiff), "Use Transform::getTransform() instead to get always accurate transforms.");
+				double * stampDiff);
 
 private:
 	cv::Mat data_;
 };
 
-RTABMAP_EXP std::ostream& operator<<(std::ostream& os, const Transform& s);
+RTABMAP_CORE_EXPORT std::ostream& operator<<(std::ostream& os, const Transform& s);
 
 class TransformStamped
 {
diff --git a/corelib/include/rtabmap/core/VWDictionary.h b/corelib/include/rtabmap/core/VWDictionary.h
index 5a48006878..fbfa7ba542 100644
--- a/corelib/include/rtabmap/core/VWDictionary.h
+++ b/corelib/include/rtabmap/core/VWDictionary.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/core/core.hpp>
@@ -43,7 +43,7 @@ class DBDriver;
 class VisualWord;
 class FlannIndex;
 
-class RTABMAP_EXP VWDictionary
+class RTABMAP_CORE_EXPORT VWDictionary
 {
 public:
 	enum NNStrategy{
diff --git a/corelib/include/rtabmap/core/VisualWord.h b/corelib/include/rtabmap/core/VisualWord.h
index 35eba36b0c..795c173783 100644
--- a/corelib/include/rtabmap/core/VisualWord.h
+++ b/corelib/include/rtabmap/core/VisualWord.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <opencv2/core/core.hpp>
 #include <map>
@@ -35,7 +35,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP VisualWord
+class RTABMAP_CORE_EXPORT VisualWord
 {
 public:
 	VisualWord(int id, const cv::Mat & descriptor, int signatureId = 0);
diff --git a/corelib/include/rtabmap/core/camera/CameraDepthAI.h b/corelib/include/rtabmap/core/camera/CameraDepthAI.h
index 9c426fb673..85b59fb2f9 100644
--- a/corelib/include/rtabmap/core/camera/CameraDepthAI.h
+++ b/corelib/include/rtabmap/core/camera/CameraDepthAI.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -43,7 +41,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraDepthAI :
+class RTABMAP_CORE_EXPORT CameraDepthAI :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraFreenect.h b/corelib/include/rtabmap/core/camera/CameraFreenect.h
index 1d3e027d81..3373e04e45 100644
--- a/corelib/include/rtabmap/core/camera/CameraFreenect.h
+++ b/corelib/include/rtabmap/core/camera/CameraFreenect.h
@@ -27,7 +27,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
@@ -41,7 +41,7 @@ namespace rtabmap
 
 class FreenectDevice;
 
-class RTABMAP_EXP CameraFreenect :
+class RTABMAP_CORE_EXPORT CameraFreenect :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraFreenect2.h b/corelib/include/rtabmap/core/camera/CameraFreenect2.h
index 204d83f0da..70210c0069 100644
--- a/corelib/include/rtabmap/core/camera/CameraFreenect2.h
+++ b/corelib/include/rtabmap/core/camera/CameraFreenect2.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -45,7 +43,7 @@ class PacketPipeline;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraFreenect2 :
+class RTABMAP_CORE_EXPORT CameraFreenect2 :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraImages.h b/corelib/include/rtabmap/core/camera/CameraImages.h
index bc364e5325..0a38c52c2d 100644
--- a/corelib/include/rtabmap/core/camera/CameraImages.h
+++ b/corelib/include/rtabmap/core/camera/CameraImages.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/utilite/UTimer.h"
 #include <list>
@@ -38,7 +36,7 @@ class UDirectory;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraImages :
+class RTABMAP_CORE_EXPORT CameraImages :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraK4A.h b/corelib/include/rtabmap/core/camera/CameraK4A.h
index d4b1377036..b942ea2086 100644
--- a/corelib/include/rtabmap/core/camera/CameraK4A.h
+++ b/corelib/include/rtabmap/core/camera/CameraK4A.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/CameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -42,7 +40,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraK4A :
+class RTABMAP_CORE_EXPORT CameraK4A :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraK4W2.h b/corelib/include/rtabmap/core/camera/CameraK4W2.h
index beb877d792..26581471ae 100644
--- a/corelib/include/rtabmap/core/camera/CameraK4W2.h
+++ b/corelib/include/rtabmap/core/camera/CameraK4W2.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/CameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -43,7 +41,7 @@ typedef struct IMultiSourceFrameReader IMultiSourceFrameReader;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraK4W2 :
+class RTABMAP_CORE_EXPORT CameraK4W2 :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraMyntEye.h b/corelib/include/rtabmap/core/camera/CameraMyntEye.h
index aeea8084ec..648d0846c8 100644
--- a/corelib/include/rtabmap/core/camera/CameraMyntEye.h
+++ b/corelib/include/rtabmap/core/camera/CameraMyntEye.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
 #include "rtabmap/utilite/USemaphore.h"
@@ -46,7 +44,7 @@ namespace rtabmap
  * Class CameraMyntEye
  *
  */
-class RTABMAP_EXP CameraMyntEye : public Camera
+class RTABMAP_CORE_EXPORT CameraMyntEye : public Camera
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/camera/CameraOpenNI2.h b/corelib/include/rtabmap/core/camera/CameraOpenNI2.h
index d22c65c572..32d14a4625 100644
--- a/corelib/include/rtabmap/core/camera/CameraOpenNI2.h
+++ b/corelib/include/rtabmap/core/camera/CameraOpenNI2.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -41,7 +39,7 @@ class VideoStream;
 
 namespace rtabmap
 {
-class RTABMAP_EXP CameraOpenNI2 :
+class RTABMAP_CORE_EXPORT CameraOpenNI2 :
 	public Camera
 {
 
diff --git a/corelib/include/rtabmap/core/camera/CameraOpenNICV.h b/corelib/include/rtabmap/core/camera/CameraOpenNICV.h
index 8f67e8409a..41a0669acf 100644
--- a/corelib/include/rtabmap/core/camera/CameraOpenNICV.h
+++ b/corelib/include/rtabmap/core/camera/CameraOpenNICV.h
@@ -27,15 +27,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
 
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraOpenNICV :
+class RTABMAP_CORE_EXPORT CameraOpenNICV :
 	public Camera
 {
 
diff --git a/corelib/include/rtabmap/core/camera/CameraOpenni.h b/corelib/include/rtabmap/core/camera/CameraOpenni.h
index 66992b73b7..31af10515e 100644
--- a/corelib/include/rtabmap/core/camera/CameraOpenni.h
+++ b/corelib/include/rtabmap/core/camera/CameraOpenni.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/utilite/UMutex.h"
 #include "rtabmap/utilite/USemaphore.h"
 #include "rtabmap/core/Camera.h"
@@ -56,7 +54,7 @@ class Grabber;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraOpenni :
+class RTABMAP_CORE_EXPORT CameraOpenni :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraRGBDImages.h b/corelib/include/rtabmap/core/camera/CameraRGBDImages.h
index 67e023650c..03189a09ff 100644
--- a/corelib/include/rtabmap/core/camera/CameraRGBDImages.h
+++ b/corelib/include/rtabmap/core/camera/CameraRGBDImages.h
@@ -32,7 +32,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraRGBDImages :
+class RTABMAP_CORE_EXPORT CameraRGBDImages :
 	public CameraImages
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraRealSense.h b/corelib/include/rtabmap/core/camera/CameraRealSense.h
index 7fd2b4571c..bf9b4de5c9 100644
--- a/corelib/include/rtabmap/core/camera/CameraRealSense.h
+++ b/corelib/include/rtabmap/core/camera/CameraRealSense.h
@@ -27,9 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
-
 #include "rtabmap/utilite/UMutex.h"
 #include "rtabmap/utilite/USemaphore.h"
 #include "rtabmap/core/CameraModel.h"
@@ -49,7 +46,7 @@ namespace rtabmap
 {
 
 class slam_event_handler;
-class RTABMAP_EXP CameraRealSense :
+class RTABMAP_CORE_EXPORT CameraRealSense :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraRealSense2.h b/corelib/include/rtabmap/core/camera/CameraRealSense2.h
index ab2d5faf24..e8e02e4847 100644
--- a/corelib/include/rtabmap/core/camera/CameraRealSense2.h
+++ b/corelib/include/rtabmap/core/camera/CameraRealSense2.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/CameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -53,7 +51,7 @@ struct rs2_extrinsics;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraRealSense2 :
+class RTABMAP_CORE_EXPORT CameraRealSense2 :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoDC1394.h b/corelib/include/rtabmap/core/camera/CameraStereoDC1394.h
index 5e126c4222..13832204b5 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoDC1394.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoDC1394.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -38,7 +36,7 @@ namespace rtabmap
 
 class DC1394Device;
 
-class RTABMAP_EXP CameraStereoDC1394 :
+class RTABMAP_CORE_EXPORT CameraStereoDC1394 :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoFlyCapture2.h b/corelib/include/rtabmap/core/camera/CameraStereoFlyCapture2.h
index 9ba5d86933..093f40865c 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoFlyCapture2.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoFlyCapture2.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
 
@@ -40,7 +38,7 @@ class Camera;
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraStereoFlyCapture2 :
+class RTABMAP_CORE_EXPORT CameraStereoFlyCapture2 :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoImages.h b/corelib/include/rtabmap/core/camera/CameraStereoImages.h
index a71b7595d2..ed3a3ae303 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoImages.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoImages.h
@@ -28,7 +28,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #pragma once
 
 #include <rtabmap/core/camera/CameraImages.h>
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
 
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Version.h"
@@ -37,7 +36,7 @@ namespace rtabmap
 {
 
 class CameraImages;
-class RTABMAP_EXP CameraStereoImages :
+class RTABMAP_CORE_EXPORT CameraStereoImages :
 	public CameraImages
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoTara.h b/corelib/include/rtabmap/core/camera/CameraStereoTara.h
index c8c12a0d9a..d6a655e4cf 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoTara.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoTara.h
@@ -32,8 +32,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/camera/CameraVideo.h"
 #include "rtabmap/core/Version.h"
@@ -42,7 +40,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraStereoTara :
+class RTABMAP_CORE_EXPORT CameraStereoTara :
 public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoVideo.h b/corelib/include/rtabmap/core/camera/CameraStereoVideo.h
index 1affbb854d..90042e05c3 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoVideo.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoVideo.h
@@ -27,15 +27,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/camera/CameraVideo.h"
 
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraStereoVideo :
+class RTABMAP_CORE_EXPORT CameraStereoVideo :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoZed.h b/corelib/include/rtabmap/core/camera/CameraStereoZed.h
index 610fd16e4f..0f5f2591ec 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoZed.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoZed.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/camera/CameraVideo.h"
 #include "rtabmap/core/Version.h"
@@ -42,7 +40,7 @@ namespace rtabmap
 {
 class ZedIMUThread;
 
-class RTABMAP_EXP CameraStereoZed :
+class RTABMAP_CORE_EXPORT CameraStereoZed :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraStereoZedOC.h b/corelib/include/rtabmap/core/camera/CameraStereoZedOC.h
index a89c4c096b..5f31ea960e 100644
--- a/corelib/include/rtabmap/core/camera/CameraStereoZedOC.h
+++ b/corelib/include/rtabmap/core/camera/CameraStereoZedOC.h
@@ -27,8 +27,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include "rtabmap/core/StereoCameraModel.h"
 #include "rtabmap/core/Camera.h"
 #include "rtabmap/core/Version.h"
@@ -46,7 +44,7 @@ namespace rtabmap
 {
 class ZedOCThread;
 
-class RTABMAP_EXP CameraStereoZedOC :
+class RTABMAP_CORE_EXPORT CameraStereoZedOC :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/camera/CameraVideo.h b/corelib/include/rtabmap/core/camera/CameraVideo.h
index 675cc08264..da7124937f 100644
--- a/corelib/include/rtabmap/core/camera/CameraVideo.h
+++ b/corelib/include/rtabmap/core/camera/CameraVideo.h
@@ -27,15 +27,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 #pragma once
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <opencv2/highgui/highgui.hpp>
 #include "rtabmap/core/Camera.h"
 
 namespace rtabmap
 {
 
-class RTABMAP_EXP CameraVideo :
+class RTABMAP_CORE_EXPORT CameraVideo :
 	public Camera
 {
 public:
diff --git a/corelib/include/rtabmap/core/clams/discrete_depth_distortion_model.h b/corelib/include/rtabmap/core/clams/discrete_depth_distortion_model.h
index 7f3e1b704e..ab473f160d 100644
--- a/corelib/include/rtabmap/core/clams/discrete_depth_distortion_model.h
+++ b/corelib/include/rtabmap/core/clams/discrete_depth_distortion_model.h
@@ -36,11 +36,11 @@ RTAB-Map integration: Mathieu Labbe
 #include <Eigen/Core>
 #include <opencv2/opencv.hpp>
 #include <rtabmap/utilite/UMutex.h>
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 namespace clams
 {
-  class RTABMAP_EXP DiscreteFrustum
+  class RTABMAP_CORE_EXPORT DiscreteFrustum
   {
   public:
     DiscreteFrustum(int smoothing = 1, double bin_depth = 1.0, double max_dist = 10.0);
@@ -65,7 +65,7 @@ namespace clams
     friend class DiscreteDepthDistortionModel;
   };
 
-  class RTABMAP_EXP DiscreteDepthDistortionModel
+  class RTABMAP_CORE_EXPORT DiscreteDepthDistortionModel
   {
   public:
     // returns all divisors of num
diff --git a/corelib/include/rtabmap/core/clams/frame_projector.h b/corelib/include/rtabmap/core/clams/frame_projector.h
index 181e0e5fa8..f057103656 100644
--- a/corelib/include/rtabmap/core/clams/frame_projector.h
+++ b/corelib/include/rtabmap/core/clams/frame_projector.h
@@ -34,7 +34,6 @@ RTAB-Map integration: Mathieu Labbe
 #include <pcl/point_types.h>
 #include <opencv2/core/core.hpp>
 #include <rtabmap/core/CameraModel.h>
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
 
 #define MAX_MULT 1.3
 #define MIN_MULT 0.7
@@ -60,7 +59,7 @@ namespace clams
 
   //! This is essentially a pinhole camera model for an RGBD sensor, with
   //! some extra functions added on for use during calibration.
-  class RTABMAP_EXP FrameProjector
+  class RTABMAP_CORE_EXPORT FrameProjector
   {
   public:
     // For storing z values in meters.  This is not Euclidean distance.
diff --git a/corelib/include/rtabmap/core/clams/slam_calibrator.h b/corelib/include/rtabmap/core/clams/slam_calibrator.h
index ee3343ca8c..671e26c08b 100644
--- a/corelib/include/rtabmap/core/clams/slam_calibrator.h
+++ b/corelib/include/rtabmap/core/clams/slam_calibrator.h
@@ -35,12 +35,10 @@ RTAB-Map integration: Mathieu Labbe
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 namespace clams
 {
   
-DiscreteDepthDistortionModel RTABMAP_EXP calibrate(
+DiscreteDepthDistortionModel RTABMAP_CORE_EXPORT calibrate(
 		const std::map<int, rtabmap::SensorData> & sequence,
 		const std::map<int, rtabmap::Transform> & trajectory,
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & map,
diff --git a/corelib/include/rtabmap/core/odometry/OdometryDVO.h b/corelib/include/rtabmap/core/odometry/OdometryDVO.h
index 2411cf7793..35427feadc 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryDVO.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryDVO.h
@@ -40,7 +40,7 @@ class RgbdCameraPyramid;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryDVO : public Odometry
+class RTABMAP_CORE_EXPORT OdometryDVO : public Odometry
 {
 public:
 	OdometryDVO(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryF2F.h b/corelib/include/rtabmap/core/odometry/OdometryF2F.h
index b3da8e8f4f..a2d3bd0995 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryF2F.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryF2F.h
@@ -35,7 +35,7 @@ namespace rtabmap {
 
 class Registration;
 
-class RTABMAP_EXP OdometryF2F : public Odometry
+class RTABMAP_CORE_EXPORT OdometryF2F : public Odometry
 {
 public:
 	OdometryF2F(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryF2M.h b/corelib/include/rtabmap/core/odometry/OdometryF2M.h
index 9f9ba67610..ce5c117325 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryF2M.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryF2M.h
@@ -41,7 +41,7 @@ class Signature;
 class Registration;
 class Optimizer;
 
-class RTABMAP_EXP OdometryF2M : public Odometry
+class RTABMAP_CORE_EXPORT OdometryF2M : public Odometry
 {
 public:
 	OdometryF2M(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryFLOAM.h b/corelib/include/rtabmap/core/odometry/OdometryFLOAM.h
index 1878be5a5c..81e9f1ef39 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryFLOAM.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryFLOAM.h
@@ -35,7 +35,7 @@ class OdomEstimationClass;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryFLOAM : public Odometry
+class RTABMAP_CORE_EXPORT OdometryFLOAM : public Odometry
 {
 public:
 	OdometryFLOAM(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryFovis.h b/corelib/include/rtabmap/core/odometry/OdometryFovis.h
index 2318517382..06b8a0ac6b 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryFovis.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryFovis.h
@@ -40,7 +40,7 @@ class StereoDepth;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryFovis : public Odometry
+class RTABMAP_CORE_EXPORT OdometryFovis : public Odometry
 {
 public:
 	OdometryFovis(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryLOAM.h b/corelib/include/rtabmap/core/odometry/OdometryLOAM.h
index 17f7056bd8..2977d2116d 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryLOAM.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryLOAM.h
@@ -40,7 +40,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryLOAM : public Odometry
+class RTABMAP_CORE_EXPORT OdometryLOAM : public Odometry
 {
 public:
 	OdometryLOAM(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryMSCKF.h b/corelib/include/rtabmap/core/odometry/OdometryMSCKF.h
index 7ab609f20f..c38cad6c79 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryMSCKF.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryMSCKF.h
@@ -35,7 +35,7 @@ namespace rtabmap {
 class ImageProcessorNoROS;
 class MsckfVioNoROS;
 
-class RTABMAP_EXP OdometryMSCKF : public Odometry
+class RTABMAP_CORE_EXPORT OdometryMSCKF : public Odometry
 {
 public:
 	OdometryMSCKF(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryMono.h b/corelib/include/rtabmap/core/odometry/OdometryMono.h
index 898b7dbf90..c0b98ceeb1 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryMono.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryMono.h
@@ -36,7 +36,7 @@ namespace rtabmap {
 class Memory;
 class Feature2D;
 
-class RTABMAP_EXP OdometryMono : public Odometry
+class RTABMAP_CORE_EXPORT OdometryMono : public Odometry
 {
 public:
 	OdometryMono(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryORBSLAM.h b/corelib/include/rtabmap/core/odometry/OdometryORBSLAM.h
index 8f5c1fb5a6..a0af8bad03 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryORBSLAM.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryORBSLAM.h
@@ -42,7 +42,7 @@ class ORBSLAMSystem;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryORBSLAM : public Odometry
+class RTABMAP_CORE_EXPORT OdometryORBSLAM : public Odometry
 {
 public:
 	OdometryORBSLAM(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryOkvis.h b/corelib/include/rtabmap/core/odometry/OdometryOkvis.h
index 5861497050..d3fe2a0589 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryOkvis.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryOkvis.h
@@ -37,7 +37,7 @@ namespace okvis {
 namespace rtabmap {
 
 class OkvisCallbackHandler;
-class RTABMAP_EXP OdometryOkvis : public Odometry
+class RTABMAP_CORE_EXPORT OdometryOkvis : public Odometry
 {
 public:
 	OdometryOkvis(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryOpen3D.h b/corelib/include/rtabmap/core/odometry/OdometryOpen3D.h
index 7f165642af..d7b7de8985 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryOpen3D.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryOpen3D.h
@@ -32,7 +32,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryOpen3D : public Odometry
+class RTABMAP_CORE_EXPORT OdometryOpen3D : public Odometry
 {
 public:
 	OdometryOpen3D(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryOpenVINS.h b/corelib/include/rtabmap/core/odometry/OdometryOpenVINS.h
index ddbf1650fb..ed0aa2de2c 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryOpenVINS.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryOpenVINS.h
@@ -36,7 +36,7 @@ class VioManager;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryOpenVINS : public Odometry
+class RTABMAP_CORE_EXPORT OdometryOpenVINS : public Odometry
 {
 public:
 	OdometryOpenVINS(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryVINS.h b/corelib/include/rtabmap/core/odometry/OdometryVINS.h
index 8dc41ca26d..030de4a338 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryVINS.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryVINS.h
@@ -34,7 +34,7 @@ namespace rtabmap {
 
 class VinsEstimator;
 
-class RTABMAP_EXP OdometryVINS : public Odometry
+class RTABMAP_CORE_EXPORT OdometryVINS : public Odometry
 {
 public:
 	OdometryVINS(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/odometry/OdometryViso2.h b/corelib/include/rtabmap/core/odometry/OdometryViso2.h
index 52658a1140..ea8b104db3 100644
--- a/corelib/include/rtabmap/core/odometry/OdometryViso2.h
+++ b/corelib/include/rtabmap/core/odometry/OdometryViso2.h
@@ -34,7 +34,7 @@ class VisualOdometryStereo;
 
 namespace rtabmap {
 
-class RTABMAP_EXP OdometryViso2 : public Odometry
+class RTABMAP_CORE_EXPORT OdometryViso2 : public Odometry
 {
 public:
 	OdometryViso2(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
diff --git a/corelib/include/rtabmap/core/optimizer/OptimizerCVSBA.h b/corelib/include/rtabmap/core/optimizer/OptimizerCVSBA.h
index c2c2c0f81b..692ade7912 100644
--- a/corelib/include/rtabmap/core/optimizer/OptimizerCVSBA.h
+++ b/corelib/include/rtabmap/core/optimizer/OptimizerCVSBA.h
@@ -28,13 +28,11 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZERCVSBA_H_
 #define OPTIMIZERCVSBA_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/Optimizer.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP OptimizerCVSBA : public Optimizer
+class RTABMAP_CORE_EXPORT OptimizerCVSBA : public Optimizer
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/optimizer/OptimizerCeres.h b/corelib/include/rtabmap/core/optimizer/OptimizerCeres.h
index 6d500a8297..abf2010d7b 100644
--- a/corelib/include/rtabmap/core/optimizer/OptimizerCeres.h
+++ b/corelib/include/rtabmap/core/optimizer/OptimizerCeres.h
@@ -28,13 +28,11 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZERCERES_H_
 #define OPTIMIZERCERES_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/Optimizer.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP OptimizerCeres : public Optimizer
+class RTABMAP_CORE_EXPORT OptimizerCeres : public Optimizer
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/optimizer/OptimizerG2O.h b/corelib/include/rtabmap/core/optimizer/OptimizerG2O.h
index 206552f983..30117d6e56 100644
--- a/corelib/include/rtabmap/core/optimizer/OptimizerG2O.h
+++ b/corelib/include/rtabmap/core/optimizer/OptimizerG2O.h
@@ -28,13 +28,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZERG2O_H_
 #define OPTIMIZERG2O_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
+#include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Optimizer.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP OptimizerG2O : public Optimizer
+class RTABMAP_CORE_EXPORT OptimizerG2O : public Optimizer
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/optimizer/OptimizerGTSAM.h b/corelib/include/rtabmap/core/optimizer/OptimizerGTSAM.h
index 465b13ece3..5cec5c2415 100644
--- a/corelib/include/rtabmap/core/optimizer/OptimizerGTSAM.h
+++ b/corelib/include/rtabmap/core/optimizer/OptimizerGTSAM.h
@@ -28,13 +28,11 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZERGTSAM_H_
 #define OPTIMIZERGTSAM_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/Optimizer.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP OptimizerGTSAM : public Optimizer
+class RTABMAP_CORE_EXPORT OptimizerGTSAM : public Optimizer
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/optimizer/OptimizerTORO.h b/corelib/include/rtabmap/core/optimizer/OptimizerTORO.h
index 8456946a4f..f2a3cecc6d 100644
--- a/corelib/include/rtabmap/core/optimizer/OptimizerTORO.h
+++ b/corelib/include/rtabmap/core/optimizer/OptimizerTORO.h
@@ -28,13 +28,11 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef OPTIMIZERTORO_H_
 #define OPTIMIZERTORO_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/Optimizer.h>
 
 namespace rtabmap {
 
-class RTABMAP_EXP OptimizerTORO : public Optimizer
+class RTABMAP_CORE_EXPORT OptimizerTORO : public Optimizer
 {
 public:
 	static bool available();
diff --git a/corelib/include/rtabmap/core/stereo/StereoBM.h b/corelib/include/rtabmap/core/stereo/StereoBM.h
index 4e8ef612b5..99d606af01 100644
--- a/corelib/include/rtabmap/core/stereo/StereoBM.h
+++ b/corelib/include/rtabmap/core/stereo/StereoBM.h
@@ -28,15 +28,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef STEREOBM_H_
 #define STEREOBM_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/StereoDense.h>
 #include <rtabmap/core/Parameters.h>
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP StereoBM : public StereoDense {
+class RTABMAP_CORE_EXPORT StereoBM : public StereoDense {
 public:
 	StereoBM(int blockSize, int numDisparities);
 	StereoBM(const ParametersMap & parameters = ParametersMap());
diff --git a/corelib/include/rtabmap/core/stereo/StereoSGBM.h b/corelib/include/rtabmap/core/stereo/StereoSGBM.h
index d04fb6c65b..1899cef5b2 100644
--- a/corelib/include/rtabmap/core/stereo/StereoSGBM.h
+++ b/corelib/include/rtabmap/core/stereo/StereoSGBM.h
@@ -28,15 +28,13 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef STEREOSGBM_H_
 #define STEREOSGBM_H_
 
-#include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
-
 #include <rtabmap/core/StereoDense.h>
 #include <rtabmap/core/Parameters.h>
 #include <opencv2/core/core.hpp>
 
 namespace rtabmap {
 
-class RTABMAP_EXP StereoSGBM : public StereoDense {
+class RTABMAP_CORE_EXPORT StereoSGBM : public StereoDense {
 public:
 	StereoSGBM(const ParametersMap & parameters = ParametersMap());
 	virtual ~StereoSGBM() {}
diff --git a/corelib/include/rtabmap/core/util2d.h b/corelib/include/rtabmap/core/util2d.h
index 82e894af0f..008309573b 100644
--- a/corelib/include/rtabmap/core/util2d.h
+++ b/corelib/include/rtabmap/core/util2d.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL2D_H_
 #define UTIL2D_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <opencv2/core/core.hpp>
 #include <rtabmap/core/Transform.h>
@@ -42,11 +42,11 @@ namespace util2d
 {
 
 // SSD: Sum of Squared Differences
-float RTABMAP_EXP ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
+float RTABMAP_CORE_EXPORT ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
 // SAD: Sum of Absolute intensity Differences
-float RTABMAP_EXP sad(const cv::Mat & windowLeft, const cv::Mat & windowRight);
+float RTABMAP_CORE_EXPORT sad(const cv::Mat & windowLeft, const cv::Mat & windowRight);
 
-std::vector<cv::Point2f> RTABMAP_EXP calcStereoCorrespondences(
+std::vector<cv::Point2f> RTABMAP_CORE_EXPORT calcStereoCorrespondences(
 		const cv::Mat & leftImage,
 		const cv::Mat & rightImage,
 		const std::vector<cv::Point2f> & leftCorners,
@@ -59,7 +59,7 @@ std::vector<cv::Point2f> RTABMAP_EXP calcStereoCorrespondences(
 		bool ssdApproach = true); // SSD by default, otherwise it is SAD
 
 // exactly as cv::calcOpticalFlowPyrLK but it should be called with pyramid (from cv::buildOpticalFlowPyramid()) and delta drops the y error.
-void RTABMAP_EXP calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputArray _nextImg,
+void RTABMAP_CORE_EXPORT calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputArray _nextImg,
                            cv::InputArray _prevPts, cv::InputOutputArray _nextPts,
                            cv::OutputArray _status, cv::OutputArray _err,
                            cv::Size winSize = cv::Size(15,3), int maxLevel = 3,
@@ -67,16 +67,16 @@ void RTABMAP_EXP calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputA
 						   int flags = 0, double minEigThreshold = 1e-4 );
 
 
-cv::Mat RTABMAP_EXP disparityFromStereoImages(
+cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoImages(
 		const cv::Mat & leftImage,
 		const cv::Mat & rightImage,
 	    const ParametersMap & parameters = ParametersMap());
 
-cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat & disparity,
+cv::Mat RTABMAP_CORE_EXPORT depthFromDisparity(const cv::Mat & disparity,
 		float fx, float baseline,
 		int type = CV_32FC1); // CV_32FC1 or CV_16UC1
 
-cv::Mat RTABMAP_EXP depthFromStereoImages(
+cv::Mat RTABMAP_CORE_EXPORT depthFromStereoImages(
 		const cv::Mat & leftImage,
 		const cv::Mat & rightImage,
 		const std::vector<cv::Point2f> & leftCorners,
@@ -87,63 +87,63 @@ cv::Mat RTABMAP_EXP depthFromStereoImages(
 		int flowIterations = 20,
 		double flowEps = 0.02);
 
-cv::Mat RTABMAP_EXP disparityFromStereoCorrespondences(
+cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoCorrespondences(
 		const cv::Size & disparitySize,
 		const std::vector<cv::Point2f> & leftCorners,
 		const std::vector<cv::Point2f> & rightCorners,
 		const std::vector<unsigned char> & mask);
 
-cv::Mat RTABMAP_EXP depthFromStereoCorrespondences(
+cv::Mat RTABMAP_CORE_EXPORT depthFromStereoCorrespondences(
 		const cv::Mat & leftImage,
 		const std::vector<cv::Point2f> & leftCorners,
 		const std::vector<cv::Point2f> & rightCorners,
 		const std::vector<unsigned char> & mask,
 		float fx, float baseline);
 
-cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat & depth32F);
-cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat & depth16U);
+cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat & depth32F);
+cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat(const cv::Mat & depth16U);
 
-float RTABMAP_EXP getDepth(
+float RTABMAP_CORE_EXPORT getDepth(
 		const cv::Mat & depthImage,
 		float x, float y,
 		bool smoothing,
 		float depthErrorRatio = 0.02f, //ratio
 		bool estWithNeighborsIfNull = false);
 
-cv::Rect RTABMAP_EXP computeRoi(const cv::Mat & image, const std::string & roiRatios);
-cv::Rect RTABMAP_EXP computeRoi(const cv::Size & imageSize, const std::string & roiRatios);
-cv::Rect RTABMAP_EXP computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
-cv::Rect RTABMAP_EXP computeRoi(const cv::Size & imageSize, const std::vector<float> & roiRatios);
+cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat & image, const std::string & roiRatios);
+cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Size & imageSize, const std::string & roiRatios);
+cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
+cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Size & imageSize, const std::vector<float> & roiRatios);
 
-cv::Mat RTABMAP_EXP decimate(const cv::Mat & image, int d);
-cv::Mat RTABMAP_EXP interpolate(const cv::Mat & image, int factor, float depthErrorRatio = 0.02f);
+cv::Mat RTABMAP_CORE_EXPORT decimate(const cv::Mat & image, int d);
+cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat & image, int factor, float depthErrorRatio = 0.02f);
 
 // Registration Depth to RGB (return registered depth image)
-cv::Mat RTABMAP_EXP registerDepth(
+cv::Mat RTABMAP_CORE_EXPORT registerDepth(
 		const cv::Mat & depth,
 		const cv::Mat & depthK,
 		const cv::Size & colorSize,
 		const cv::Mat & colorK,
 		const rtabmap::Transform & transform);
 
-cv::Mat RTABMAP_EXP fillDepthHoles(
+cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(
 		const cv::Mat & depth,
 		int maximumHoleSize = 1,
 		float errorRatio = 0.02f);
 
-void RTABMAP_EXP fillRegisteredDepthHoles(
+void RTABMAP_CORE_EXPORT fillRegisteredDepthHoles(
 		cv::Mat & depthRegistered,
 		bool vertical,
 		bool horizontal,
 		bool fillDoubleHoles = false);
 
-cv::Mat RTABMAP_EXP fastBilateralFiltering(
+cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering(
 		const cv::Mat & depth,
 		float sigmaS = 15.0f,
 		float sigmaR = 0.05f,
 		bool earlyDivision = false);
 
-cv::Mat RTABMAP_EXP brightnessAndContrastAuto(
+cv::Mat RTABMAP_CORE_EXPORT brightnessAndContrastAuto(
 		const cv::Mat & src,
 		const cv::Mat & mask,
 		float clipLowHistPercent=0,
@@ -151,10 +151,10 @@ cv::Mat RTABMAP_EXP brightnessAndContrastAuto(
 		float * alphaOut = 0,
 		float * betaOut = 0);
 
-cv::Mat RTABMAP_EXP exposureFusion(
+cv::Mat RTABMAP_CORE_EXPORT exposureFusion(
 	const std::vector<cv::Mat> & images);
 
-void RTABMAP_EXP HSVtoRGB( float *r, float *g, float *b, float h, float s, float v );
+void RTABMAP_CORE_EXPORT HSVtoRGB( float *r, float *g, float *b, float h, float s, float v );
 
 } // namespace util3d
 } // namespace rtabmap
diff --git a/corelib/include/rtabmap/core/util3d.h b/corelib/include/rtabmap/core/util3d.h
index 718ebb401f..5077083906 100644
--- a/corelib/include/rtabmap/core/util3d.h
+++ b/corelib/include/rtabmap/core/util3d.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_H_
 #define UTIL3D_H_
 
-#include "rtabmap/core/RtabmapExp.h"
+#include "rtabmap/core/rtabmap_core_export.h"
 
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -48,17 +48,17 @@ namespace rtabmap
 namespace util3d
 {
 
-cv::Mat RTABMAP_EXP rgbFromCloud(
+cv::Mat RTABMAP_CORE_EXPORT rgbFromCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
 		bool bgrOrder = true);
 
-cv::Mat RTABMAP_EXP depthFromCloud(
+cv::Mat RTABMAP_CORE_EXPORT depthFromCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
 		float & fx,
 		float & fy,
 		bool depth16U = true);
 
-void RTABMAP_EXP rgbdFromCloud(
+void RTABMAP_CORE_EXPORT rgbdFromCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBA> & cloud,
 		cv::Mat & rgb,
 		cv::Mat & depth,
@@ -67,7 +67,7 @@ void RTABMAP_EXP rgbdFromCloud(
 		bool bgrOrder = true,
 		bool depth16U = true);
 
-pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(
+pcl::PointXYZ RTABMAP_CORE_EXPORT projectDepthTo3D(
 		const cv::Mat & depthImage,
 		float x, float y,
 		float cx, float cy,
@@ -75,21 +75,22 @@ pcl::PointXYZ RTABMAP_EXP projectDepthTo3D(
 		bool smoothing,
 		float depthErrorRatio = 0.02f);
 
-Eigen::Vector3f RTABMAP_EXP projectDepthTo3DRay(
+Eigen::Vector3f RTABMAP_CORE_EXPORT projectDepthTo3DRay(
 		const cv::Size & imageSize,
 		float x, float y,
 		float cx, float cy,
 		float fx, float fy);
 
-RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
+// Use cloudFromDepth with CameraModel interface.
+RTABMAP_DEPRECATED pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cloudFromDepth(
 		const cv::Mat & imageDepth,
 		float cx, float cy,
 		float fx, float fy,
 		int decimation = 1,
 		float maxDepth = 0.0f,
 		float minDepth = 0.0f,
-		std::vector<int> * validIndices = 0), "Use cloudFromDepth with CameraModel interface.");
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
+		std::vector<int> * validIndices = 0);
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cloudFromDepth(
 		const cv::Mat & imageDepth,
 		const CameraModel & model,
 		int decimation = 1,
@@ -97,7 +98,8 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDepth(
 		float minDepth = 0.0f,
 		std::vector<int> * validIndices = 0);
 
-RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
+// Use cloudFromDepthRGB with CameraModel interface.
+RTABMAP_DEPRECATED pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cloudFromDepthRGB(
 		const cv::Mat & imageRgb,
 		const cv::Mat & imageDepth,
 		float cx, float cy,
@@ -105,8 +107,8 @@ RTABMAP_DEPRECATED (pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFrom
 		int decimation = 1,
 		float maxDepth = 0.0f,
 		float minDepth = 0.0f,
-		std::vector<int> * validIndices = 0), "Use cloudFromDepthRGB with CameraModel interface.");
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
+		std::vector<int> * validIndices = 0);
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cloudFromDepthRGB(
 		const cv::Mat & imageRgb,
 		const cv::Mat & imageDepth,
 		const CameraModel & model,
@@ -115,7 +117,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDepthRGB(
 		float minDepth = 0.0f,
 		std::vector<int> * validIndices = 0);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cloudFromDisparity(
 		const cv::Mat & imageDisparity,
 		const StereoCameraModel & model,
 		int decimation = 1,
@@ -123,7 +125,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromDisparity(
 		float minDepth = 0.0f,
 		std::vector<int> * validIndices = 0);
 
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cloudFromDisparityRGB(
 		const cv::Mat & imageRgb,
 		const cv::Mat & imageDisparity,
 		const StereoCameraModel & model,
@@ -132,7 +134,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromDisparityRGB(
 		float minDepth = 0.0f,
 		std::vector<int> * validIndices = 0);
 
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cloudFromStereoImages(
 		const cv::Mat & imageLeft,
 		const cv::Mat & imageRight,
 		const StereoCameraModel & model,
@@ -142,7 +144,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudFromStereoImages(
 		std::vector<int> * validIndices = 0,
 		const ParametersMap & parameters = ParametersMap());
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cloudFromSensorData(
 		const SensorData & sensorData,
 		int decimation = 1,
 		float maxDepth = 0.0f,
@@ -165,7 +167,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
  * @param roiRatios, [left, right, top, bottom] region of interest (in ratios) of the image projected.
  * @return a RGB cloud.
  */
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cloudRGBFromSensorData(
 		const SensorData & sensorData,
 		int decimation = 1,
 		float maxDepth = 0.0f,
@@ -177,7 +179,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
 /**
  * Simulate a laser scan rotating counterclockwise, using middle line of the depth image.
  */
-pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
+pcl::PointCloud<pcl::PointXYZ> RTABMAP_CORE_EXPORT laserScanFromDepthImage(
 					const cv::Mat & depthImage,
 					float fx,
 					float fy,
@@ -191,7 +193,7 @@ pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImage(
  * The last value of the scan is the most left value of the first depth image. The first value of the scan is the most right value of the last depth image.
  *
  */
-pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImages(
+pcl::PointCloud<pcl::PointXYZ> RTABMAP_CORE_EXPORT laserScanFromDepthImages(
 		const cv::Mat & depthImages,
 		const std::vector<CameraModel> & cameraModels,
 		float maxDepth,
@@ -200,104 +202,104 @@ pcl::PointCloud<pcl::PointXYZ> RTABMAP_EXP laserScanFromDepthImages(
 template<typename PointCloud2T>
 LaserScan laserScanFromPointCloud(const PointCloud2T & cloud, bool filterNaNs = true, bool is2D = false, const Transform & transform = Transform());
 // return CV_32FC3  (x,y,z)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC6 (x,y,z,normal_x,normal_y,normal_z)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC4 (x,y,z,rgb)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC4 (x,y,z,I)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC7 (x,y,z,rgb,normal_x,normal_y,normal_z)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGB> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC7 (x,y,z,I,normal_x,normal_y,normal_z)
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScanFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const pcl::IndicesPtr & indices, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC2  (x,y)
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC3  (x,y,I)
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC5  (x,y,normal_x, normal_y, normal_z)
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointNormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZ> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
 // return CV_32FC6  (x,y,I,normal_x, normal_y, normal_z)
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
-LaserScan RTABMAP_EXP laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZINormal> & cloud, const Transform & transform = Transform(), bool filterNaNs = true);
+LaserScan RTABMAP_CORE_EXPORT laserScan2dFromPointCloud(const pcl::PointCloud<pcl::PointXYZI> & cloud, const pcl::PointCloud<pcl::Normal> & normals, const Transform & transform = Transform(), bool filterNaNs = true);
 
-pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan & laserScan, const Transform & transform = Transform());
+pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloud2(const LaserScan & laserScan, const Transform & transform = Transform());
 // For 2d laserScan, z is set to null.
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloud(const LaserScan & laserScan, const Transform & transform = Transform());
 // For laserScan without normals, normals are set to null.
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudNormal(const LaserScan & laserScan, const Transform & transform = Transform());
 // For laserScan without rgb, rgb is set to default r,g,b parameters.
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP laserScanToPointCloudRGB(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudRGB(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
 // For laserScan without intensity, intensity is set to intensity parameter.
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudI(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
 // For laserScan without rgb, rgb is set to default r,g,b parameters.
 // For laserScan without normals, normals are set to null.
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudRGBNormal(const LaserScan & laserScan, const Transform & transform = Transform(), unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
 // For laserScan without intensity, intensity is set to default intensity parameter.
 // For laserScan without normals, normals are set to null.
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT laserScanToPointCloudINormal(const LaserScan & laserScan, const Transform & transform = Transform(), float intensity = 0.0f);
 
 // For 2d laserScan, z is set to null.
-pcl::PointXYZ RTABMAP_EXP laserScanToPoint(const LaserScan & laserScan, int index);
+pcl::PointXYZ RTABMAP_CORE_EXPORT laserScanToPoint(const LaserScan & laserScan, int index);
 // For laserScan without normals, normals are set to null.
-pcl::PointNormal RTABMAP_EXP laserScanToPointNormal(const LaserScan & laserScan, int index);
+pcl::PointNormal RTABMAP_CORE_EXPORT laserScanToPointNormal(const LaserScan & laserScan, int index);
 // For laserScan without rgb, rgb is set to default r,g,b parameters.
-pcl::PointXYZRGB RTABMAP_EXP laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
+pcl::PointXYZRGB RTABMAP_CORE_EXPORT laserScanToPointRGB(const LaserScan & laserScan, int index, unsigned char r = 100, unsigned char g = 100, unsigned char b = 100);
 // For laserScan without intensity, intensity is set to intensity parameter.
-pcl::PointXYZI RTABMAP_EXP laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
+pcl::PointXYZI RTABMAP_CORE_EXPORT laserScanToPointI(const LaserScan & laserScan, int index, float intensity);
 // For laserScan without rgb, rgb is set to default r,g,b parameters.
 // For laserScan without normals, normals are set to null.
-pcl::PointXYZRGBNormal RTABMAP_EXP laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
+pcl::PointXYZRGBNormal RTABMAP_CORE_EXPORT laserScanToPointRGBNormal(const LaserScan & laserScan, int index, unsigned char r, unsigned char g, unsigned char b);
 // For laserScan without intensity, intensity is set to default intensity parameter.
 // For laserScan without normals, normals are set to null.
-pcl::PointXYZINormal RTABMAP_EXP laserScanToPointINormal(const LaserScan & laserScan, int index, float intensity);
+pcl::PointXYZINormal RTABMAP_CORE_EXPORT laserScanToPointINormal(const LaserScan & laserScan, int index, float intensity);
 
-void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, cv::Point3f & min, cv::Point3f & max);
-void RTABMAP_EXP getMinMax3D(const cv::Mat & laserScan, pcl::PointXYZ & min, pcl::PointXYZ & max);
+void RTABMAP_CORE_EXPORT getMinMax3D(const cv::Mat & laserScan, cv::Point3f & min, cv::Point3f & max);
+void RTABMAP_CORE_EXPORT getMinMax3D(const cv::Mat & laserScan, pcl::PointXYZ & min, pcl::PointXYZ & max);
 
-cv::Point3f RTABMAP_EXP projectDisparityTo3D(
+cv::Point3f RTABMAP_CORE_EXPORT projectDisparityTo3D(
 		const cv::Point2f & pt,
 		float disparity,
 		const StereoCameraModel & model);
 
-cv::Point3f RTABMAP_EXP projectDisparityTo3D(
+cv::Point3f RTABMAP_CORE_EXPORT projectDisparityTo3D(
 		const cv::Point2f & pt,
 		const cv::Mat & disparity,
 		const StereoCameraModel & model);
 
 // Register point cloud to camera (return registered depth image 32FC1)
-cv::Mat RTABMAP_EXP projectCloudToCamera(
+cv::Mat RTABMAP_CORE_EXPORT projectCloudToCamera(
 		const cv::Size & imageSize,
 		const cv::Mat & cameraMatrixK,  
 		const cv::Mat & laserScan,                   // assuming points are already in /base_link coordinate
 		const rtabmap::Transform & cameraTransform); // /base_link -> /camera_link
 
 // Register point cloud to camera (return registered depth image 32FC1)
-cv::Mat RTABMAP_EXP projectCloudToCamera(
+cv::Mat RTABMAP_CORE_EXPORT projectCloudToCamera(
 		const cv::Size & imageSize,
 		const cv::Mat & cameraMatrixK,
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr laserScan, // assuming points are already in /base_link coordinate
 		const rtabmap::Transform & cameraTransform);         // /base_link -> /camera_link
 
 // Register point cloud to camera (return registered depth image 32FC1)
-cv::Mat RTABMAP_EXP projectCloudToCamera(
+cv::Mat RTABMAP_CORE_EXPORT projectCloudToCamera(
 		const cv::Size & imageSize,
 		const cv::Mat & cameraMatrixK,                       
 		const pcl::PCLPointCloud2::Ptr laserScan, 			 // assuming points are already in /base_link coordinate
 		const rtabmap::Transform & cameraTransform);         // /base_link -> /camera_link
 
 // Direction vertical (>=0), horizontal (<0)
-void RTABMAP_EXP fillProjectedCloudHoles(
+void RTABMAP_CORE_EXPORT fillProjectedCloudHoles(
 		cv::Mat & depthRegistered,
 		bool verticalDirection,
 		bool fillToBorder);
@@ -306,7 +308,7 @@ void RTABMAP_EXP fillProjectedCloudHoles(
  * For each point, return pixel of the best camera (NodeID->CameraIndex)
  * looking at it based on the policy and parameters
  */
-std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectCloudToCameras (
+std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_CORE_EXPORT projectCloudToCameras (
 		const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
 		const std::map<int, Transform> & cameraPoses,
 		const std::map<int, std::vector<CameraModel> > & cameraModels,
@@ -320,7 +322,7 @@ std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectC
  * For each point, return pixel of the best camera (NodeID->CameraIndex)
  * looking at it based on the policy and parameters
  */
-std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectCloudToCameras (
+std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_CORE_EXPORT projectCloudToCameras (
 		const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
 		const std::map<int, Transform> & cameraPoses,
 		const std::map<int, std::vector<CameraModel> > & cameraModels,
@@ -331,11 +333,11 @@ std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > RTABMAP_EXP projectC
 		bool distanceToCamPolicy = false,
 		const ProgressState * state = 0);
 
-bool RTABMAP_EXP isFinite(const cv::Point3f & pt);
+bool RTABMAP_CORE_EXPORT isFinite(const cv::Point3f & pt);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP concatenateClouds(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT concatenateClouds(
 		const std::list<pcl::PointCloud<pcl::PointXYZ>::Ptr> & clouds);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT concatenateClouds(
 		const std::list<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & clouds);
 
 /**
@@ -347,7 +349,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP concatenateClouds(
  * two set of indices set are disjoint and/or you need sorted indices, the use of mergeIndices().
  * @return the indices concatenated.
  */
-pcl::IndicesPtr RTABMAP_EXP concatenate(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT concatenate(
 		const std::vector<pcl::IndicesPtr> & indices);
 
 /**
@@ -360,16 +362,16 @@ pcl::IndicesPtr RTABMAP_EXP concatenate(
  * two set of indices set are disjoint and/or you need sorted indices, the use of mergeIndices().
  * @return the indices concatenated.
  */
-pcl::IndicesPtr RTABMAP_EXP concatenate(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT concatenate(
 		const pcl::IndicesPtr & indicesA,
 		const pcl::IndicesPtr & indicesB);
 
-void RTABMAP_EXP savePCDWords(
+void RTABMAP_CORE_EXPORT savePCDWords(
 		const std::string & fileName,
 		const std::multimap<int, pcl::PointXYZ> & words,
 		const Transform & transform = Transform::getIdentity());
 
-void RTABMAP_EXP savePCDWords(
+void RTABMAP_CORE_EXPORT savePCDWords(
 		const std::string & fileName,
 		const std::multimap<int, cv::Point3f> & words,
 		const Transform & transform = Transform::getIdentity());
@@ -378,18 +380,20 @@ void RTABMAP_EXP savePCDWords(
  * Assume KITTI velodyne format
  * Return scan 4 channels (format=XYZI).
  */
-cv::Mat RTABMAP_EXP loadBINScan(const std::string & fileName);
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName);
-RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadBINCloud(const std::string & fileName, int dim), "Use interface without dim argument.");
+cv::Mat RTABMAP_CORE_EXPORT loadBINScan(const std::string & fileName);
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT loadBINCloud(const std::string & fileName);
+// Use interface without dim argument.
+RTABMAP_DEPRECATED pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT loadBINCloud(const std::string & fileName, int dim);
 
 // Load *.pcd, *.ply or *.bin (KITTI format).
-LaserScan RTABMAP_EXP loadScan(const std::string & path);
+LaserScan RTABMAP_CORE_EXPORT loadScan(const std::string & path);
 
-RTABMAP_DEPRECATED(pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP loadCloud(
+// Use loadScan() instead.
+RTABMAP_DEPRECATED pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT loadCloud(
 		const std::string & path,
 		const Transform & transform = Transform::getIdentity(),
 		int downsampleStep = 1,
-		float voxelSize = 0.0f), "Use loadScan() instead.");
+		float voxelSize = 0.0f);
 
 } // namespace util3d
 } // namespace rtabmap
diff --git a/corelib/include/rtabmap/core/util3d_correspondences.h b/corelib/include/rtabmap/core/util3d_correspondences.h
index f73a59fb36..6bbaeb2d48 100644
--- a/corelib/include/rtabmap/core/util3d_correspondences.h
+++ b/corelib/include/rtabmap/core/util3d_correspondences.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_CORRESPONDENCES_H_
 #define UTIL3D_CORRESPONDENCES_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -44,12 +44,12 @@ namespace util3d
 {
 
 
-void RTABMAP_EXP findCorrespondences(
+void RTABMAP_CORE_EXPORT findCorrespondences(
 		const std::multimap<int, cv::KeyPoint> & wordsA,
 		const std::multimap<int, cv::KeyPoint> & wordsB,
 		std::list<std::pair<cv::Point2f, cv::Point2f> > & pairs);
 
-void RTABMAP_EXP findCorrespondences(
+void RTABMAP_CORE_EXPORT findCorrespondences(
 		const std::multimap<int, cv::Point3f> & words1,
 		const std::multimap<int, cv::Point3f> & words2,
 		std::vector<cv::Point3f> & inliers1,
@@ -57,7 +57,7 @@ void RTABMAP_EXP findCorrespondences(
 		float maxDepth,
 		std::vector<int> * uniqueCorrespondences = 0);
 
-void RTABMAP_EXP findCorrespondences(
+void RTABMAP_CORE_EXPORT findCorrespondences(
 		const std::map<int, cv::Point3f> & words1,
 		const std::map<int, cv::Point3f> & words2,
 		std::vector<cv::Point3f> & inliers1,
@@ -66,17 +66,17 @@ void RTABMAP_EXP findCorrespondences(
 		std::vector<int> * correspondences = 0);
 
 // remove depth by z axis
-void RTABMAP_EXP extractXYZCorrespondences(const std::multimap<int, pcl::PointXYZ> & words1,
+void RTABMAP_CORE_EXPORT extractXYZCorrespondences(const std::multimap<int, pcl::PointXYZ> & words1,
 									  const std::multimap<int, pcl::PointXYZ> & words2,
 									  pcl::PointCloud<pcl::PointXYZ> & cloud1,
 									  pcl::PointCloud<pcl::PointXYZ> & cloud2);
 
-void RTABMAP_EXP extractXYZCorrespondencesRANSAC(const std::multimap<int, pcl::PointXYZ> & words1,
+void RTABMAP_CORE_EXPORT extractXYZCorrespondencesRANSAC(const std::multimap<int, pcl::PointXYZ> & words1,
 									  const std::multimap<int, pcl::PointXYZ> & words2,
 									  pcl::PointCloud<pcl::PointXYZ> & cloud1,
 									  pcl::PointCloud<pcl::PointXYZ> & cloud2);
 
-void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
+void RTABMAP_CORE_EXPORT extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
 									   const cv::Mat & depthImage1,
 									   const cv::Mat & depthImage2,
 									   float cx, float cy,
@@ -85,23 +85,23 @@ void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f
 									   pcl::PointCloud<pcl::PointXYZ> & cloud1,
 									   pcl::PointCloud<pcl::PointXYZ> & cloud2);
 
-void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
+void RTABMAP_CORE_EXPORT extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
 							   const pcl::PointCloud<pcl::PointXYZ> & cloud1,
 							   const pcl::PointCloud<pcl::PointXYZ> & cloud2,
 							   pcl::PointCloud<pcl::PointXYZ> & inliers1,
 							   pcl::PointCloud<pcl::PointXYZ> & inliers2,
 							   char depthAxis);
-void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
+void RTABMAP_CORE_EXPORT extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
 							   const pcl::PointCloud<pcl::PointXYZRGB> & cloud1,
 							   const pcl::PointCloud<pcl::PointXYZRGB> & cloud2,
 							   pcl::PointCloud<pcl::PointXYZ> & inliers1,
 							   pcl::PointCloud<pcl::PointXYZ> & inliers2,
 							   char depthAxis);
 
-int RTABMAP_EXP countUniquePairs(const std::multimap<int, pcl::PointXYZ> & wordsA,
+int RTABMAP_CORE_EXPORT countUniquePairs(const std::multimap<int, pcl::PointXYZ> & wordsA,
 					 const std::multimap<int, pcl::PointXYZ> & wordsB);
 
-void RTABMAP_EXP filterMaxDepth(pcl::PointCloud<pcl::PointXYZ> & inliers1,
+void RTABMAP_CORE_EXPORT filterMaxDepth(pcl::PointCloud<pcl::PointXYZ> & inliers1,
 					pcl::PointCloud<pcl::PointXYZ> & inliers2,
 					float maxDepth,
 					char depthAxis,
diff --git a/corelib/include/rtabmap/core/util3d_features.h b/corelib/include/rtabmap/core/util3d_features.h
index 3f22cc12e8..2a02bf2eb7 100644
--- a/corelib/include/rtabmap/core/util3d_features.h
+++ b/corelib/include/rtabmap/core/util3d_features.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_FEATURES_H_
 #define UTIL3D_FEATURES_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <opencv2/calib3d/calib3d.hpp>
 #include <rtabmap/core/Transform.h>
@@ -44,28 +44,28 @@ namespace util3d
 {
 
 
-std::vector<cv::Point3f> RTABMAP_EXP generateKeypoints3DDepth(
+std::vector<cv::Point3f> RTABMAP_CORE_EXPORT generateKeypoints3DDepth(
 		const std::vector<cv::KeyPoint> & keypoints,
 		const cv::Mat & depth,
 		const CameraModel & cameraModel,
 		float minDepth = 0,
 		float maxDepth = 0);
 
-std::vector<cv::Point3f> RTABMAP_EXP generateKeypoints3DDepth(
+std::vector<cv::Point3f> RTABMAP_CORE_EXPORT generateKeypoints3DDepth(
 		const std::vector<cv::KeyPoint> & keypoints,
 		const cv::Mat & depth,
 		const std::vector<CameraModel> & cameraModels,
 		float minDepth = 0,
 		float maxDepth = 0);
 
-std::vector<cv::Point3f> RTABMAP_EXP generateKeypoints3DDisparity(
+std::vector<cv::Point3f> RTABMAP_CORE_EXPORT generateKeypoints3DDisparity(
 		const std::vector<cv::KeyPoint> & keypoints,
 		const cv::Mat & disparity,
 		const StereoCameraModel & stereoCameraModel,
 		float minDepth = 0,
 		float maxDepth = 0);
 
-std::vector<cv::Point3f> RTABMAP_EXP generateKeypoints3DStereo(
+std::vector<cv::Point3f> RTABMAP_CORE_EXPORT generateKeypoints3DStereo(
 		const std::vector<cv::Point2f> & leftCorners,
 		const std::vector<cv::Point2f> & rightCorners,
 		const StereoCameraModel & model,
@@ -73,7 +73,7 @@ std::vector<cv::Point3f> RTABMAP_EXP generateKeypoints3DStereo(
 		float minDepth = 0,
 		float maxDepth = 0);
 
-std::map<int, cv::Point3f> RTABMAP_EXP generateWords3DMono(
+std::map<int, cv::Point3f> RTABMAP_CORE_EXPORT generateWords3DMono(
 		const std::map<int, cv::KeyPoint> & kpts,
 		const std::map<int, cv::KeyPoint> & previousKpts,
 		const CameraModel & cameraModel,
@@ -84,7 +84,7 @@ std::map<int, cv::Point3f> RTABMAP_EXP generateWords3DMono(
 		double * variance = 0,
 		std::vector<int> * matchesOut = 0);
 
-std::multimap<int, cv::KeyPoint> RTABMAP_EXP aggregate(
+std::multimap<int, cv::KeyPoint> RTABMAP_CORE_EXPORT aggregate(
 		const std::list<int> & wordIds,
 		const std::vector<cv::KeyPoint> & keypoints);
 
diff --git a/corelib/include/rtabmap/core/util3d_filtering.h b/corelib/include/rtabmap/core/util3d_filtering.h
index 7c365f6409..977a3b91d3 100644
--- a/corelib/include/rtabmap/core/util3d_filtering.h
+++ b/corelib/include/rtabmap/core/util3d_filtering.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_FILTERING_H_
 #define UTIL3D_FILTERING_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 #include <rtabmap/core/Transform.h>
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -48,7 +48,7 @@ namespace util3d
  * operations like computing normals while the scan has already
  * normals and voxel filtering is not used.
  */
-LaserScan RTABMAP_EXP commonFiltering(
+LaserScan RTABMAP_CORE_EXPORT commonFiltering(
 		const LaserScan & scan,
 		int downsamplingStep,
 		float rangeMin = 0.0f,
@@ -57,7 +57,8 @@ LaserScan RTABMAP_EXP commonFiltering(
 		int normalK = 0,
 		float normalRadius = 0.0f,
 		float groundNormalsUp = 0.0f);
-RTABMAP_DEPRECATED(LaserScan RTABMAP_EXP commonFiltering(
+// Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp=0.8, otherwise set groundNormalsUp=0.0.
+RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT commonFiltering(
 		const LaserScan & scan,
 		int downsamplingStep,
 		float rangeMin,
@@ -65,75 +66,75 @@ RTABMAP_DEPRECATED(LaserScan RTABMAP_EXP commonFiltering(
 		float voxelSize,
 		int normalK,
 		float normalRadius,
-		bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp=0.8, otherwise set groundNormalsUp=0.0.");
+		bool forceGroundNormalsUp);
 
-LaserScan RTABMAP_EXP rangeFiltering(
+LaserScan RTABMAP_CORE_EXPORT rangeFiltering(
 		const LaserScan & scan,
 		float rangeMin,
 		float rangeMax);
 
-LaserScan RTABMAP_EXP downsample(
+LaserScan RTABMAP_CORE_EXPORT downsample(
 		const LaserScan & cloud,
 		int step);
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		int step);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		int step);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		int step);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		int step);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		int step);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP downsample(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT downsample(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		int step);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		float voxelSize);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		float voxelSize);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		float voxelSize);
 
@@ -157,185 +158,185 @@ inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
 }
 
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		int samples);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		int samples);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		int samples);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		int samples);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		int samples);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP randomSampling(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		int samples);
 
 
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP passThrough(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP passThrough(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const std::string & axis,
 		float min,
 		float max,
 		bool negative = false);
 
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PCLPointCloud2::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::IndicesPtr RTABMAP_EXP cropBox(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
 		const Transform & transform = Transform::getIdentity(),
 		bool negative = false);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP cropBox(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const Eigen::Vector4f & min,
 		const Eigen::Vector4f & max,
@@ -343,7 +344,7 @@ pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP cropBox(
 		bool negative = false);
 
 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
-pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT frustumFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & cameraPose,
@@ -353,7 +354,7 @@ pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
 		float farClipPlaneDistance,
 		bool negative = false);
 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT frustumFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const Transform & cameraPose,
 		float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
@@ -362,7 +363,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
 		float farClipPlaneDistance,
 		bool negative = false);
 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT frustumFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const Transform & cameraPose,
 		float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
@@ -372,48 +373,48 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
 		bool negative = false);
 
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
-pcl::PCLPointCloud2::Ptr RTABMAP_EXP removeNaNFromPointCloud(
+pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
 		const pcl::PCLPointCloud2::Ptr & cloud);
 
 
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
 
 /**
  * For convenience.
  */
 
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		float radiusSearch,
 		int minNeighborsInRadius);
@@ -430,69 +431,69 @@ pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
  * @return the indices of the points satisfying the parameters.
  */
 
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
-pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float radiusSearch,
 		int minNeighborsInRadius);
 
 /* for convenience */
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
@@ -511,42 +512,42 @@ pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
  * @return the indices of the points satisfying the parameters.
  */
 
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
 		const std::map<int, Transform> & viewpoints,
 		float factor=0.01f,
 		float neighborScale=2.0f);
-pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const std::vector<int> & viewpointIndices,
@@ -557,7 +558,7 @@ pcl::IndicesPtr RTABMAP_EXP proportionalRadiusFiltering(
 /**
  * For convenience.
  */
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
 		float radiusSearch,
@@ -572,7 +573,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
  * @param radiusSearch the radius in meter.
  * @return the indices of the points satisfying the parameters.
  */
-pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
@@ -583,7 +584,7 @@ pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
 /**
  * For convenience.
  */
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
 		float radiusSearch,
@@ -599,7 +600,7 @@ pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
  * @param radiusSearch the radius in meter.
  * @return the indices of the points satisfying the parameters.
  */
-pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
@@ -611,13 +612,13 @@ pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
 /**
  * For convenience.
  */
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP subtractFiltering(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
 		float radiusSearch,
 		float maxAngle = M_PI/4.0f,
 		int minNeighborsInRadius = 1);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
 		float radiusSearch,
@@ -633,7 +634,7 @@ pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
  * @param radiusSearch the radius in meter.
  * @return the indices of the points satisfying the parameters.
  */
-pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
@@ -641,7 +642,7 @@ pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
 		float radiusSearch,
 		float maxAngle = M_PI/4.0f,
 		int minNeighborsInRadius = 1);
-pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
@@ -659,7 +660,7 @@ pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
  * @param radiusSearchRatio the ratio used to compute the radius at different distances (e.g., a ratio of 0.1 at 4 m results in a radius of 4 cm).
  * @return the indices of the points satisfying the parameters.
  */
-pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractAdaptiveFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
@@ -677,7 +678,7 @@ pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
  * @param radiusSearchRatio the ratio used to compute the radius at different distances (e.g., a ratio of 0.01 at 4 m results in a radius of 4 cm).
  * @return the indices of the points satisfying the parameters.
  */
-pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractAdaptiveFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
@@ -692,14 +693,14 @@ pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
  * For convenience.
  */
 
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		float angleMax,
 		const Eigen::Vector4f & normal,
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float angleMax,
 		const Eigen::Vector4f & normal,
@@ -723,7 +724,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
  * @param viewpoint from which viewpoint the normals should be estimated (see pcl::NormalEstimation).
  * @return the indices of the points which respect the normal constraint.
  */
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -731,7 +732,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -739,7 +740,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -747,7 +748,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -755,7 +756,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -763,7 +764,7 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 		int normalKSearch,
 		const Eigen::Vector4f & viewpoint,
 		float groundNormalsUp = 0.0f);
-pcl::IndicesPtr RTABMAP_EXP normalFiltering(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float angleMax,
@@ -775,13 +776,13 @@ pcl::IndicesPtr RTABMAP_EXP normalFiltering(
 /**
  * For convenience.
  */
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float clusterTolerance,
 		int minClusterSize,
@@ -800,42 +801,42 @@ std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
  * @param biggestClusterIndex the index of the biggest cluster, if the clusters are empty, a negative index is set.
  * @return the indices of each cluster found.
  */
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
 		int minClusterSize,
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
-std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
+std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float clusterTolerance,
@@ -843,58 +844,58 @@ std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
 		int maxClusterSize = std::numeric_limits<int>::max(),
 		int * biggestClusterIndex = 0);
 
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
-pcl::IndicesPtr RTABMAP_EXP extractIndices(
+pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP extractIndices(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative,
 		bool keepOrganized);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP extractIndices(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative,
 		bool keepOrganized);
 // PCL default lacks of pcl::PointNormal type support
-//pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP extractIndices(
+//pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 //		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 //		const pcl::IndicesPtr & indices,
 //		bool negative,
 //		bool keepOrganized);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP extractIndices(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative,
 		bool keepOrganized);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP extractIndices(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative,
 		bool keepOrganized);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP extractIndices(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		bool negative,
diff --git a/corelib/include/rtabmap/core/util3d_mapping.h b/corelib/include/rtabmap/core/util3d_mapping.h
index 6ca8668df0..b1c865d7cd 100644
--- a/corelib/include/rtabmap/core/util3d_mapping.h
+++ b/corelib/include/rtabmap/core/util3d_mapping.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_MAPPING_H_
 #define UTIL3D_MAPPING_H_
 
-#include "rtabmap/core/RtabmapExp.h"
+#include "rtabmap/core/rtabmap_core_export.h"
 
 #include <opencv2/core/core.hpp>
 #include <map>
@@ -43,24 +43,26 @@ namespace rtabmap
 namespace util3d
 {
 
-RTABMAP_DEPRECATED(void RTABMAP_EXP occupancy2DFromLaserScan(
+// Use interface with \"viewpoint\" parameter to make sure the ray tracing origin is from the sensor and not the base.
+RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT occupancy2DFromLaserScan(
 		const cv::Mat & scan, // in /base_link frame
 		cv::Mat & empty,
 		cv::Mat & occupied,
 		float cellSize,
 		bool unknownSpaceFilled = false,
-		float scanMaxRange = 0.0f), "Use interface with \"viewpoint\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
+		float scanMaxRange = 0.0f);
 
-RTABMAP_DEPRECATED(void RTABMAP_EXP occupancy2DFromLaserScan(
+// Use interface with scanHit/scanNoHit parameters: scanNoHit set to null matrix has the same functionality than this method.
+RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT occupancy2DFromLaserScan(
 		const cv::Mat & scan, // in /base_link frame
 		const cv::Point3f & viewpoint, // /base_link -> /base_scan
 		cv::Mat & empty,
 		cv::Mat & occupied,
 		float cellSize,
 		bool unknownSpaceFilled = false,
-		float scanMaxRange = 0.0f), "Use interface with scanHit/scanNoHit parameters: scanNoHit set to null matrix has the same functionality than this method.");
+		float scanMaxRange = 0.0f);
 
-void RTABMAP_EXP occupancy2DFromLaserScan(
+void RTABMAP_CORE_EXPORT occupancy2DFromLaserScan(
 		const cv::Mat & scanHit, // in /base_link frame
 		const cv::Mat & scanNoHit, // in /base_link frame
 		const cv::Point3f & viewpoint, // /base_link -> /base_scan
@@ -70,7 +72,7 @@ void RTABMAP_EXP occupancy2DFromLaserScan(
 		bool unknownSpaceFilled = false,
 		float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
 
-cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps(
+cv::Mat RTABMAP_CORE_EXPORT create2DMapFromOccupancyLocalMaps(
 		const std::map<int, Transform> & poses,
 		const std::map<int, std::pair<cv::Mat, cv::Mat> > & occupancy,
 		float cellSize,
@@ -80,16 +82,18 @@ cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps(
 		bool erode = false,
 		float footprintRadius = 0.0f);
 
-RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
+// Use interface with \"viewpoints\" parameter to make sure the ray tracing origin is from the sensor and not the base.
+RTABMAP_DEPRECATED cv::Mat RTABMAP_CORE_EXPORT create2DMap(const std::map<int, Transform> & poses,
 		const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
 		float cellSize,
 		bool unknownSpaceFilled,
 		float & xMin,
 		float & yMin,
 		float minMapSize = 0.0f,
-		float scanMaxRange = 0.0f), "Use interface with \"viewpoints\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
+		float scanMaxRange = 0.0f);
 
-RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
+// Use interface with cv::Mat scans.
+RTABMAP_DEPRECATED cv::Mat RTABMAP_CORE_EXPORT create2DMap(const std::map<int, Transform> & poses,
 		const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
 		const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
 		float cellSize,
@@ -97,7 +101,7 @@ RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform
 		float & xMin,
 		float & yMin,
 		float minMapSize = 0.0f,
-		float scanMaxRange = 0.0f), "Use interface with cv::Mat scans.");
+		float scanMaxRange = 0.0f);
 
 /**
  * Create 2d Occupancy grid (CV_8S)
@@ -114,7 +118,7 @@ RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform
  * @param minMapSize minimum map size in meters
  * @param scanMaxRange laser scan maximum range, would be set if unknownSpaceFilled=true
  */
-cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
+cv::Mat RTABMAP_CORE_EXPORT create2DMap(const std::map<int, Transform> & poses,
 		const std::map<int, std::pair<cv::Mat, cv::Mat> > & scans, // <id, <hit, no hit> >, in /base_link frame
 		const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
 		float cellSize,
@@ -124,15 +128,15 @@ cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
 		float minMapSize = 0.0f,
 		float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
 
-void RTABMAP_EXP rayTrace(const cv::Point2i & start,
+void RTABMAP_CORE_EXPORT rayTrace(const cv::Point2i & start,
 		const cv::Point2i & end,
 		cv::Mat & grid,
 		bool stopOnObstacle);
 
-cv::Mat RTABMAP_EXP convertMap2Image8U(const cv::Mat & map8S, bool pgmFormat = false);
-cv::Mat RTABMAP_EXP convertImage8U2Map(const cv::Mat & map8U, bool pgmFormat = false);
+cv::Mat RTABMAP_CORE_EXPORT convertMap2Image8U(const cv::Mat & map8S, bool pgmFormat = false);
+cv::Mat RTABMAP_CORE_EXPORT convertImage8U2Map(const cv::Mat & map8U, bool pgmFormat = false);
 
-cv::Mat RTABMAP_EXP erodeMap(const cv::Mat & map);
+cv::Mat RTABMAP_CORE_EXPORT erodeMap(const cv::Mat & map);
 
 template<typename PointT>
 typename pcl::PointCloud<PointT>::Ptr projectCloudOnXYPlane(
diff --git a/corelib/include/rtabmap/core/util3d_motion_estimation.h b/corelib/include/rtabmap/core/util3d_motion_estimation.h
index 02cd15c988..e859c7ac69 100644
--- a/corelib/include/rtabmap/core/util3d_motion_estimation.h
+++ b/corelib/include/rtabmap/core/util3d_motion_estimation.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_MOTION_ESTIMATION_H_
 #define UTIL3D_MOTION_ESTIMATION_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <rtabmap/core/Transform.h>
 #include <rtabmap/core/CameraModel.h>
@@ -39,7 +39,7 @@ namespace rtabmap
 namespace util3d
 {
 
-Transform RTABMAP_EXP estimateMotion3DTo2D(
+Transform RTABMAP_CORE_EXPORT estimateMotion3DTo2D(
 			const std::map<int, cv::Point3f> & words3A,
 			const std::map<int, cv::KeyPoint> & words2B,
 			const CameraModel & cameraModel,
@@ -55,7 +55,7 @@ Transform RTABMAP_EXP estimateMotion3DTo2D(
 			std::vector<int> * matchesOut = 0,
 			std::vector<int> * inliersOut = 0);
 			
-Transform RTABMAP_EXP estimateMotion3DTo2D(
+Transform RTABMAP_CORE_EXPORT estimateMotion3DTo2D(
 			const std::map<int, cv::Point3f> & words3A,
 			const std::map<int, cv::KeyPoint> & words2B,
 			const std::vector<CameraModel> & cameraModels,
@@ -71,7 +71,7 @@ Transform RTABMAP_EXP estimateMotion3DTo2D(
 			std::vector<int> * matchesOut = 0,
 			std::vector<int> * inliersOut = 0);
 
-Transform RTABMAP_EXP estimateMotion3DTo3D(
+Transform RTABMAP_CORE_EXPORT estimateMotion3DTo3D(
 			const std::map<int, cv::Point3f> & words3A,
 			const std::map<int, cv::Point3f> & words3B,
 			int minInliers = 10,
@@ -82,7 +82,7 @@ Transform RTABMAP_EXP estimateMotion3DTo3D(
 			std::vector<int> * matchesOut = 0,
 			std::vector<int> * inliersOut = 0);
 
-void RTABMAP_EXP solvePnPRansac(
+void RTABMAP_CORE_EXPORT solvePnPRansac(
 		const std::vector<cv::Point3f> & objectPoints,
 		const std::vector<cv::Point2f> & imagePoints,
 		const cv::Mat & cameraMatrix,
diff --git a/corelib/include/rtabmap/core/util3d_registration.h b/corelib/include/rtabmap/core/util3d_registration.h
index 8c1d37d706..fa74801d58 100644
--- a/corelib/include/rtabmap/core/util3d_registration.h
+++ b/corelib/include/rtabmap/core/util3d_registration.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_REGISTRATION_H_
 #define UTIL3D_REGISTRATION_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -41,15 +41,15 @@ namespace rtabmap
 namespace util3d
 {
 
-int RTABMAP_EXP getCorrespondencesCount(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
+int RTABMAP_CORE_EXPORT getCorrespondencesCount(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
 							const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
 							float maxDistance);
 
-Transform RTABMAP_EXP transformFromXYZCorrespondencesSVD(
+Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondencesSVD(
 	const pcl::PointCloud<pcl::PointXYZ> & cloud1,
 	const pcl::PointCloud<pcl::PointXYZ> & cloud2);
 
-Transform RTABMAP_EXP transformFromXYZCorrespondences(
+Transform RTABMAP_CORE_EXPORT transformFromXYZCorrespondences(
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud1,
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud2,
 		double inlierThreshold = 0.02,
@@ -59,34 +59,34 @@ Transform RTABMAP_EXP transformFromXYZCorrespondences(
 		std::vector<int> * inliers = 0,
 		cv::Mat * variance = 0);
 
-void RTABMAP_EXP computeVarianceAndCorrespondences(
+void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
 		const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudA,
 		const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloudB,
 		double maxCorrespondenceDistance,
 		double maxCorrespondenceAngle, // <=0 means that we don't care about normal angle difference
 		double & variance,
 		int & correspondencesOut);
-void RTABMAP_EXP computeVarianceAndCorrespondences(
+void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
 		const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudA,
 		const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloudB,
 		double maxCorrespondenceDistance,
 		double maxCorrespondenceAngle, // <=0 means that we don't care about normal angle difference
 		double & variance,
 		int & correspondencesOut);
-void RTABMAP_EXP computeVarianceAndCorrespondences(
+void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudA,
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloudB,
 		double maxCorrespondenceDistance,
 		double & variance,
 		int & correspondencesOut);
-void RTABMAP_EXP computeVarianceAndCorrespondences(
+void RTABMAP_CORE_EXPORT computeVarianceAndCorrespondences(
 		const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudA,
 		const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloudB,
 		double maxCorrespondenceDistance,
 		double & variance,
 		int & correspondencesOut);
 
-Transform RTABMAP_EXP icp(
+Transform RTABMAP_CORE_EXPORT icp(
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_source,
 		const pcl::PointCloud<pcl::PointXYZ>::ConstPtr & cloud_target,
 		double maxCorrespondenceDistance,
@@ -95,7 +95,7 @@ Transform RTABMAP_EXP icp(
 		pcl::PointCloud<pcl::PointXYZ> & cloud_source_registered,
 		float epsilon = 0.0f,
 		bool icp2D = false);
-Transform RTABMAP_EXP icp(
+Transform RTABMAP_CORE_EXPORT icp(
 		const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_source,
 		const pcl::PointCloud<pcl::PointXYZI>::ConstPtr & cloud_target,
 		double maxCorrespondenceDistance,
@@ -105,7 +105,7 @@ Transform RTABMAP_EXP icp(
 		float epsilon = 0.0f,
 		bool icp2D = false);
 
-Transform RTABMAP_EXP icpPointToPlane(
+Transform RTABMAP_CORE_EXPORT icpPointToPlane(
 		const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_source,
 		const pcl::PointCloud<pcl::PointNormal>::ConstPtr & cloud_target,
 		double maxCorrespondenceDistance,
@@ -114,7 +114,7 @@ Transform RTABMAP_EXP icpPointToPlane(
 		pcl::PointCloud<pcl::PointNormal> & cloud_source_registered,
 		float epsilon = 0.0f,
 		bool icp2D = false);
-Transform RTABMAP_EXP icpPointToPlane(
+Transform RTABMAP_CORE_EXPORT icpPointToPlane(
 		const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_source,
 		const pcl::PointCloud<pcl::PointXYZINormal>::ConstPtr & cloud_target,
 		double maxCorrespondenceDistance,
diff --git a/corelib/include/rtabmap/core/util3d_surface.h b/corelib/include/rtabmap/core/util3d_surface.h
index 4068129751..080cd8b7e1 100644
--- a/corelib/include/rtabmap/core/util3d_surface.h
+++ b/corelib/include/rtabmap/core/util3d_surface.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_SURFACE_H_
 #define UTIL3D_SURFACE_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <pcl/PolygonMesh.h>
 #include <pcl/point_cloud.h>
@@ -61,74 +61,74 @@ namespace util3d
  * @param neighborPolygons returned index from polygons to neighbor polygons (index size = polygons size).
  * @param vertexPolygons returned index from vertices to polygons (index size = cloudSize).
  */
-void RTABMAP_EXP createPolygonIndexes(
+void RTABMAP_CORE_EXPORT createPolygonIndexes(
 		const std::vector<pcl::Vertices> & polygons,
 		int cloudSize,
 		std::vector<std::set<int> > & neighborPolygons,
 		std::vector<std::set<int> > & vertexPolygons);
 
-std::list<std::list<int> > RTABMAP_EXP clusterPolygons(
+std::list<std::list<int> > RTABMAP_CORE_EXPORT clusterPolygons(
 		const std::vector<std::set<int> > & neighborPolygons,
 		int minClusterSize = 0);
 
-std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		double angleTolerance,
 		bool quad,
 		int trianglePixelSize,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
-std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		double angleTolerance = M_PI/16,
 		bool quad=true,
 		int trianglePixelSize = 2,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
-std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		double angleTolerance = M_PI/16,
 		bool quad=true,
 		int trianglePixelSize = 2,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
 
-void RTABMAP_EXP appendMesh(
+void RTABMAP_CORE_EXPORT appendMesh(
 		pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
 		std::vector<pcl::Vertices> & polygonsA,
 		const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
 		const std::vector<pcl::Vertices> & polygonsB);
-void RTABMAP_EXP appendMesh(
+void RTABMAP_CORE_EXPORT appendMesh(
 		pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
 		std::vector<pcl::Vertices> & polygonsA,
 		const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
 		const std::vector<pcl::Vertices> & polygonsB);
 
 // return map from new to old polygon indices
-std::vector<int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
+std::vector<int> RTABMAP_CORE_EXPORT filterNotUsedVerticesFromMesh(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
 		const std::vector<pcl::Vertices> & polygons,
 		pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
 		std::vector<pcl::Vertices> & outputPolygons);
-std::vector<int> RTABMAP_EXP filterNotUsedVerticesFromMesh(
+std::vector<int> RTABMAP_CORE_EXPORT filterNotUsedVerticesFromMesh(
 		const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
 		const std::vector<pcl::Vertices> & polygons,
 		pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
 		std::vector<pcl::Vertices> & outputPolygons);
-std::vector<int> RTABMAP_EXP filterNaNPointsFromMesh(
+std::vector<int> RTABMAP_CORE_EXPORT filterNaNPointsFromMesh(
 		const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
 		const std::vector<pcl::Vertices> & polygons,
 		pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
 		std::vector<pcl::Vertices> & outputPolygons);
 
-std::vector<pcl::Vertices> RTABMAP_EXP filterCloseVerticesFromMesh(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT filterCloseVerticesFromMesh(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
 		const std::vector<pcl::Vertices> & polygons,
 		float radius,
 		float angle,
 		bool keepLatestInRadius);
 
-std::vector<pcl::Vertices> RTABMAP_EXP filterInvalidPolygons(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT filterInvalidPolygons(
 		const std::vector<pcl::Vertices> & polygons);
 
-pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(
+pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT createMesh(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
 		float gp3SearchRadius = 0.025,
 		float gp3Mu = 2.5,
@@ -138,7 +138,7 @@ pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(
 		float gp3MaximumAngle = 2*M_PI/3,
 		bool gp3NormalConsistency = true);
 
-pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
+pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT createTextureMesh(
 		const pcl::PolygonMesh::Ptr & mesh,
 		const std::map<int, Transform> & poses,
 		const std::map<int, CameraModel> & cameraModels,
@@ -151,7 +151,7 @@ pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
 		const ProgressState * state = 0,
 		std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0, // For each point, we have a list of cameras with corresponding pixel in it. Beware that the camera ids don't correspond to pose ids, they are indexes from 0 to total camera models and texture's materials.
 		bool distanceToCamPolicy = false);
-pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
+pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT createTextureMesh(
 		const pcl::PolygonMesh::Ptr & mesh,
 		const std::map<int, Transform> & poses,
 		const std::map<int, std::vector<CameraModel> > & cameraModels,
@@ -168,26 +168,26 @@ pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
 /**
  * Remove not textured polygon clusters. If minClusterSize<0, only the largest cluster is kept.
  */
-void RTABMAP_EXP cleanTextureMesh(
+void RTABMAP_CORE_EXPORT cleanTextureMesh(
 		pcl::TextureMesh & textureMesh,
 		int minClusterSize);
 
-pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(
+pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT concatenateTextureMeshes(
 		const std::list<pcl::TextureMesh::Ptr> & meshes);
 
-void RTABMAP_EXP concatenateTextureMaterials(
+void RTABMAP_CORE_EXPORT concatenateTextureMaterials(
 		pcl::TextureMesh & mesh, const cv::Size & imageSize, int textureSize, int maxTextures, float & scale, std::vector<bool> * materialsKept=0);
 
-std::vector<std::vector<RTABMAP_PCL_INDEX> > RTABMAP_EXP convertPolygonsFromPCL(
+std::vector<std::vector<RTABMAP_PCL_INDEX> > RTABMAP_CORE_EXPORT convertPolygonsFromPCL(
 		const std::vector<pcl::Vertices> & polygons);
-std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > RTABMAP_EXP convertPolygonsFromPCL(
+std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > RTABMAP_CORE_EXPORT convertPolygonsFromPCL(
 		const std::vector<std::vector<pcl::Vertices> > & polygons);
-std::vector<pcl::Vertices> RTABMAP_EXP convertPolygonsToPCL(
+std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT convertPolygonsToPCL(
 		const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
-std::vector<std::vector<pcl::Vertices> > RTABMAP_EXP convertPolygonsToPCL(
+std::vector<std::vector<pcl::Vertices> > RTABMAP_CORE_EXPORT convertPolygonsToPCL(
 		const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & tex_polygons);
 
-pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(
+pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT assembleTextureMesh(
 		const cv::Mat & cloudMat,
 		const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
@@ -198,7 +198,7 @@ pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(
 		cv::Mat & textures,
 		bool mergeTextures = false);
 
-pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(
+pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT assemblePolygonMesh(
 		const cv::Mat & cloudMat,
 		const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
 
@@ -206,7 +206,7 @@ pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(
  * Merge all textures in the mesh into "textureCount" textures of size "textureSize".
  * @return merged textures corresponding to new materials set in TextureMesh (height=textureSize, width=textureSize*materials)
  */
-cv::Mat RTABMAP_EXP mergeTextures(
+cv::Mat RTABMAP_CORE_EXPORT mergeTextures(
 		pcl::TextureMesh & mesh,
 		const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
 		const std::map<int, CameraModel> & calibrations, // Should match images
@@ -228,7 +228,7 @@ cv::Mat RTABMAP_EXP mergeTextures(
 		std::map<int, std::map<int, cv::Vec4d> > * gains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains Gray-R-G-B>
 		std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
 		std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
-cv::Mat RTABMAP_EXP mergeTextures(
+cv::Mat RTABMAP_CORE_EXPORT mergeTextures(
 		pcl::TextureMesh & mesh,
 		const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
 		const std::map<int, std::vector<CameraModel> > & calibrations, // Should match images
@@ -251,9 +251,10 @@ cv::Mat RTABMAP_EXP mergeTextures(
 		std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
 		std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
 
-void RTABMAP_EXP fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
+void RTABMAP_CORE_EXPORT fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
 
-RTABMAP_DEPRECATED(bool RTABMAP_EXP multiBandTexturing(
+// Use the same method with 22 parameters instead.
+RTABMAP_DEPRECATED bool RTABMAP_CORE_EXPORT multiBandTexturing(
 		const std::string & outputOBJPath,
 		const pcl::PCLPointCloud2 & cloud,
 		const std::vector<pcl::Vertices> & polygons,
@@ -268,7 +269,7 @@ RTABMAP_DEPRECATED(bool RTABMAP_EXP multiBandTexturing(
 		const std::map<int, std::map<int, cv::Vec4d> > & gains = std::map<int, std::map<int, cv::Vec4d> >(),       // optional output of util3d::mergeTextures()
 		const std::map<int, std::map<int, cv::Mat> > & blendingGains = std::map<int, std::map<int, cv::Mat> >(),   // optional output of util3d::mergeTextures()
 		const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),                             // optional output of util3d::mergeTextures()
-		bool gainRGB = true), "Use the same method with 22 parameters instead.");
+		bool gainRGB = true);
 
 /**
  * Texture mesh with AliceVision's multiband texturing approach. See also https://meshroom-manual.readthedocs.io/en/bibtex1/node-reference/nodes/Texturing.html.
@@ -296,7 +297,7 @@ RTABMAP_DEPRECATED(bool RTABMAP_EXP multiBandTexturing(
  * @param angleHardThreshold 0.0 to disable angle hard threshold filtering (0.0, 180.0).
  * @param forceVisibleByAllVertices Triangle visibility is based on the union of vertices visibility.
  */
-bool RTABMAP_EXP multiBandTexturing(
+bool RTABMAP_CORE_EXPORT multiBandTexturing(
 		const std::string & outputOBJPath,
 		const pcl::PCLPointCloud2 & cloud,
 		const std::vector<pcl::Vertices> & polygons,
@@ -321,108 +322,108 @@ bool RTABMAP_EXP multiBandTexturing(
 		double angleHardThreshold = 90.0,
 		bool forceVisibleByAllVertices = false);
 
-cv::Mat RTABMAP_EXP computeNormals(
+cv::Mat RTABMAP_CORE_EXPORT computeNormals(
 		const cv::Mat & laserScan,
 		int searchK,
 		float searchRadius);
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		int searchK = 20,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
 
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		int searchK = 5,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		int searchK = 5,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		int searchK = 5,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		int searchK = 5,
 		float searchRadius = 0.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
 
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float maxDepthChangeFactor = 0.02f,
 		float normalSmoothingSize = 10.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
-pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
+pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float maxDepthChangeFactor = 0.02f,
 		float normalSmoothingSize = 10.0f,
 		const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
 
-float RTABMAP_EXP computeNormalsComplexity(
+float RTABMAP_CORE_EXPORT computeNormalsComplexity(
 		const LaserScan & scan,
 		const Transform & t = Transform::getIdentity(),
 		cv::Mat * pcaEigenVectors = 0,
 		cv::Mat * pcaEigenValues = 0);
-float RTABMAP_EXP computeNormalsComplexity(
+float RTABMAP_CORE_EXPORT computeNormalsComplexity(
 		const pcl::PointCloud<pcl::Normal> & normals,
 		const Transform & t = Transform::getIdentity(),
 		bool is2d = false,
 		cv::Mat * pcaEigenVectors = 0,
 		cv::Mat * pcaEigenValues = 0);
-float RTABMAP_EXP computeNormalsComplexity(
+float RTABMAP_CORE_EXPORT computeNormalsComplexity(
 		const pcl::PointCloud<pcl::PointNormal> & cloud,
 		const Transform & t = Transform::getIdentity(),
 		bool is2d = false,
 		cv::Mat * pcaEigenVectors = 0,
 		cv::Mat * pcaEigenValues = 0);
-float RTABMAP_EXP computeNormalsComplexity(
+float RTABMAP_CORE_EXPORT computeNormalsComplexity(
 		const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
 		const Transform & t = Transform::getIdentity(),
 		bool is2d = false,
 		cv::Mat * pcaEigenVectors = 0,
 		cv::Mat * pcaEigenValues = 0);
-float RTABMAP_EXP computeNormalsComplexity(
+float RTABMAP_CORE_EXPORT computeNormalsComplexity(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
 		const Transform & t = Transform::getIdentity(),
 		bool is2d = false,
 		cv::Mat * pcaEigenVectors = 0,
 		cv::Mat * pcaEigenValues = 0);
 
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT mls(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		float searchRadius = 0.0f,
 		int polygonialOrder = 2,
@@ -432,7 +433,7 @@ pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
 		int pointDensity = 0,            // RANDOM_UNIFORM_DENSITY
 		float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
 		int dilationIterations = 0);     // VOXEL_GRID_DILATION
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT mls(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		float searchRadius = 0.0f,
@@ -444,66 +445,70 @@ pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
 		float dilationVoxelSize = 1.0f,  // VOXEL_GRID_DILATION
 		int dilationIterations = 0);     // VOXEL_GRID_DILATION
 
-RTABMAP_DEPRECATED(LaserScan RTABMAP_EXP adjustNormalsToViewPoint(
+// Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
+RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		const LaserScan & scan,
 		const Eigen::Vector3f & viewpoint,
-		bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
-LaserScan RTABMAP_EXP adjustNormalsToViewPoint(
+		bool forceGroundNormalsUp);
+LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		const LaserScan & scan,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
 		float groundNormalsUp = 0.0f);
-RTABMAP_DEPRECATED(void RTABMAP_EXP adjustNormalsToViewPoint(
+// Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
+RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint,
-		bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
-void RTABMAP_EXP adjustNormalsToViewPoint(
+		bool forceGroundNormalsUp);
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
 		float groundNormalsUp = 0.0f);
-RTABMAP_DEPRECATED(void RTABMAP_EXP adjustNormalsToViewPoint(
+// Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
+RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint,
-		bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
-void RTABMAP_EXP adjustNormalsToViewPoint(
+		bool forceGroundNormalsUp);
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
 		float groundNormalsUp = 0.0f);
-RTABMAP_DEPRECATED(void RTABMAP_EXP adjustNormalsToViewPoint(
+// Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
+RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint,
-		bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
-void RTABMAP_EXP adjustNormalsToViewPoint(
+		bool forceGroundNormalsUp);
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
 		pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
 		float groundNormalsUp = 0.0f);
 
-void RTABMAP_EXP adjustNormalsToViewPoints(
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
 		const std::map<int, Transform> & poses,
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
 		const std::vector<int> & rawCameraIndices,
 		pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		float groundNormalsUp = 0.0f);
-void RTABMAP_EXP adjustNormalsToViewPoints(
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
 		const std::map<int, Transform> & poses,
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
 		const std::vector<int> & rawCameraIndices,
 		pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		float groundNormalsUp = 0.0f);
-void RTABMAP_EXP adjustNormalsToViewPoints(
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
 		const std::map<int, Transform> & poses,
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
 		const std::vector<int> & rawCameraIndices,
 		pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		float groundNormalsUp = 0.0f);
 
-void RTABMAP_EXP adjustNormalsToViewPoints(
+void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
 		const std::map<int, Transform> & viewpoints,
 		const LaserScan & rawScan,
 		const std::vector<int> & viewpointIds,
 		LaserScan & scan,
 		float groundNormalsUp = 0.0f);
 
-pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
+pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
 
 template<typename pointT>
 std::vector<pcl::Vertices> normalizePolygonsSide(
@@ -545,7 +550,7 @@ void denseMeshPostProcessing(
  *
  *   Mathieu:  Adapted for PCL format
  */
-bool RTABMAP_EXP intersectRayTriangle(
+bool RTABMAP_CORE_EXPORT intersectRayTriangle(
 		const Eigen::Vector3f & p,
 		const Eigen::Vector3f & dir,
 		const Eigen::Vector3f & v0,
diff --git a/corelib/include/rtabmap/core/util3d_transforms.h b/corelib/include/rtabmap/core/util3d_transforms.h
index 20f02b8570..cf66753f03 100644
--- a/corelib/include/rtabmap/core/util3d_transforms.h
+++ b/corelib/include/rtabmap/core/util3d_transforms.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef UTIL3D_TRANSFORMS_H_
 #define UTIL3D_TRANSFORMS_H_
 
-#include <rtabmap/core/RtabmapExp.h>
+#include <rtabmap/core/rtabmap_core_export.h>
 
 #include <pcl/point_cloud.h>
 #include <pcl/point_types.h>
@@ -42,76 +42,76 @@ namespace rtabmap
 namespace util3d
 {
 
-LaserScan RTABMAP_EXP transformLaserScan(
+LaserScan RTABMAP_CORE_EXPORT transformLaserScan(
 		const LaserScan & laserScan,
 		const Transform & transform);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const Transform & transform);
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
-pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP transformPointCloud(
+pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT transformPointCloud(
 		const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
 		const pcl::IndicesPtr & indices,
 		const Transform & transform);
 
-cv::Point3f RTABMAP_EXP transformPoint(
+cv::Point3f RTABMAP_CORE_EXPORT transformPoint(
 		const cv::Point3f & pt,
 		const Transform & transform);
-cv::Point3d RTABMAP_EXP transformPoint(
+cv::Point3d RTABMAP_CORE_EXPORT transformPoint(
 		const cv::Point3d & pt,
 		const Transform & transform);
-pcl::PointXYZ RTABMAP_EXP transformPoint(
+pcl::PointXYZ RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointXYZ & pt,
 		const Transform & transform);
-pcl::PointXYZI RTABMAP_EXP transformPoint(
+pcl::PointXYZI RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointXYZI & pt,
 		const Transform & transform);
-pcl::PointXYZRGB RTABMAP_EXP transformPoint(
+pcl::PointXYZRGB RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointXYZRGB & pt,
 		const Transform & transform);
-pcl::PointNormal RTABMAP_EXP transformPoint(
+pcl::PointNormal RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointNormal & point,
 		const Transform & transform);
-pcl::PointXYZRGBNormal RTABMAP_EXP transformPoint(
+pcl::PointXYZRGBNormal RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointXYZRGBNormal & point,
 		const Transform & transform);
-pcl::PointXYZINormal RTABMAP_EXP transformPoint(
+pcl::PointXYZINormal RTABMAP_CORE_EXPORT transformPoint(
 		const pcl::PointXYZINormal & point,
 		const Transform & transform);
 
diff --git a/corelib/src/CMakeLists.txt b/corelib/src/CMakeLists.txt
index 956f9a6e94..965dbebfc9 100644
--- a/corelib/src/CMakeLists.txt
+++ b/corelib/src/CMakeLists.txt
@@ -143,20 +143,29 @@ IF(MSVC)
 ENDIF(MSVC)
 
 SET(INCLUDE_DIRS
-    ${CMAKE_CURRENT_BINARY_DIR}/../include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${CMAKE_CURRENT_SOURCE_DIR}/../include
-	${CMAKE_CURRENT_SOURCE_DIR}
-	${CMAKE_CURRENT_BINARY_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-	${PCL_INCLUDE_DIRS}
+    ${CMAKE_CURRENT_SOURCE_DIR}
+    ${CMAKE_CURRENT_SOURCE_DIR}/../include
+    ${CMAKE_CURRENT_BINARY_DIR}
+    ${CMAKE_CURRENT_BINARY_DIR}/include
 	${ZLIB_INCLUDE_DIRS}
 )
 
+SET(PUBLIC_INCLUDE_DIRS
+ 	${OpenCV_INCLUDE_DIRS}
+ 	${PCL_INCLUDE_DIRS}
+)
+
 SET(LIBRARIES
-	${OpenCV_LIBS} 
-	${PCL_LIBRARIES} 
-	${ZLIB_LIBRARIES} 
+	${ZLIB_LIBRARIES}
+)
+
+# Issue that qhull dependency uses optimized and debug keywords,
+# which are converted to \$<\$<NOT:\$<CONFIG:DEBUG>> and \$<\$<CONFIG:DEBUG>
+# in RTABMap_coreTargets.cmake (not sure why?!).
+list(REMOVE_ITEM PCL_LIBRARIES "debug" "optimized")
+SET(PUBLIC_LIBRARIES
+	${OpenCV_LIBS}
+	${PCL_LIBRARIES}
 )
 
 IF(Sqlite3_FOUND)
@@ -264,18 +273,18 @@ IF(KinectSDK2_FOUND)
 ENDIF(KinectSDK2_FOUND)
 
 IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
+	SET(PUBLIC_INCLUDE_DIRS
+		${PUBLIC_INCLUDE_DIRS}
 		${k4a_INCLUDE_DIRS}
 	)
 	IF(WIN32)
-	    SET(LIBRARIES
-			${LIBRARIES}
+	    SET(PUBLIC_LIBRARIES
+			${PUBLIC_LIBRARIES}
 			${k4a_LIBRARIES}
 		)
 	ELSE()
-		SET(LIBRARIES
-			${LIBRARIES}
+		SET(PUBLIC_LIBRARIES
+			${PUBLIC_LIBRARIES}
 			k4a::k4a 
 			k4a::k4arecord
 		)
@@ -294,23 +303,23 @@ IF(RealSense_FOUND)
 ENDIF(RealSense_FOUND)
 
 IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
+	SET(PUBLIC_INCLUDE_DIRS
+		${PUBLIC_INCLUDE_DIRS}
 		${realsense2_INCLUDE_DIRS}
 	)
 	IF(WIN32)
-	    SET(LIBRARIES
-			${LIBRARIES}
+	    SET(PUBLIC_LIBRARIES
+			${PUBLIC_LIBRARIES}
 			${RealSense2_LIBRARIES}
 		)
 	ELSEIF(APPLE)
-	    SET(LIBRARIES
-			${LIBRARIES}
+	    SET(PUBLIC_LIBRARIES
+			${PUBLIC_LIBRARIES}
 			${realsense2_LIBRARIES}
 		)
 	ELSE()
-		SET(LIBRARIES
-			${LIBRARIES}
+		SET(PUBLIC_LIBRARIES
+			${PUBLIC_LIBRARIES}
 			realsense2::realsense2 # target
 		)
 	ENDIF()
@@ -387,7 +396,7 @@ IF(G2O_FOUND)
           g2o::csparse_extension)
       ENDIF(TARGET g2o::solver_csparse)
       IF(TARGET g2o::solver_cholmod)
-        SET(LIBRARIES ${LIBRARIES} 
+        SET(LIBRARIES ${LIBRARIES}
           g2o::solver_cholmod)
       ENDIF(TARGET g2o::solver_cholmod)
 	ELSE()
@@ -559,12 +568,12 @@ IF(ZEDOC_FOUND)
 ENDIF(ZEDOC_FOUND)
 
 IF(octomap_FOUND)
-    SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
+    SET(PUBLIC_INCLUDE_DIRS
+		${PUBLIC_INCLUDE_DIRS}
 		${OCTOMAP_INCLUDE_DIRS}
 	)
-	SET(LIBRARIES
-		${LIBRARIES}
+	SET(PUBLIC_LIBRARIES
+		${PUBLIC_LIBRARIES}
 		${OCTOMAP_LIBRARIES}
 	)
 	SET(SRC_FILES
@@ -752,7 +761,20 @@ INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 # Add binary that is built from the source file "main.cpp".
 # The extension is automatically found.
 ADD_LIBRARY(rtabmap_core ${SRC_FILES} ${RESOURCES_HEADERS})
-TARGET_LINK_LIBRARIES(rtabmap_core rtabmap_utilite ${LIBRARIES})
+
+generate_export_header(rtabmap_core
+ DEPRECATED_MACRO_NAME RTABMAP_DEPRECATED)
+
+target_include_directories(rtabmap_core PUBLIC 
+  "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../include;${CMAKE_CURRENT_BINARY_DIR}/include;${PUBLIC_INCLUDE_DIRS}>"
+  "$<INSTALL_INTERFACE:${INSTALL_INCLUDE_DIR};${PUBLIC_INCLUDE_DIRS}>")
+  
+TARGET_LINK_LIBRARIES(rtabmap_core 
+  PUBLIC 
+    rtabmap_utilite 
+    ${PUBLIC_LIBRARIES}
+  PRIVATE 
+    ${LIBRARIES})
 
 SET_TARGET_PROPERTIES(
      rtabmap_core
@@ -761,21 +783,37 @@ SET_TARGET_PROPERTIES(
      SOVERSION ${RTABMAP_MAJOR_VERSION}.${RTABMAP_MINOR_VERSION}
 )
 
-INSTALL(TARGETS rtabmap_core
+INSTALL(TARGETS rtabmap_core EXPORT rtabmap_coreTargets
         RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" COMPONENT runtime
         LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel
         ARCHIVE DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel)
-		
-install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/../include/ 
-		DESTINATION "${INSTALL_INCLUDE_DIR}"
-		COMPONENT devel 
-		FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" 
-		PATTERN ".svn" EXCLUDE)
-		
-# For generated Version.h
-install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/../include/ 
-        DESTINATION "${INSTALL_INCLUDE_DIR}"
-        COMPONENT devel 
-        FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" 
-        PATTERN ".svn" EXCLUDE)
+        
+configure_file(
+  ${CMAKE_CURRENT_BINARY_DIR}/rtabmap_core_export.h
+  ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}/core/rtabmap_core_export.h
+  COPYONLY)
+  
+install(
+  DIRECTORY
+    ${CMAKE_CURRENT_SOURCE_DIR}/../include/${PROJECT_PREFIX}
+    ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}
+  DESTINATION
+    ${INSTALL_INCLUDE_DIR}
+  COMPONENT
+    devel
+  FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp"
+)
+
+export(EXPORT rtabmap_coreTargets
+  FILE "${CMAKE_CURRENT_BINARY_DIR}/../../${PROJECT_NAME}_coreTargets.cmake"
+)
 
+install(EXPORT rtabmap_coreTargets
+  FILE
+    ${PROJECT_NAME}_coreTargets.cmake
+  DESTINATION
+    ${INSTALL_CMAKE_DIR}
+  COMPONENT
+    devel
+)
+	
diff --git a/corelib/src/Graph.cpp b/corelib/src/Graph.cpp
index a9a645d8ae..ebf92f28aa 100644
--- a/corelib/src/Graph.cpp
+++ b/corelib/src/Graph.cpp
@@ -1761,7 +1761,7 @@ std::list<std::pair<int, Transform> > computePath(
 }
 
 // Dijksta
-std::list<int> RTABMAP_EXP computePath(
+std::list<int> computePath(
 			const std::multimap<int, Link> & links,
 			int from,
 			int to,
diff --git a/corelib/src/Statistics.cpp b/corelib/src/Statistics.cpp
index 57bcb29cbc..016e9ca179 100644
--- a/corelib/src/Statistics.cpp
+++ b/corelib/src/Statistics.cpp
@@ -25,7 +25,7 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#include "rtabmap/core/Statistics.h"
+#include <rtabmap/core/Statistics.h>
 #include <rtabmap/utilite/UStl.h>
 #include <rtabmap/utilite/UConversion.h>
 
diff --git a/corelib/src/util3d.cpp b/corelib/src/util3d.cpp
index 8421f078a5..ecbed214ce 100644
--- a/corelib/src/util3d.cpp
+++ b/corelib/src/util3d.cpp
@@ -850,7 +850,7 @@ pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudFromStereoImages(
 			validIndices);
 }
 
-pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
+pcl::PointCloud<pcl::PointXYZ>::Ptr cloudFromSensorData(
 		const SensorData & sensorData,
 		int decimation,
 		float maxDepth,
@@ -1053,7 +1053,7 @@ pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cloudFromSensorData(
 	return cloud;
 }
 
-pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cloudRGBFromSensorData(
+pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBFromSensorData(
 		const SensorData & sensorData,
 		int decimation,
 		float maxDepth,
diff --git a/corelib/src/util3d_filtering.cpp b/corelib/src/util3d_filtering.cpp
index fb61deca13..c32ffb304c 100644
--- a/corelib/src/util3d_filtering.cpp
+++ b/corelib/src/util3d_filtering.cpp
@@ -1002,7 +1002,7 @@ pcl::PointCloud<pcl::PointXYZI>::Ptr removeNaNFromPointCloud(const pcl::PointClo
 	return removeNaNFromPointCloudImpl<pcl::PointXYZI>(cloud);
 }
 
-pcl::PCLPointCloud2::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PCLPointCloud2::Ptr & cloud)
+pcl::PCLPointCloud2::Ptr removeNaNFromPointCloud(const pcl::PCLPointCloud2::Ptr & cloud)
 {
 	pcl::PCLPointCloud2::Ptr output(new pcl::PCLPointCloud2);
 	output->fields = cloud->fields;
diff --git a/examples/BOWMapping/CMakeLists.txt b/examples/BOWMapping/CMakeLists.txt
index 0aaab05d0c..17e9de9b75 100644
--- a/examples/BOWMapping/CMakeLists.txt
+++ b/examples/BOWMapping/CMakeLists.txt
@@ -4,46 +4,15 @@ IF(DEFINED PROJECT_NAME)
    set(internal TRUE)
 ENDIF(DEFINED PROJECT_NAME)
 
-if(internal)
-	# inside rtabmap project (see below for external build)
-	SET(RTABMap_INCLUDE_DIRS 
-	    ${PROJECT_BINARY_DIR}/corelib/include
-	    ${PROJECT_SOURCE_DIR}/utilite/include
-		${PROJECT_SOURCE_DIR}/corelib/include
-	)
-	SET(RTABMap_LIBRARIES 
-	    rtabmap_core
-		rtabmap_utilite
-	)  
-else()
+if(NOT internal)
 	# external build
 	PROJECT( MyProject )
 	
 	FIND_PACKAGE(RTABMap REQUIRED)
-	FIND_PACKAGE(OpenCV REQUIRED)
-	FIND_PACKAGE(PCL 1.7 REQUIRED)
-endif()
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
 endif()
 
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-    ${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(bow_mapping main.cpp)
-TARGET_LINK_LIBRARIES(bow_mapping ${LIBRARIES})
+TARGET_LINK_LIBRARIES(bow_mapping rtabmap)
 
 if(internal)
   SET_TARGET_PROPERTIES( bow_mapping 
diff --git a/examples/NoEventsExample/CMakeLists.txt b/examples/NoEventsExample/CMakeLists.txt
index a1ea87d1fb..08fb583bd3 100644
--- a/examples/NoEventsExample/CMakeLists.txt
+++ b/examples/NoEventsExample/CMakeLists.txt
@@ -4,57 +4,13 @@ IF(DEFINED PROJECT_NAME)
    set(internal TRUE)
 ENDIF(DEFINED PROJECT_NAME)
 
-if(internal)
-	# inside rtabmap project (see below for external build)
-	SET(RTABMap_INCLUDE_DIRS 
-	    ${PROJECT_BINARY_DIR}/corelib/include
-	    ${PROJECT_SOURCE_DIR}/utilite/include
-		${PROJECT_SOURCE_DIR}/corelib/include
-		${PROJECT_SOURCE_DIR}/guilib/include
-	)
-	SET(RTABMap_LIBRARIES 
-	    rtabmap_core
-		rtabmap_gui
-		rtabmap_utilite
-	)  
-else()
+if(NOT internal)
 	# external build
 	PROJECT( MyProject )
 	
-	FIND_PACKAGE(RTABMap REQUIRED)
-	FIND_PACKAGE(OpenCV REQUIRED)
-	FIND_PACKAGE(PCL 1.7 REQUIRED)
-	
-	# Find Qt5 first
-	FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui Svg QUIET)
-    	IF(NOT Qt5_FOUND)
-       		FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui QtSvg)
-    	ENDIF(NOT Qt5_FOUND)
+	FIND_PACKAGE(RTABMap REQUIRED COMPONENTS gui)
 endif()
 
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${QT_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(QT4_FOUND)
     QT4_WRAP_CPP(moc_srcs MapBuilder.h)
 ELSE()
@@ -63,7 +19,7 @@ ENDIF()
 
 ADD_EXECUTABLE(noEventsExample main.cpp ${moc_srcs})
   
-TARGET_LINK_LIBRARIES(noEventsExample ${LIBRARIES})
+TARGET_LINK_LIBRARIES(noEventsExample rtabmap_gui)
 
 if(internal)
 	SET_TARGET_PROPERTIES( noEventsExample 
diff --git a/examples/RGBDMapping/CMakeLists.txt b/examples/RGBDMapping/CMakeLists.txt
index 75a862161d..7346dece41 100644
--- a/examples/RGBDMapping/CMakeLists.txt
+++ b/examples/RGBDMapping/CMakeLists.txt
@@ -4,79 +4,13 @@ IF(DEFINED PROJECT_NAME)
    set(internal TRUE)
 ENDIF(DEFINED PROJECT_NAME)
 
-if(internal)
-	# inside rtabmap project (see below for external build)
-	SET(RTABMap_INCLUDE_DIRS 
-	    ${PROJECT_BINARY_DIR}/corelib/include
-	    ${PROJECT_SOURCE_DIR}/utilite/include
-		${PROJECT_SOURCE_DIR}/corelib/include
-		${PROJECT_SOURCE_DIR}/guilib/include
-	)
-	SET(RTABMap_LIBRARIES 
-	    rtabmap_core
-		rtabmap_gui
-		rtabmap_utilite
-	)  
-else()
+if(NOT internal)
 	# external build
 	PROJECT( MyProject )
 	
-	FIND_PACKAGE(RTABMap REQUIRED)
-	FIND_PACKAGE(OpenCV REQUIRED)
-	FIND_PACKAGE(PCL 1.7 REQUIRED)
-	
-	# Find Qt5 first
-	FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui Svg QUIET)
-    	IF(NOT Qt5_FOUND)
-       		FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui QtSvg)
-    	ENDIF(NOT Qt5_FOUND)
-
-	# fix libproj.so not found on Xenial
-	if(NOT "${PCL_LIBRARIES}" STREQUAL "")
-   		list(REMOVE_ITEM PCL_LIBRARIES "vtkproj4")
-	endif()
-
+	FIND_PACKAGE(RTABMap REQUIRED COMPONENTS gui)
 endif()
 
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${QT_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(QT4_FOUND)
     QT4_WRAP_CPP(moc_srcs MapBuilder.h)
 ELSE()
@@ -85,7 +19,7 @@ ENDIF()
 
 ADD_EXECUTABLE(rgbd_mapping main.cpp ${moc_srcs})
   
-TARGET_LINK_LIBRARIES(rgbd_mapping ${LIBRARIES})
+TARGET_LINK_LIBRARIES(rgbd_mapping rtabmap_gui)
 
 if(internal)
   SET_TARGET_PROPERTIES( rgbd_mapping 
diff --git a/examples/WifiMapping/CMakeLists.txt b/examples/WifiMapping/CMakeLists.txt
index 11a4e72941..7f150b0713 100644
--- a/examples/WifiMapping/CMakeLists.txt
+++ b/examples/WifiMapping/CMakeLists.txt
@@ -4,73 +4,13 @@ IF(DEFINED PROJECT_NAME)
    set(internal TRUE)
 ENDIF(DEFINED PROJECT_NAME)
 
-if(internal)
-	# inside rtabmap project (see below for external build)
-	SET(RTABMap_INCLUDE_DIRS 
-	    ${PROJECT_BINARY_DIR}/corelib/include
-	    ${PROJECT_SOURCE_DIR}/utilite/include
-		${PROJECT_SOURCE_DIR}/corelib/include
-		${PROJECT_SOURCE_DIR}/guilib/include
-	)
-	SET(RTABMap_LIBRARIES 
-	    rtabmap_core
-		rtabmap_gui
-		rtabmap_utilite
-	)  
-else()
+if(NOT internal)
 	# external build
 	PROJECT( MyProject )
 	
 	FIND_PACKAGE(RTABMap REQUIRED)
-	FIND_PACKAGE(OpenCV REQUIRED)
-	FIND_PACKAGE(PCL 1.7 REQUIRED)
-	
-	# Find Qt5 first
-	FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui Svg QUIET)
-    	IF(NOT Qt5_FOUND)
-       		FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui QtSvg)
-    	ENDIF(NOT Qt5_FOUND)
-endif()
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
 endif()
 
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${QT_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(QT4_FOUND)
     QT4_WRAP_CPP(moc_srcs MapBuilder.h MapBuilderWifi.h)
 ELSE()
@@ -80,6 +20,8 @@ ENDIF()
 SET(srcs
     main.cpp)
 
+set(LIBRARIES "")
+
 IF(APPLE)
     FIND_LIBRARY(CoreWLAN_LIBRARY CoreWLAN)
     FIND_LIBRARY(Foundation_LIBRARY Foundation)
@@ -96,7 +38,7 @@ IF(APPLE)
 ENDIF(APPLE)
 
 ADD_EXECUTABLE(wifi_mapping ${srcs} ${moc_srcs})
-TARGET_LINK_LIBRARIES(wifi_mapping ${LIBRARIES})
+TARGET_LINK_LIBRARIES(wifi_mapping rtabmap_gui ${LIBRARIES})
 
 if(internal)
   SET_TARGET_PROPERTIES( wifi_mapping 
diff --git a/guilib/include/rtabmap/gui/AboutDialog.h b/guilib/include/rtabmap/gui/AboutDialog.h
index 86689270e0..00cf7afe15 100644
--- a/guilib/include/rtabmap/gui/AboutDialog.h
+++ b/guilib/include/rtabmap/gui/AboutDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_ABOUTDIALOG_H_
 #define RTABMAP_ABOUTDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QtCore/QUrl>
@@ -37,7 +37,7 @@ class Ui_aboutDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP AboutDialog : public QDialog
+class RTABMAP_GUI_EXPORT AboutDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/CalibrationDialog.h b/guilib/include/rtabmap/gui/CalibrationDialog.h
index 5785c501f8..efc66438c1 100644
--- a/guilib/include/rtabmap/gui/CalibrationDialog.h
+++ b/guilib/include/rtabmap/gui/CalibrationDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_CALIBRATIONDIALOG_H_
 #define RTABMAP_CALIBRATIONDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QSettings>
@@ -43,7 +43,7 @@ class Ui_calibrationDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP CalibrationDialog  : public QDialog, public UEventsHandler
+class RTABMAP_GUI_EXPORT CalibrationDialog  : public QDialog, public UEventsHandler
 {
 	Q_OBJECT;
 
diff --git a/guilib/include/rtabmap/gui/CameraViewer.h b/guilib/include/rtabmap/gui/CameraViewer.h
index 2343aa8ee4..0f227f7b54 100644
--- a/guilib/include/rtabmap/gui/CameraViewer.h
+++ b/guilib/include/rtabmap/gui/CameraViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_CAMERAVIEWER_H_
 #define RTABMAP_CAMERAVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UEventsHandler.h>
 #include <QDialog>
@@ -45,7 +45,7 @@ namespace rtabmap {
 class ImageView;
 class CloudViewer;
 
-class RTABMAPGUI_EXP CameraViewer : public QDialog, public UEventsHandler
+class RTABMAP_GUI_EXPORT CameraViewer : public QDialog, public UEventsHandler
 {
 	Q_OBJECT
 public:
diff --git a/guilib/include/rtabmap/gui/CloudViewer.h b/guilib/include/rtabmap/gui/CloudViewer.h
index f0d354a94d..12cb0c1e78 100644
--- a/guilib/include/rtabmap/gui/CloudViewer.h
+++ b/guilib/include/rtabmap/gui/CloudViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_CLOUDVIEWER_H_
 #define RTABMAP_CLOUDVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include "rtabmap/core/Transform.h"
 #include "rtabmap/core/StereoCameraModel.h"
@@ -75,7 +75,7 @@ namespace rtabmap {
 
 class OctoMap;
 
-class RTABMAPGUI_EXP CloudViewer : public PCLQVTKWidget
+class RTABMAP_GUI_EXPORT CloudViewer : public PCLQVTKWidget
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/CloudViewerCellPicker.h b/guilib/include/rtabmap/gui/CloudViewerCellPicker.h
index 2781101f20..6cc3c6634a 100644
--- a/guilib/include/rtabmap/gui/CloudViewerCellPicker.h
+++ b/guilib/include/rtabmap/gui/CloudViewerCellPicker.h
@@ -8,13 +8,13 @@
 #ifndef GUILIB_SRC_CLOUDVIEWERCELLPICKER_H_
 #define GUILIB_SRC_CLOUDVIEWERCELLPICKER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <vtkCellPicker.h>
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP CloudViewerCellPicker : public vtkCellPicker {
+class RTABMAP_GUI_EXPORT CloudViewerCellPicker : public vtkCellPicker {
 public:
 public:
     static CloudViewerCellPicker *New ();
diff --git a/guilib/include/rtabmap/gui/CloudViewerInteractorStyle.h b/guilib/include/rtabmap/gui/CloudViewerInteractorStyle.h
index 0cbad9e030..0c7d103065 100644
--- a/guilib/include/rtabmap/gui/CloudViewerInteractorStyle.h
+++ b/guilib/include/rtabmap/gui/CloudViewerInteractorStyle.h
@@ -8,7 +8,7 @@
 #ifndef GUILIB_SRC_CLOUDVIEWERINTERACTORSTYLE_H_
 #define GUILIB_SRC_CLOUDVIEWERINTERACTORSTYLE_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <pcl/visualization/mouse_event.h>
 #include <pcl/visualization/point_picking_event.h>
@@ -19,7 +19,7 @@ namespace rtabmap {
 
 class CloudViewer;
 
-class RTABMAPGUI_EXP CloudViewerInteractorStyle: public pcl::visualization::PCLVisualizerInteractorStyle
+class RTABMAP_GUI_EXPORT CloudViewerInteractorStyle: public pcl::visualization::PCLVisualizerInteractorStyle
 {
 public:
     static CloudViewerInteractorStyle *New ();
diff --git a/guilib/include/rtabmap/gui/ConsoleWidget.h b/guilib/include/rtabmap/gui/ConsoleWidget.h
index c1e7ea533a..b0c074771b 100644
--- a/guilib/include/rtabmap/gui/ConsoleWidget.h
+++ b/guilib/include/rtabmap/gui/ConsoleWidget.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_CONSOLEWIDGET_H_
 #define RTABMAP_CONSOLEWIDGET_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UEventsHandler.h>
 #include <QWidget>
@@ -42,7 +42,7 @@ class QTextCursor;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP ConsoleWidget : public QWidget, public UEventsHandler
+class RTABMAP_GUI_EXPORT ConsoleWidget : public QWidget, public UEventsHandler
 {
 	Q_OBJECT;
 
diff --git a/guilib/include/rtabmap/gui/CreateSimpleCalibrationDialog.h b/guilib/include/rtabmap/gui/CreateSimpleCalibrationDialog.h
index eb43801531..0482195014 100644
--- a/guilib/include/rtabmap/gui/CreateSimpleCalibrationDialog.h
+++ b/guilib/include/rtabmap/gui/CreateSimpleCalibrationDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_CREATESIMPLECALIBRATIONDIALOG_H_
 #define RTABMAP_CREATESIMPLECALIBRATIONDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QSettings>
@@ -37,7 +37,7 @@ class Ui_createSimpleCalibrationDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP CreateSimpleCalibrationDialog : public QDialog
+class RTABMAP_GUI_EXPORT CreateSimpleCalibrationDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/DataRecorder.h b/guilib/include/rtabmap/gui/DataRecorder.h
index 7285a4355a..5b718635de 100644
--- a/guilib/include/rtabmap/gui/DataRecorder.h
+++ b/guilib/include/rtabmap/gui/DataRecorder.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_DATARECORDER_H_
 #define RTABMAP_DATARECORDER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UEventsHandler.h>
 #include <QWidget>
@@ -43,7 +43,7 @@ namespace rtabmap {
 class Memory;
 class ImageView;
 
-class RTABMAPGUI_EXP DataRecorder : public QWidget, public UEventsHandler
+class RTABMAP_GUI_EXPORT DataRecorder : public QWidget, public UEventsHandler
 {
 	Q_OBJECT
 public:
diff --git a/guilib/include/rtabmap/gui/DatabaseViewer.h b/guilib/include/rtabmap/gui/DatabaseViewer.h
index 8360575925..b86906ed29 100644
--- a/guilib/include/rtabmap/gui/DatabaseViewer.h
+++ b/guilib/include/rtabmap/gui/DatabaseViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_DATABASEVIEWER_H_
 #define RTABMAP_DATABASEVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QMainWindow>
 #include <QtCore/QByteArray>
@@ -62,7 +62,7 @@ class ExportCloudsDialog;
 class EditDepthArea;
 class EditMapArea;
 
-class RTABMAPGUI_EXP DatabaseViewer : public QMainWindow
+class RTABMAP_GUI_EXPORT DatabaseViewer : public QMainWindow
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/DepthCalibrationDialog.h b/guilib/include/rtabmap/gui/DepthCalibrationDialog.h
index 78b36370d8..01b2d55076 100644
--- a/guilib/include/rtabmap/gui/DepthCalibrationDialog.h
+++ b/guilib/include/rtabmap/gui/DepthCalibrationDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_DEPTHCALIBRATIONDIALOG_H_
 #define RTABMAP_DEPTHCALIBRATIONDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QMap>
@@ -46,7 +46,7 @@ namespace rtabmap {
 
 class ProgressDialog;
 
-class RTABMAPGUI_EXP DepthCalibrationDialog : public QDialog
+class RTABMAP_GUI_EXPORT DepthCalibrationDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/EditConstraintDialog.h b/guilib/include/rtabmap/gui/EditConstraintDialog.h
index acf7eb0828..8a37be8e76 100644
--- a/guilib/include/rtabmap/gui/EditConstraintDialog.h
+++ b/guilib/include/rtabmap/gui/EditConstraintDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_EDITCONSTRAINTDIALOG_H_
 #define RTABMAP_EDITCONSTRAINTDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <rtabmap/core/Transform.h>
@@ -37,7 +37,7 @@ class Ui_EditConstraintDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP EditConstraintDialog : public QDialog
+class RTABMAP_GUI_EXPORT EditConstraintDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/EditDepthArea.h b/guilib/include/rtabmap/gui/EditDepthArea.h
index 6878ea77c6..955872da97 100644
--- a/guilib/include/rtabmap/gui/EditDepthArea.h
+++ b/guilib/include/rtabmap/gui/EditDepthArea.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_EDITDEPTHAREA_H
 #define RTABMAP_EDITDEPTHAREA_H
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QColor>
 #include <QImage>
@@ -42,7 +42,7 @@ class QAction;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP EditDepthArea : public QWidget
+class RTABMAP_GUI_EXPORT EditDepthArea : public QWidget
 {
     Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/EditMapArea.h b/guilib/include/rtabmap/gui/EditMapArea.h
index 8e77727676..36793a7e75 100644
--- a/guilib/include/rtabmap/gui/EditMapArea.h
+++ b/guilib/include/rtabmap/gui/EditMapArea.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_EDITMAPAREA_H
 #define RTABMAP_EDITMAPAREA_H
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QColor>
 #include <QImage>
@@ -42,7 +42,7 @@ class QAction;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP EditMapArea : public QWidget
+class RTABMAP_GUI_EXPORT EditMapArea : public QWidget
 {
     Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/ExportBundlerDialog.h b/guilib/include/rtabmap/gui/ExportBundlerDialog.h
index 96f1e62a0b..edd9ac187f 100644
--- a/guilib/include/rtabmap/gui/ExportBundlerDialog.h
+++ b/guilib/include/rtabmap/gui/ExportBundlerDialog.h
@@ -25,10 +25,10 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#ifndef RTABMAP_EXPORTBUNDLERDIALOG_H_
-#define RTABMAP_EXPORTBUNDLERDIALOG_H_
+#ifndef RTABMAP_CORE_EXPORTBUNDLERDIALOG_H_
+#define RTABMAP_CORE_EXPORTBUNDLERDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Signature.h>
 #include <rtabmap/core/Parameters.h>
@@ -39,7 +39,7 @@ class Ui_ExportBundlerDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP ExportBundlerDialog : public QDialog
+class RTABMAP_GUI_EXPORT ExportBundlerDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/ExportCloudsDialog.h b/guilib/include/rtabmap/gui/ExportCloudsDialog.h
index b2ffa71589..fcfd66f76e 100644
--- a/guilib/include/rtabmap/gui/ExportCloudsDialog.h
+++ b/guilib/include/rtabmap/gui/ExportCloudsDialog.h
@@ -25,10 +25,10 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#ifndef RTABMAP_EXPORTCLOUDSDIALOG_H_
-#define RTABMAP_EXPORTCLOUDSDIALOG_H_
+#ifndef RTABMAP_CORE_EXPORTCLOUDSDIALOG_H_
+#define RTABMAP_CORE_EXPORTCLOUDSDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QMap>
@@ -51,7 +51,7 @@ class ProgressDialog;
 class GainCompensator;
 class DBDriver;
 
-class RTABMAPGUI_EXP ExportCloudsDialog : public QDialog
+class RTABMAP_GUI_EXPORT ExportCloudsDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/ExportDialog.h b/guilib/include/rtabmap/gui/ExportDialog.h
index 6316e02ac7..2db6f99203 100644
--- a/guilib/include/rtabmap/gui/ExportDialog.h
+++ b/guilib/include/rtabmap/gui/ExportDialog.h
@@ -25,10 +25,10 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
 
-#ifndef RTABMAP_EXPORTDIALOG_H_
-#define RTABMAP_EXPORTDIALOG_H_
+#ifndef RTABMAP_CORE_EXPORTDIALOG_H_
+#define RTABMAP_CORE_EXPORTDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QSettings>
@@ -37,7 +37,7 @@ class Ui_ExportDialog;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP ExportDialog : public QDialog
+class RTABMAP_GUI_EXPORT ExportDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/GraphViewer.h b/guilib/include/rtabmap/gui/GraphViewer.h
index dff621a2b4..fac00a0908 100644
--- a/guilib/include/rtabmap/gui/GraphViewer.h
+++ b/guilib/include/rtabmap/gui/GraphViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_GRAPHVIEWER_H_
 #define RTABMAP_GRAPHVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QGraphicsView>
 #include <QtCore/QMap>
@@ -49,7 +49,7 @@ namespace rtabmap {
 class NodeItem;
 class LinkItem;
 
-class RTABMAPGUI_EXP GraphViewer : public QGraphicsView {
+class RTABMAP_GUI_EXPORT GraphViewer : public QGraphicsView {
 
 	Q_OBJECT;
 
diff --git a/guilib/include/rtabmap/gui/ImageView.h b/guilib/include/rtabmap/gui/ImageView.h
index c250c65619..eb054f5a7d 100644
--- a/guilib/include/rtabmap/gui/ImageView.h
+++ b/guilib/include/rtabmap/gui/ImageView.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_IMAGEVIEW_H_
 #define RTABMAP_IMAGEVIEW_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QGraphicsView>
 #include <QtCore/QRectF>
@@ -45,7 +45,7 @@ namespace rtabmap {
 
 class KeypointItem;
 
-class RTABMAPGUI_EXP ImageView : public QWidget {
+class RTABMAP_GUI_EXPORT ImageView : public QWidget {
 
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/KeypointItem.h b/guilib/include/rtabmap/gui/KeypointItem.h
index 006bfaa0bd..7f4f9f6419 100644
--- a/guilib/include/rtabmap/gui/KeypointItem.h
+++ b/guilib/include/rtabmap/gui/KeypointItem.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_KEYPOINTITEM_H_
 #define RTABMAP_KEYPOINTITEM_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QGraphicsEllipseItem>
 #include <QGraphicsTextItem>
@@ -38,7 +38,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP KeypointItem : public QGraphicsEllipseItem
+class RTABMAP_GUI_EXPORT KeypointItem : public QGraphicsEllipseItem
 {
 public:
 	KeypointItem(int id, const cv::KeyPoint & kpt, float depth = 0, const QColor & color = Qt::green, QGraphicsItem * parent = 0);
diff --git a/guilib/include/rtabmap/gui/LoopClosureViewer.h b/guilib/include/rtabmap/gui/LoopClosureViewer.h
index 66a845a945..c269f33f09 100644
--- a/guilib/include/rtabmap/gui/LoopClosureViewer.h
+++ b/guilib/include/rtabmap/gui/LoopClosureViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_LOOPCLOSUREVIEWER_H_
 #define RTABMAP_LOOPCLOSUREVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <rtabmap/core/Transform.h>
@@ -40,7 +40,7 @@ class Ui_loopClosureViewer;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP LoopClosureViewer : public QWidget {
+class RTABMAP_GUI_EXPORT LoopClosureViewer : public QWidget {
 
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/MainWindow.h b/guilib/include/rtabmap/gui/MainWindow.h
index fc10620a1f..533e4cec51 100644
--- a/guilib/include/rtabmap/gui/MainWindow.h
+++ b/guilib/include/rtabmap/gui/MainWindow.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_MAINWINDOW_H_
 #define RTABMAP_MAINWINDOW_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UEventsHandler.h"
 #include <QMainWindow>
@@ -76,7 +76,7 @@ class DataRecorder;
 class OctoMap;
 class MultiSessionLocWidget;
 
-class RTABMAPGUI_EXP MainWindow : public QMainWindow, public UEventsHandler
+class RTABMAP_GUI_EXPORT MainWindow : public QMainWindow, public UEventsHandler
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/MapVisibilityWidget.h b/guilib/include/rtabmap/gui/MapVisibilityWidget.h
index 328e27df7b..e4675a3523 100644
--- a/guilib/include/rtabmap/gui/MapVisibilityWidget.h
+++ b/guilib/include/rtabmap/gui/MapVisibilityWidget.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_MAPVISIBILITYWIDGET_H_
 #define RTABMAP_MAPVISIBILITYWIDGET_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QWidget>
 #include <rtabmap/core/Transform.h>
@@ -36,7 +36,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP MapVisibilityWidget : public QWidget {
+class RTABMAP_GUI_EXPORT MapVisibilityWidget : public QWidget {
 	Q_OBJECT;
 public:
 	MapVisibilityWidget(QWidget * parent = 0);
diff --git a/guilib/include/rtabmap/gui/MultiSessionLocSubView.h b/guilib/include/rtabmap/gui/MultiSessionLocSubView.h
index cc8a1fca6c..dcbc7fff86 100644
--- a/guilib/include/rtabmap/gui/MultiSessionLocSubView.h
+++ b/guilib/include/rtabmap/gui/MultiSessionLocSubView.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_MULTISESSIONLOCSUBVIEW_H_
 #define RTABMAP_MULTISESSIONLOCSUBVIEW_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 #include <opencv2/core.hpp>
 #include <QWidget>
 
@@ -38,7 +38,7 @@ namespace rtabmap {
 
 class ImageView;
 
-class RTABMAPGUI_EXP MultiSessionLocSubView : public QWidget
+class RTABMAP_GUI_EXPORT MultiSessionLocSubView : public QWidget
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/MultiSessionLocWidget.h b/guilib/include/rtabmap/gui/MultiSessionLocWidget.h
index 54cf968263..97361087ef 100644
--- a/guilib/include/rtabmap/gui/MultiSessionLocWidget.h
+++ b/guilib/include/rtabmap/gui/MultiSessionLocWidget.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_MULTISESSIONLOCWIDGET_H_
 #define RTABMAP_MULTISESSIONLOCWIDGET_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include "rtabmap/core/Statistics.h"
 #include "rtabmap/core/Signature.h"
@@ -42,7 +42,7 @@ namespace rtabmap {
 class MultiSessionLocSubView;
 class ImageView;
 
-class RTABMAPGUI_EXP MultiSessionLocWidget : public QWidget
+class RTABMAP_GUI_EXPORT MultiSessionLocWidget : public QWidget
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/OdometryViewer.h b/guilib/include/rtabmap/gui/OdometryViewer.h
index 97de724653..5c8684665d 100644
--- a/guilib/include/rtabmap/gui/OdometryViewer.h
+++ b/guilib/include/rtabmap/gui/OdometryViewer.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_ODOMETRYVIEWER_H_
 #define RTABMAP_ODOMETRYVIEWER_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include "rtabmap/core/OdometryEvent.h"
 #include "rtabmap/core/Parameters.h"
@@ -45,7 +45,7 @@ namespace rtabmap {
 class ImageView;
 class CloudViewer;
 
-class RTABMAPGUI_EXP OdometryViewer : public QDialog, public UEventsHandler
+class RTABMAP_GUI_EXPORT OdometryViewer : public QDialog, public UEventsHandler
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/ParametersToolBox.h b/guilib/include/rtabmap/gui/ParametersToolBox.h
index 18bbf596ce..f52c841b0d 100644
--- a/guilib/include/rtabmap/gui/ParametersToolBox.h
+++ b/guilib/include/rtabmap/gui/ParametersToolBox.h
@@ -32,7 +32,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_PARAMETERSTOOLBOX_H_
 #define RTABMAP_PARAMETERSTOOLBOX_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/core/Parameters.h>
 #include <QWidget>
@@ -44,7 +44,7 @@ class QComboBox;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP ParametersToolBox: public QWidget
+class RTABMAP_GUI_EXPORT ParametersToolBox: public QWidget
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/PdfPlot.h b/guilib/include/rtabmap/gui/PdfPlot.h
index 900bc89cc8..4a4ca49832 100644
--- a/guilib/include/rtabmap/gui/PdfPlot.h
+++ b/guilib/include/rtabmap/gui/PdfPlot.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_PDFPLOT_H_
 #define RTABMAP_PDFPLOT_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <rtabmap/utilite/UPlot.h>
 #include "opencv2/opencv.hpp"
@@ -36,7 +36,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP PdfPlotItem : public UPlotItem
+class RTABMAP_GUI_EXPORT PdfPlotItem : public UPlotItem
 {
 public:
 	PdfPlotItem(float dataX, float dataY, float width, int childCount = -1);
@@ -59,7 +59,7 @@ class RTABMAPGUI_EXP PdfPlotItem : public UPlotItem
 
 };
 
-class RTABMAPGUI_EXP PdfPlotCurve : public UPlotCurve
+class RTABMAP_GUI_EXPORT PdfPlotCurve : public UPlotCurve
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/PostProcessingDialog.h b/guilib/include/rtabmap/gui/PostProcessingDialog.h
index d7f0ac8815..b0b2bfe893 100644
--- a/guilib/include/rtabmap/gui/PostProcessingDialog.h
+++ b/guilib/include/rtabmap/gui/PostProcessingDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_POSTPROCESSINGDIALOG_H_
 #define RTABMAP_POSTPROCESSINGDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QtCore/QSettings>
@@ -40,7 +40,7 @@ class QAbstractButton;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP PostProcessingDialog : public QDialog
+class RTABMAP_GUI_EXPORT PostProcessingDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/PreferencesDialog.h b/guilib/include/rtabmap/gui/PreferencesDialog.h
index 446b7e674e..3604c4cada 100644
--- a/guilib/include/rtabmap/gui/PreferencesDialog.h
+++ b/guilib/include/rtabmap/gui/PreferencesDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_PREFERENCESDIALOG_H_
 #define RTABMAP_PREFERENCESDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 #include <QtCore/QModelIndex>
@@ -63,7 +63,7 @@ class Camera;
 class CalibrationDialog;
 class CreateSimpleCalibrationDialog;
 
-class RTABMAPGUI_EXP PreferencesDialog : public QDialog
+class RTABMAP_GUI_EXPORT PreferencesDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/ProgressDialog.h b/guilib/include/rtabmap/gui/ProgressDialog.h
index db3c4f9a6f..3fbf6deb68 100644
--- a/guilib/include/rtabmap/gui/ProgressDialog.h
+++ b/guilib/include/rtabmap/gui/ProgressDialog.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_PROGRESSDIALOG_H_
 #define RTABMAP_PROGRESSDIALOG_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QDialog>
 
@@ -40,7 +40,7 @@ class QCheckBox;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP ProgressDialog : public QDialog
+class RTABMAP_GUI_EXPORT ProgressDialog : public QDialog
 {
 	Q_OBJECT
 
diff --git a/guilib/include/rtabmap/gui/RtabmapGuiExp.h b/guilib/include/rtabmap/gui/RtabmapGuiExp.h
deleted file mode 100644
index b0af5a6d70..0000000000
--- a/guilib/include/rtabmap/gui/RtabmapGuiExp.h
+++ /dev/null
@@ -1,41 +0,0 @@
-/*
-Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
-All rights reserved.
-
-Redistribution and use in source and binary forms, with or without
-modification, are permitted provided that the following conditions are met:
-    * Redistributions of source code must retain the above copyright
-      notice, this list of conditions and the following disclaimer.
-    * Redistributions in binary form must reproduce the above copyright
-      notice, this list of conditions and the following disclaimer in the
-      documentation and/or other materials provided with the distribution.
-    * Neither the name of the Universite de Sherbrooke nor the
-      names of its contributors may be used to endorse or promote products
-      derived from this software without specific prior written permission.
-
-THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
-ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
-WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
-DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
-DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
-(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
-ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
-(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
-SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-*/
-
-#ifndef RTABMAPGUIEXP_H
-#define RTABMAPGUIEXP_H
-
-#if defined(_WIN32)
-  #if defined(rtabmap_gui_EXPORTS)
-    #define RTABMAPGUI_EXP   __declspec( dllexport )
-  #else
-    #define RTABMAPGUI_EXP   __declspec( dllimport )
-  #endif
-#else
-  #define RTABMAPGUI_EXP
-#endif
-
-#endif // RTABMAPGUIEXP_H
diff --git a/guilib/include/rtabmap/gui/StatsToolBox.h b/guilib/include/rtabmap/gui/StatsToolBox.h
index 0a9b417ab1..86ab8c7be9 100644
--- a/guilib/include/rtabmap/gui/StatsToolBox.h
+++ b/guilib/include/rtabmap/gui/StatsToolBox.h
@@ -28,7 +28,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 #ifndef RTABMAP_STATSTOOLBOX_H_
 #define RTABMAP_STATSTOOLBOX_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QWidget>
 #include <QtCore/QMap>
@@ -41,7 +41,7 @@ class QToolBox;
 
 namespace rtabmap {
 
-class RTABMAPGUI_EXP StatItem : public QWidget
+class RTABMAP_GUI_EXPORT StatItem : public QWidget
 {
 	Q_OBJECT;
 
@@ -87,7 +87,7 @@ private Q_SLOTS:
 
 
 
-class RTABMAPGUI_EXP StatsToolBox : public QWidget
+class RTABMAP_GUI_EXPORT StatsToolBox : public QWidget
 {
 	Q_OBJECT;
 
diff --git a/guilib/include/rtabmap/utilite/UImageView.h b/guilib/include/rtabmap/utilite/UImageView.h
index 437bc82c52..2de08aba6e 100644
--- a/guilib/include/rtabmap/utilite/UImageView.h
+++ b/guilib/include/rtabmap/utilite/UImageView.h
@@ -8,12 +8,12 @@
 #ifndef IMAGEVIEW_H_
 #define IMAGEVIEW_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QWidget>
 #include <QtGui/QPainter>
 
-class RTABMAPGUI_EXP UImageView : public QWidget
+class RTABMAP_GUI_EXPORT UImageView : public QWidget
 {
 	Q_OBJECT;
 public:
diff --git a/guilib/include/rtabmap/utilite/UPlot.h b/guilib/include/rtabmap/utilite/UPlot.h
index 7a2dcae5d6..21ad58968a 100644
--- a/guilib/include/rtabmap/utilite/UPlot.h
+++ b/guilib/include/rtabmap/utilite/UPlot.h
@@ -20,7 +20,7 @@
 #ifndef UPLOT_H_
 #define UPLOT_H_
 
-#include "rtabmap/gui/RtabmapGuiExp.h" // DLL export/import defines
+#include "rtabmap/gui/rtabmap_gui_export.h" // DLL export/import defines
 
 #include <QFrame>
 #include <QtCore/QList>
@@ -43,7 +43,7 @@ class QScrollArea;
  * UPlotItem is a QGraphicsEllipseItem and can be inherited to do custom behaviors
  * on an hoverEnterEvent() for example.
  */
-class RTABMAPGUI_EXP UPlotItem : public QGraphicsEllipseItem
+class RTABMAP_GUI_EXPORT UPlotItem : public QGraphicsEllipseItem
 {
 public:
 	/**
@@ -89,7 +89,7 @@ class UPlot;
 /**
  * UPlotCurve is a curve used to hold data shown in a UPlot.
  */
-class RTABMAPGUI_EXP UPlotCurve : public QObject
+class RTABMAP_GUI_EXPORT UPlotCurve : public QObject
 {
 	Q_OBJECT
 
@@ -259,7 +259,7 @@ public Q_SLOTS:
 /**
  * A special UPlotCurve that shows as a line at the specified value, spanning all the UPlot.
  */
-class RTABMAPGUI_EXP UPlotCurveThreshold : public UPlotCurve
+class RTABMAP_GUI_EXPORT UPlotCurveThreshold : public UPlotCurve
 {
 	Q_OBJECT
 
@@ -292,7 +292,7 @@ public Q_SLOTS:
 /**
  * The UPlot axis object.
  */
-class RTABMAPGUI_EXP UPlotAxis : public QWidget
+class RTABMAP_GUI_EXPORT UPlotAxis : public QWidget
 {
 public:
 	/**
@@ -342,7 +342,7 @@ class RTABMAPGUI_EXP UPlotAxis : public QWidget
 /**
  * The UPlot legend item. Used internally by UPlot.
  */
-class RTABMAPGUI_EXP UPlotLegendItem : public QPushButton
+class RTABMAP_GUI_EXPORT UPlotLegendItem : public QPushButton
 {
 	Q_OBJECT
 
@@ -383,7 +383,7 @@ private Q_SLOTS:
 /**
  * The UPlot legend. Used internally by UPlot.
  */
-class RTABMAPGUI_EXP UPlotLegend : public QWidget
+class RTABMAP_GUI_EXPORT UPlotLegend : public QWidget
 {
 	Q_OBJECT
 
@@ -430,7 +430,7 @@ private Q_SLOTS:
 /**
  * Orientable QLabel. Inherit QLabel and let you to specify the orientation.
  */
-class RTABMAPGUI_EXP UOrientableLabel : public QLabel
+class RTABMAP_GUI_EXPORT UOrientableLabel : public QLabel
 {
 	Q_OBJECT
 
@@ -486,7 +486,7 @@ class RTABMAPGUI_EXP UOrientableLabel : public QLabel
  *
  *
  */
-class RTABMAPGUI_EXP UPlot : public QWidget
+class RTABMAP_GUI_EXPORT UPlot : public QWidget
 {
 	Q_OBJECT
 
diff --git a/guilib/src/CMakeLists.txt b/guilib/src/CMakeLists.txt
index 07efc7cd27..87d214eff8 100644
--- a/guilib/src/CMakeLists.txt
+++ b/guilib/src/CMakeLists.txt
@@ -128,51 +128,30 @@ IF(MSVC)
 ENDIF(MSVC)
 
 SET(INCLUDE_DIRS
-	${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
 	${CMAKE_CURRENT_SOURCE_DIR}/../include
 	${CMAKE_CURRENT_SOURCE_DIR}
-	${OpenCV_INCLUDE_DIRS}
 	${CMAKE_CURRENT_BINARY_DIR} # for qt ui generated in binary dir
-	${PCL_INCLUDE_DIRS}
 )
 
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
 IF(QT4_FOUND)
     INCLUDE(${QT_USE_FILE})
 ENDIF(QT4_FOUND)
 
-SET(LIBRARIES
-    ${QT_LIBRARIES} 
-	${OpenCV_LIBS} 
-	${PCL_LIBRARIES}
-)
+SET(LIBRARIES "")
+SET(PUBLIC_LIBRARIES "")
 
-IF(octomap_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${OCTOMAP_INCLUDE_DIRS}
-	)
-	SET(LIBRARIES
-		${LIBRARIES}
-		${OCTOMAP_LIBRARIES}
-	)
-ENDIF(octomap_FOUND)
+IF(Qt5_FOUND)
+    SET(PUBLIC_LIBRARIES ${PUBLIC_LIBRARIES} Qt5::Widgets Qt5::Core Qt5::Gui)
+    SET(LIBRARIES ${LIBRARIES} Qt5::PrintSupport)
+    IF(Qt5Svg_FOUND)
+        SET(LIBRARIES ${LIBRARIES} Qt5::Svg)
+    ENDIF()
+ELSE()
+    SET(PUBLIC_LIBRARIES ${PUBLIC_LIBRARIES} ${QTCORE_LIBRARY} ${QTGUI_LIBRARY})
+    IF(QTSVG_FOUND)
+        SET(LIBRARIES ${LIBRARIES} ${QTSVG_LIBRARY})
+    ENDIF()
+ENDIF()
 
 IF(CPUTSDF_FOUND)
 	SET(INCLUDE_DIRS
@@ -208,16 +187,20 @@ add_definitions(${PCL_DEFINITIONS})
 
 # create a library from the source files
 ADD_LIBRARY(rtabmap_gui ${SRC_FILES})
-# Linking with Qt libraries
 
-TARGET_LINK_LIBRARIES(rtabmap_gui rtabmap_core rtabmap_utilite ${LIBRARIES})
-IF(Qt5_FOUND)
-    IF(Qt5Svg_FOUND)
-        QT5_USE_MODULES(rtabmap_gui Widgets Core Gui Svg PrintSupport)
-    ELSE()
-        QT5_USE_MODULES(rtabmap_gui Widgets Core Gui PrintSupport)
-    ENDIF()
-ENDIF(Qt5_FOUND)
+generate_export_header(rtabmap_gui
+ DEPRECATED_MACRO_NAME RTABMAP_DEPRECATED)
+
+target_include_directories(rtabmap_gui PUBLIC 
+  "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../include;${CMAKE_CURRENT_BINARY_DIR}/include>"
+  "$<INSTALL_INTERFACE:${INSTALL_INCLUDE_DIR}>")
+
+TARGET_LINK_LIBRARIES(rtabmap_gui 
+  PUBLIC
+    rtabmap_core ${PUBLIC_LIBRARIES}
+  PRIVATE
+    ${LIBRARIES}
+)
 
 SET_TARGET_PROPERTIES(
      rtabmap_gui
@@ -226,9 +209,34 @@ SET_TARGET_PROPERTIES(
      SOVERSION ${RTABMAP_MAJOR_VERSION}.${RTABMAP_MINOR_VERSION}
 )
 
-INSTALL(TARGETS rtabmap_gui
+INSTALL(TARGETS rtabmap_gui EXPORT rtabmap_guiTargets
         RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" COMPONENT runtime
         LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel
         ARCHIVE DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel)
-        
-install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/../include/ DESTINATION "${INSTALL_INCLUDE_DIR}" COMPONENT devel FILES_MATCHING PATTERN "*.h" PATTERN ".svn" EXCLUDE)
+
+configure_file(
+  ${CMAKE_CURRENT_BINARY_DIR}/rtabmap_gui_export.h
+  ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}/gui/rtabmap_gui_export.h
+  COPYONLY)
+  
+install(
+  DIRECTORY
+    ${CMAKE_CURRENT_SOURCE_DIR}/../include/${PROJECT_PREFIX}
+    ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}
+  DESTINATION
+    ${INSTALL_INCLUDE_DIR}
+  COMPONENT
+    devel
+  FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp"
+)
+export(EXPORT rtabmap_guiTargets
+  FILE "${CMAKE_CURRENT_BINARY_DIR}/../../${PROJECT_NAME}_guiTargets.cmake"
+)
+install(EXPORT rtabmap_guiTargets
+  FILE
+    ${PROJECT_NAME}_guiTargets.cmake
+  DESTINATION
+    ${INSTALL_CMAKE_DIR}
+  COMPONENT
+    devel
+)
diff --git a/package.xml b/package.xml
index 43ba8c102a..482eeb6032 100644
--- a/package.xml
+++ b/package.xml
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>rtabmap</name>
-  <version>0.20.23</version>
+  <version>0.21.0</version>
   <description>RTAB-Map's standalone library. RTAB-Map is a RGB-D SLAM approach with real-time constraints.</description>
   <maintainer email="matlabbe@gmail.com">Mathieu Labbe</maintainer>
   <author>Mathieu Labbe</author>
diff --git a/tools/Calibration/CMakeLists.txt b/tools/Calibration/CMakeLists.txt
index 8d76844ea7..9bb3f74f48 100644
--- a/tools/Calibration/CMakeLists.txt
+++ b/tools/Calibration/CMakeLists.txt
@@ -1,44 +1,6 @@
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-	${QT_LIBRARIES} 
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(calibration main.cpp)
-TARGET_LINK_LIBRARIES(calibration rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(calibration rtabmap_gui)
 
 SET_TARGET_PROPERTIES( calibration 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-calibration)
diff --git a/tools/Camera/CMakeLists.txt b/tools/Camera/CMakeLists.txt
index 69add6252f..8100133e1d 100644
--- a/tools/Camera/CMakeLists.txt
+++ b/tools/Camera/CMakeLists.txt
@@ -1,22 +1,6 @@
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(camera main.cpp)
-TARGET_LINK_LIBRARIES(camera rtabmap_core rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(camera rtabmap_core)
 
 SET_TARGET_PROPERTIES( camera 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-camera)
diff --git a/tools/CameraRGBD/CMakeLists.txt b/tools/CameraRGBD/CMakeLists.txt
index 5549e6fdb5..4b203e5119 100644
--- a/tools/CameraRGBD/CMakeLists.txt
+++ b/tools/CameraRGBD/CMakeLists.txt
@@ -1,44 +1,6 @@
 
-IF(NOT WITH_QT)
-   # visualization module required
-   FIND_PACKAGE(PCL 1.7 REQUIRED QUIET COMPONENTS common io kdtree search surface filters registration sample_consensus segmentation visualization)
-ENDIF(NOT WITH_QT)
-
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(rgbd_camera main.cpp)
-TARGET_LINK_LIBRARIES(rgbd_camera rtabmap_core rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(rgbd_camera rtabmap_gui)
 
 SET_TARGET_PROPERTIES( rgbd_camera 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-rgbd_camera)
diff --git a/tools/CleanupLocalGrids/CMakeLists.txt b/tools/CleanupLocalGrids/CMakeLists.txt
index 9d05dff6ee..7d16f37ab6 100644
--- a/tools/CleanupLocalGrids/CMakeLists.txt
+++ b/tools/CleanupLocalGrids/CMakeLists.txt
@@ -1,31 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(cleanupLocalGrids main.cpp)
   
-TARGET_LINK_LIBRARIES(cleanupLocalGrids ${LIBRARIES})
+TARGET_LINK_LIBRARIES(cleanupLocalGrids rtabmap_core)
 
 SET_TARGET_PROPERTIES( cleanupLocalGrids 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-cleanupLocalGrids)
diff --git a/tools/ConsoleApp/CMakeLists.txt b/tools/ConsoleApp/CMakeLists.txt
index 0300e9e35c..818f2bd459 100644
--- a/tools/ConsoleApp/CMakeLists.txt
+++ b/tools/ConsoleApp/CMakeLists.txt
@@ -1,32 +1,8 @@
 
-SET(SRC_FILES
-    main.cpp
-)
-
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-    ${CMAKE_CURRENT_SOURCE_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-	${CMAKE_CURRENT_SOURCE_DIR}/../include
-	${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Make sure the compiler can find include files from our library.
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 # Add binary called "consoleApp" that is built from the source file "main.cpp".
 # The extension is automatically found.
-ADD_EXECUTABLE(consoleApp ${SRC_FILES})
-TARGET_LINK_LIBRARIES(consoleApp rtabmap_core rtabmap_utilite ${LIBRARIES})
+ADD_EXECUTABLE(consoleApp main.cpp)
+TARGET_LINK_LIBRARIES(consoleApp rtabmap_core)
 
 SET_TARGET_PROPERTIES( consoleApp 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-console)
diff --git a/tools/DataRecorder/CMakeLists.txt b/tools/DataRecorder/CMakeLists.txt
index 3757d30b9a..61b3c53309 100644
--- a/tools/DataRecorder/CMakeLists.txt
+++ b/tools/DataRecorder/CMakeLists.txt
@@ -1,54 +1,10 @@
 
-SET(SRC_FILES
-    main.cpp
-)
-
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${CMAKE_CURRENT_SOURCE_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-    ${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES} 
-	${QT_LIBRARIES} 
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(MINGW)
-  ADD_EXECUTABLE(dataRecorder WIN32 ${SRC_FILES})
+  ADD_EXECUTABLE(dataRecorder WIN32 main.cpp)
 ELSE()
-  ADD_EXECUTABLE(dataRecorder ${SRC_FILES})
+  ADD_EXECUTABLE(dataRecorder main.cpp)
 ENDIF()
-TARGET_LINK_LIBRARIES(dataRecorder rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(dataRecorder rtabmap_gui)
 
 SET_TARGET_PROPERTIES( dataRecorder 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-dataRecorder)
diff --git a/tools/DatabaseViewer/CMakeLists.txt b/tools/DatabaseViewer/CMakeLists.txt
index fc75a8e513..0c1dd55b50 100644
--- a/tools/DatabaseViewer/CMakeLists.txt
+++ b/tools/DatabaseViewer/CMakeLists.txt
@@ -1,38 +1,11 @@
 
-SET(SRC_FILES
-    main.cpp
-)
-
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES}
-	${QT_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(MINGW)
-  ADD_EXECUTABLE(databaseViewer WIN32 ${SRC_FILES})
+  ADD_EXECUTABLE(databaseViewer WIN32 main.cpp)
 ELSE()
-  ADD_EXECUTABLE(databaseViewer ${SRC_FILES})
+  ADD_EXECUTABLE(databaseViewer main.cpp)
 ENDIF()
 
-TARGET_LINK_LIBRARIES(databaseViewer rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(databaseViewer rtabmap_gui)
 
 SET_TARGET_PROPERTIES( databaseViewer 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-databaseViewer)
diff --git a/tools/DetectMoreLoopClosures/CMakeLists.txt b/tools/DetectMoreLoopClosures/CMakeLists.txt
index f18fe556db..19b2fbc871 100644
--- a/tools/DetectMoreLoopClosures/CMakeLists.txt
+++ b/tools/DetectMoreLoopClosures/CMakeLists.txt
@@ -1,35 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(detectMoreLoopClosures main.cpp)
   
-TARGET_LINK_LIBRARIES(detectMoreLoopClosures ${LIBRARIES})
+TARGET_LINK_LIBRARIES(detectMoreLoopClosures rtabmap_core)
 
 SET_TARGET_PROPERTIES( detectMoreLoopClosures 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-detectMoreLoopClosures)
diff --git a/tools/EpipolarGeometry/CMakeLists.txt b/tools/EpipolarGeometry/CMakeLists.txt
index b4ceba59e8..5f92f7b8b9 100644
--- a/tools/EpipolarGeometry/CMakeLists.txt
+++ b/tools/EpipolarGeometry/CMakeLists.txt
@@ -1,35 +1,10 @@
 
-SET(SRC_FILES
-    main.cpp
-)
-
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES} 
-	${QT_LIBRARIES} 
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(MINGW)
-  ADD_EXECUTABLE(epipolar_geometry WIN32 ${SRC_FILES})
+  ADD_EXECUTABLE(epipolar_geometry WIN32 main.cpp)
 ELSE()
-  ADD_EXECUTABLE(epipolar_geometry ${SRC_FILES})
+  ADD_EXECUTABLE(epipolar_geometry main.cpp)
 ENDIF()
-TARGET_LINK_LIBRARIES(epipolar_geometry rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(epipolar_geometry rtabmap_gui)
 
 SET_TARGET_PROPERTIES( epipolar_geometry 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-epipolar_geometry)
diff --git a/tools/EurocDataset/CMakeLists.txt b/tools/EurocDataset/CMakeLists.txt
index fd1859f885..c8b06dbc75 100644
--- a/tools/EurocDataset/CMakeLists.txt
+++ b/tools/EurocDataset/CMakeLists.txt
@@ -16,40 +16,20 @@ ENDIF(NOT yaml-cpp_FOUND)
 
 IF(yaml-cpp_FOUND)
 
-# inside rtabmap project (see below for external build)
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-	
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
 SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
     ${YAML_CPP_INCLUDE_DIRS}
 )
 
 SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
 	${YAML_CPP_LIBRARIES}
+	yaml-cpp
 )
 
 INCLUDE_DIRECTORIES(${INCLUDE_DIRS} yaml-cpp)
 
 ADD_EXECUTABLE(euroc_dataset main.cpp)
   
-TARGET_LINK_LIBRARIES(euroc_dataset ${LIBRARIES} yaml-cpp)
+TARGET_LINK_LIBRARIES(euroc_dataset rtabmap_core ${LIBRARIES})
 
 SET_TARGET_PROPERTIES( euroc_dataset 
     PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-euroc_dataset)
diff --git a/tools/Export/CMakeLists.txt b/tools/Export/CMakeLists.txt
index 792e8b8e14..fb3d5c4843 100644
--- a/tools/Export/CMakeLists.txt
+++ b/tools/Export/CMakeLists.txt
@@ -1,31 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(export main.cpp)
   
-TARGET_LINK_LIBRARIES(export ${LIBRARIES})
+TARGET_LINK_LIBRARIES(export rtabmap_core)
 
 SET_TARGET_PROPERTIES( export 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-export)
diff --git a/tools/ExtractObject/CMakeLists.txt b/tools/ExtractObject/CMakeLists.txt
index e57bea5858..0be69c08d5 100644
--- a/tools/ExtractObject/CMakeLists.txt
+++ b/tools/ExtractObject/CMakeLists.txt
@@ -1,26 +1,7 @@
 
-SET(SRC_FILES
-    main.cpp
-)
 
-SET(INCLUDE_DIRS
-	${PCL_INCLUDE_DIRS}
-	${PROJECT_SOURCE_DIR}/utilite/include
-)
-
-SET(LIBRARIES
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Make sure the compiler can find include files from our library.
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
-# Add binary called "consoleApp" that is built from the source file "main.cpp".
-# The extension is automatically found.
-ADD_EXECUTABLE(extractObject ${SRC_FILES})
-TARGET_LINK_LIBRARIES(extractObject rtabmap_utilite ${LIBRARIES})
+ADD_EXECUTABLE(extractObject main.cpp)
+TARGET_LINK_LIBRARIES(extractObject rtabmap_core)
 
 SET_TARGET_PROPERTIES( extractObject 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-extractObject)
diff --git a/tools/GlobalBundleAdjustment/CMakeLists.txt b/tools/GlobalBundleAdjustment/CMakeLists.txt
index b2853c3984..988ee0b91a 100644
--- a/tools/GlobalBundleAdjustment/CMakeLists.txt
+++ b/tools/GlobalBundleAdjustment/CMakeLists.txt
@@ -1,35 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(globalBundleAdjustment main.cpp)
   
-TARGET_LINK_LIBRARIES(globalBundleAdjustment ${LIBRARIES})
+TARGET_LINK_LIBRARIES(globalBundleAdjustment rtabmap_core)
 
 SET_TARGET_PROPERTIES( globalBundleAdjustment 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-globalBundleAdjustment)
diff --git a/tools/ImagesJoiner/CMakeLists.txt b/tools/ImagesJoiner/CMakeLists.txt
index c6979bfe71..879441e2da 100644
--- a/tools/ImagesJoiner/CMakeLists.txt
+++ b/tools/ImagesJoiner/CMakeLists.txt
@@ -1,25 +1,6 @@
 
-SET(SRC_FILES
-    main.cpp
-)
-
-SET(INCLUDE_DIRS
-	${PROJECT_SOURCE_DIR}/utilite/include
-    ${CMAKE_CURRENT_SOURCE_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-)
-
-# Make sure the compiler can find include files from our library.
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
-# Add binary called "imagesJoiner" that is built from the source file "main.cpp".
-# The extension is automatically found.
-ADD_EXECUTABLE(imagesJoiner ${SRC_FILES})
-TARGET_LINK_LIBRARIES(imagesJoiner rtabmap_utilite ${LIBRARIES})
+ADD_EXECUTABLE(imagesJoiner main.cpp)
+TARGET_LINK_LIBRARIES(imagesJoiner rtabmap_core)
 
 SET_TARGET_PROPERTIES( imagesJoiner 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-imagesJoiner)
diff --git a/tools/Info/CMakeLists.txt b/tools/Info/CMakeLists.txt
index dafcb77c59..fc2180c995 100644
--- a/tools/Info/CMakeLists.txt
+++ b/tools/Info/CMakeLists.txt
@@ -1,35 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(info main.cpp)
   
-TARGET_LINK_LIBRARIES(info ${LIBRARIES})
+TARGET_LINK_LIBRARIES(info rtabmap_core)
 
 SET_TARGET_PROPERTIES( info 
 	PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-info)
diff --git a/tools/KittiDataset/CMakeLists.txt b/tools/KittiDataset/CMakeLists.txt
index 81bcca771b..27bc793da2 100644
--- a/tools/KittiDataset/CMakeLists.txt
+++ b/tools/KittiDataset/CMakeLists.txt
@@ -1,37 +1,7 @@
-cmake_minimum_required(VERSION 2.8)
-
-# inside rtabmap project (see below for external build)
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-	
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(kitti_dataset main.cpp)
   
-TARGET_LINK_LIBRARIES(kitti_dataset ${LIBRARIES})
+TARGET_LINK_LIBRARIES(kitti_dataset rtabmap_core)
 
 SET_TARGET_PROPERTIES( kitti_dataset 
     PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-kitti_dataset)
diff --git a/tools/Matcher/CMakeLists.txt b/tools/Matcher/CMakeLists.txt
index 89dbeb80ec..39b490fb16 100644
--- a/tools/Matcher/CMakeLists.txt
+++ b/tools/Matcher/CMakeLists.txt
@@ -1,28 +1,6 @@
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-	${QT_LIBRARIES} 
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(matcher main.cpp)
-TARGET_LINK_LIBRARIES(matcher rtabmap_core rtabmap_utilite rtabmap_gui ${LIBRARIES})
+TARGET_LINK_LIBRARIES(matcher rtabmap_gui)
 
 SET_TARGET_PROPERTIES( matcher 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-matcher)
diff --git a/tools/OdometryViewer/CMakeLists.txt b/tools/OdometryViewer/CMakeLists.txt
index e5a1b5a55e..11ff94fc93 100644
--- a/tools/OdometryViewer/CMakeLists.txt
+++ b/tools/OdometryViewer/CMakeLists.txt
@@ -1,54 +1,10 @@
 
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/guilib/include
-    ${CMAKE_CURRENT_SOURCE_DIR}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-IF(QT4_FOUND)
-    INCLUDE(${QT_USE_FILE})
-ENDIF(QT4_FOUND)
-
-SET(LIBRARIES
-    ${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES} 
-	${QT_LIBRARIES} 
-)
-
-SET(SRC_FILES
-    main.cpp 
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 IF(MINGW)
-  ADD_EXECUTABLE(odometryViewer WIN32 ${SRC_FILES})
+  ADD_EXECUTABLE(odometryViewer WIN32 main.cpp)
 ELSE()
-  ADD_EXECUTABLE(odometryViewer ${SRC_FILES})
+  ADD_EXECUTABLE(odometryViewer main.cpp)
 ENDIF()
-TARGET_LINK_LIBRARIES(odometryViewer rtabmap_core rtabmap_gui rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(odometryViewer rtabmap_gui)
 
 SET_TARGET_PROPERTIES( odometryViewer 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-odometryViewer)
diff --git a/tools/Recovery/CMakeLists.txt b/tools/Recovery/CMakeLists.txt
index 61de000012..bd0151f919 100644
--- a/tools/Recovery/CMakeLists.txt
+++ b/tools/Recovery/CMakeLists.txt
@@ -1,35 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(recovery main.cpp)
   
-TARGET_LINK_LIBRARIES(recovery ${LIBRARIES})
+TARGET_LINK_LIBRARIES(recovery rtabmap_core)
 
 SET_TARGET_PROPERTIES( recovery 
 	PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-recovery)
diff --git a/tools/Report/CMakeLists.txt b/tools/Report/CMakeLists.txt
index 96bf26c778..c9c6c6e7d3 100644
--- a/tools/Report/CMakeLists.txt
+++ b/tools/Report/CMakeLists.txt
@@ -1,47 +1,11 @@
-cmake_minimum_required(VERSION 2.8)
 
-# inside rtabmap project (see below for external build)
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-    ${PROJECT_SOURCE_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/guilib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-    rtabmap_utilite
-)  
-	
-if(POLICY CMP0020)
-    cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-    ${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-    ${RTABMap_LIBRARIES}
-    ${OpenCV_LIBRARIES}
-    ${PCL_LIBRARIES}
-)
+set(LIBRARIES rtabmap_core)
 
 IF(QT4_FOUND OR Qt5_FOUND)
-    IF(QT4_FOUND)
-        INCLUDE(${QT_USE_FILE})
-    ENDIF(QT4_FOUND)
-    SET(LIBRARIES
-        ${LIBRARIES}
-        ${QT_LIBRARIES}
-        rtabmap_gui
-    )
     ADD_DEFINITIONS("-DWITH_QT")
+    set(LIBRARIES ${LIBRARIES} rtabmap_gui)
 ENDIF(QT4_FOUND OR Qt5_FOUND)
 
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(report main.cpp)
   
 TARGET_LINK_LIBRARIES(report ${LIBRARIES})
diff --git a/tools/Reprocess/CMakeLists.txt b/tools/Reprocess/CMakeLists.txt
index c5e707bd53..18ec5704ce 100644
--- a/tools/Reprocess/CMakeLists.txt
+++ b/tools/Reprocess/CMakeLists.txt
@@ -1,46 +1,7 @@
 
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-IF(octomap_FOUND)
-    SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${OCTOMAP_INCLUDE_DIRS}
-	)
-	SET(LIBRARIES
-		${LIBRARIES}
-		${OCTOMAP_LIBRARIES}
-	)
-ENDIF(octomap_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(reprocess main.cpp)
   
-TARGET_LINK_LIBRARIES(reprocess ${LIBRARIES})
+TARGET_LINK_LIBRARIES(reprocess rtabmap_core)
 
 SET_TARGET_PROPERTIES( reprocess 
 	PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-reprocess)
diff --git a/tools/RgbdDataset/CMakeLists.txt b/tools/RgbdDataset/CMakeLists.txt
index 80232c7670..918eb781f2 100644
--- a/tools/RgbdDataset/CMakeLists.txt
+++ b/tools/RgbdDataset/CMakeLists.txt
@@ -1,54 +1,7 @@
-cmake_minimum_required(VERSION 2.8)
-
-# inside rtabmap project (see below for external build)
-SET(RTABMap_INCLUDE_DIRS 
-    ${PROJECT_BINARY_DIR}/corelib/include
-    ${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-)
-SET(RTABMap_LIBRARIES 
-    rtabmap_core
-	rtabmap_utilite
-)  
-
-if(POLICY CMP0020)
-	cmake_policy(SET CMP0020 NEW)
-endif()
-
-SET(INCLUDE_DIRS
-	${RTABMap_INCLUDE_DIRS}
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${RTABMap_LIBRARIES}
-	${OpenCV_LIBRARIES}
-	${PCL_LIBRARIES}
-)
-
-# Hack as CameraRealsense2.h needs realsense2 include dir
-IF(realsense2_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${realsense2_INCLUDE_DIRS}
-	)
-ENDIF(realsense2_FOUND)
-
-# Hack as CameraK4A.h needs k4a include dir
-IF(k4a_FOUND)
-	SET(INCLUDE_DIRS
-		${INCLUDE_DIRS}
-		${k4a_INCLUDE_DIRS}
-	)
-ENDIF(k4a_FOUND)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(rgbd_dataset main.cpp)
   
-TARGET_LINK_LIBRARIES(rgbd_dataset ${LIBRARIES})
-
+TARGET_LINK_LIBRARIES(rgbd_dataset rtabmap_core)
 
 SET_TARGET_PROPERTIES( rgbd_dataset 
     PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-rgbd_dataset)
diff --git a/tools/StereoEval/CMakeLists.txt b/tools/StereoEval/CMakeLists.txt
index 87aa50555e..be6e422110 100644
--- a/tools/StereoEval/CMakeLists.txt
+++ b/tools/StereoEval/CMakeLists.txt
@@ -1,22 +1,6 @@
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-    ${OpenCV_INCLUDE_DIRS}
-    ${PCL_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES} 
-	${PCL_LIBRARIES}
-)
-
-add_definitions(${PCL_DEFINITIONS})
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
 
 ADD_EXECUTABLE(stereoEval main.cpp)
-TARGET_LINK_LIBRARIES(stereoEval rtabmap_core rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(stereoEval rtabmap_core)
 
 SET_TARGET_PROPERTIES( stereoEval 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-stereoEval)
diff --git a/tools/VocabularyComparison/CMakeLists.txt b/tools/VocabularyComparison/CMakeLists.txt
index ed35daf119..16bbcc076b 100644
--- a/tools/VocabularyComparison/CMakeLists.txt
+++ b/tools/VocabularyComparison/CMakeLists.txt
@@ -1,19 +1,6 @@
 
-SET(INCLUDE_DIRS
-    ${PROJECT_BINARY_DIR}/corelib/include
-	${PROJECT_SOURCE_DIR}/utilite/include
-	${PROJECT_SOURCE_DIR}/corelib/include
-    ${OpenCV_INCLUDE_DIRS}
-)
-
-SET(LIBRARIES
-	${OpenCV_LIBRARIES}
-)
-
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
-
 ADD_EXECUTABLE(vocabularyComparison main.cpp)
-TARGET_LINK_LIBRARIES(vocabularyComparison rtabmap_core rtabmap_utilite ${LIBRARIES})
+TARGET_LINK_LIBRARIES(vocabularyComparison rtabmap_core)
 
 SET_TARGET_PROPERTIES( vocabularyComparison 
   PROPERTIES OUTPUT_NAME ${PROJECT_PREFIX}-vocabularyComparison)
diff --git a/utilite/include/rtabmap/utilite/UConversion.h b/utilite/include/rtabmap/utilite/UConversion.h
index 024d09b0c7..705cee3a72 100644
--- a/utilite/include/rtabmap/utilite/UConversion.h
+++ b/utilite/include/rtabmap/utilite/UConversion.h
@@ -20,7 +20,7 @@
 #ifndef UCONVERSION_H
 #define UCONVERSION_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include <string>
 #include <vector>
@@ -48,7 +48,7 @@
  * @param after the new character replacing the old one
  * @return the modified string
  */
-std::string UTILITE_EXP uReplaceChar(const std::string & str, char before, char after);
+std::string UTILITE_EXPORT uReplaceChar(const std::string & str, char before, char after);
 
 /**
  * Replace old characters in a string with the specified string.
@@ -64,7 +64,7 @@ std::string UTILITE_EXP uReplaceChar(const std::string & str, char before, char
  * @param after the new string replacing the old character
  * @return the modified string
  */
-std::string UTILITE_EXP uReplaceChar(const std::string & str, char before, const std::string & after);
+std::string UTILITE_EXPORT uReplaceChar(const std::string & str, char before, const std::string & after);
 
 /**
  * Transform characters from a string to upper case.
@@ -77,7 +77,7 @@ std::string UTILITE_EXP uReplaceChar(const std::string & str, char before, const
  * @param str the string
  * @return the modified string
  */
-std::string UTILITE_EXP uToUpperCase(const std::string & str);
+std::string UTILITE_EXPORT uToUpperCase(const std::string & str);
 
 /**
  * Transform characters from a string to lower case.
@@ -90,53 +90,53 @@ std::string UTILITE_EXP uToUpperCase(const std::string & str);
  * @param str the string
  * @return the modified string
  */
-std::string UTILITE_EXP uToLowerCase(const std::string & str);
+std::string UTILITE_EXPORT uToLowerCase(const std::string & str);
 
 /**
  * Convert a number (unsigned int) to a string.
  * @param number the number to convert in a string
  * @return the string
  */
-std::string UTILITE_EXP uNumber2Str(unsigned int number);
+std::string UTILITE_EXPORT uNumber2Str(unsigned int number);
 /**
  * Convert a number (int) to a string.
  * @param number the number to convert in a string
  * @return the string
  */
-std::string UTILITE_EXP uNumber2Str(int number);
+std::string UTILITE_EXPORT uNumber2Str(int number);
 /**
  * Convert a number (float) to a string.
  * @param number the number to convert in a string
  * @return the string
  */
-std::string UTILITE_EXP uNumber2Str(float number, int precision=6, bool fixed = false);
+std::string UTILITE_EXPORT uNumber2Str(float number, int precision=6, bool fixed = false);
 /**
  * Convert a number (double) to a string.
  * @param number the number to convert in a string
  * @return the string
  */
-std::string UTILITE_EXP uNumber2Str(double number, int precision=6, bool fixed = false);
+std::string UTILITE_EXPORT uNumber2Str(double number, int precision=6, bool fixed = false);
 
 /**
  * Convert a string to an integer.
  * @param the string
  * @return the number
  */
-int UTILITE_EXP uStr2Int(const std::string & str);
+int UTILITE_EXPORT uStr2Int(const std::string & str);
 
 /**
  * Convert a string to a float independent of the locale (comma/dot).
  * @param the string
  * @return the number
  */
-float UTILITE_EXP uStr2Float(const std::string & str);
+float UTILITE_EXPORT uStr2Float(const std::string & str);
 
 /**
  * Convert a string to a double independent of the locale (comma/dot).
  * @param the string
  * @return the number
  */
-double UTILITE_EXP uStr2Double(const std::string & str);
+double UTILITE_EXPORT uStr2Double(const std::string & str);
 
 
 /**
@@ -145,7 +145,7 @@ double UTILITE_EXP uStr2Double(const std::string & str);
  * @param boolean the boolean to convert in a string
  * @return the string
  */
-std::string UTILITE_EXP uBool2Str(bool boolean);
+std::string UTILITE_EXPORT uBool2Str(bool boolean);
 /**
  * Convert a string to a boolean.
  * The format used is :
@@ -153,22 +153,22 @@ std::string UTILITE_EXP uBool2Str(bool boolean);
  * @param str the string to convert in a boolean
  * @return the boolean
  */
-bool UTILITE_EXP uStr2Bool(const char * str);
-bool UTILITE_EXP uStr2Bool(const std::string & str);
+bool UTILITE_EXPORT uStr2Bool(const char * str);
+bool UTILITE_EXPORT uStr2Bool(const std::string & str);
 
 /**
  * Convert a string to an array of bytes including the null character ('\0').
  * @param str the string
  * @return the array of bytes
  */
-std::vector<unsigned char> UTILITE_EXP uStr2Bytes(const std::string & str);
+std::vector<unsigned char> UTILITE_EXPORT uStr2Bytes(const std::string & str);
 
 /**
  * Convert an array of bytes to string, the array of bytes must end with the null character ('\0').
  * @param bytes the array of bytes
  * @return the string
  */
-std::string UTILITE_EXP uBytes2Str(const std::vector<unsigned char> & bytes);
+std::string UTILITE_EXPORT uBytes2Str(const std::vector<unsigned char> & bytes);
 
 /**
  * Convert a bytes array to an hexadecimal string.
@@ -185,7 +185,7 @@ std::string UTILITE_EXP uBytes2Str(const std::vector<unsigned char> & bytes);
  * @param bytesLen the length of the bytes array
  * @return the hexadecimal string
  */
-std::string UTILITE_EXP uBytes2Hex(const char * bytes, unsigned int bytesLen);
+std::string UTILITE_EXPORT uBytes2Hex(const char * bytes, unsigned int bytesLen);
 /**
  * Convert an hexadecimal string to a bytes array.
  * The string must be pair length. The hexadecimal
@@ -200,7 +200,7 @@ std::string UTILITE_EXP uBytes2Hex(const char * bytes, unsigned int bytesLen);
  * @param hex the hexadecimal string
  * @return the bytes array
  */
-std::vector<char> UTILITE_EXP uHex2Bytes(const std::string & hex);
+std::vector<char> UTILITE_EXPORT uHex2Bytes(const std::string & hex);
 /**
  * Convert an hexadecimal string to a bytes array.
  * The string must be pair length. The hexadecimal
@@ -215,7 +215,7 @@ std::vector<char> UTILITE_EXP uHex2Bytes(const std::string & hex);
  * @param bytesLen the hexadecimal string length
  * @return the bytes array
  */
-std::vector<char> UTILITE_EXP uHex2Bytes(const char * hex, int hexLen);
+std::vector<char> UTILITE_EXPORT uHex2Bytes(const char * hex, int hexLen);
 
 /**
  * Convert an hexadecimal string to an ascii string. A convenient way
@@ -233,7 +233,7 @@ std::vector<char> UTILITE_EXP uHex2Bytes(const char * hex, int hexLen);
  * @param hex the hexadecimal string
  * @return the ascii string
  */
-std::string UTILITE_EXP uHex2Str(const std::string & hex);
+std::string UTILITE_EXPORT uHex2Str(const std::string & hex);
 
 /**
  * Convert hexadecimal (left or right part) value to an ascii character.
@@ -247,7 +247,7 @@ std::string UTILITE_EXP uHex2Str(const std::string & hex);
  * @param rightPart If we want the character corresponding to the right of left part (4 bits) of the byte value.
  * @return the ascii character (in upper case)
  */
-unsigned char UTILITE_EXP uHex2Ascii(const unsigned char & c, bool rightPart);
+unsigned char UTILITE_EXPORT uHex2Ascii(const unsigned char & c, bool rightPart);
 
 /**
  * Convert an ascii character to an hexadecimal value (right 4 bits).
@@ -261,30 +261,30 @@ unsigned char UTILITE_EXP uHex2Ascii(const unsigned char & c, bool rightPart);
  * @param c the ascii character
  * @return the hexadecimal value
  */
-unsigned char UTILITE_EXP uAscii2Hex(const unsigned char & c);
+unsigned char UTILITE_EXPORT uAscii2Hex(const unsigned char & c);
 
 /**
  * Format a string like printf, and return it as a std::string
  */
-std::string UTILITE_EXP uFormatv (const char *fmt, va_list ap);
+std::string UTILITE_EXPORT uFormatv (const char *fmt, va_list ap);
 
 /**
  * Format a string like printf, and return it as a std::string
  */
-std::string UTILITE_EXP uFormat (const char *fmt, ...);
+std::string UTILITE_EXPORT uFormat (const char *fmt, ...);
 
 #ifdef _WIN32
 /**
  * Convert multi-byte string to unicode (wide-char) string.
  * Note that returned whar_t * must be deleted : delete [] wText;
  */
-UTILITE_EXP wchar_t * createWCharFromChar(const char * text);
+UTILITE_EXPORT wchar_t * createWCharFromChar(const char * text);
 
 /**
  * Convert unicode (wide-char) string to multi-byte string.
  * Note that returned char * must be deleted : delete [] text;
  */
-UTILITE_EXP char * createCharFromWChar(const wchar_t * wText);
+UTILITE_EXPORT char * createCharFromWChar(const wchar_t * wText);
 #endif
 
 #endif /* UCONVERSION_H */
diff --git a/utilite/include/rtabmap/utilite/UDestroyer.h b/utilite/include/rtabmap/utilite/UDestroyer.h
index 08e665a6a7..187320f82f 100644
--- a/utilite/include/rtabmap/utilite/UDestroyer.h
+++ b/utilite/include/rtabmap/utilite/UDestroyer.h
@@ -20,8 +20,6 @@
 #ifndef UDESTROYER_H
 #define UDESTROYER_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
-
 /**
  * This class is used to delete a dynamically created
  * objects. It was mainly designed to remove dynamically created Singleton.
diff --git a/utilite/include/rtabmap/utilite/UDirectory.h b/utilite/include/rtabmap/utilite/UDirectory.h
index caed174c98..9b52fbc837 100644
--- a/utilite/include/rtabmap/utilite/UDirectory.h
+++ b/utilite/include/rtabmap/utilite/UDirectory.h
@@ -20,7 +20,7 @@
 #ifndef UDIRECTORY_H
 #define UDIRECTORY_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include <string>
 #include <vector>
@@ -31,7 +31,7 @@
  *
  * This class can be used to get file names in a directory.
  */
-class UTILITE_EXP UDirectory
+class UTILITE_EXPORT UDirectory
 {
 public:
 	/**
diff --git a/utilite/include/rtabmap/utilite/UEvent.h b/utilite/include/rtabmap/utilite/UEvent.h
index 6dc5b61d80..68d087cdb4 100644
--- a/utilite/include/rtabmap/utilite/UEvent.h
+++ b/utilite/include/rtabmap/utilite/UEvent.h
@@ -20,7 +20,7 @@
 #ifndef UEVENT_H
 #define UEVENT_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include <string>
 
@@ -54,7 +54,7 @@ class UEventsHandler;
  * @see UEventsHandler
  * @see getClassName()
  */
-class UTILITE_EXP UEvent{
+class UTILITE_EXPORT UEvent{
 public:
     virtual ~UEvent() {}
 
diff --git a/utilite/include/rtabmap/utilite/UEventsHandler.h b/utilite/include/rtabmap/utilite/UEventsHandler.h
index b80b6fea8d..6cbeb2d6bb 100644
--- a/utilite/include/rtabmap/utilite/UEventsHandler.h
+++ b/utilite/include/rtabmap/utilite/UEventsHandler.h
@@ -20,7 +20,7 @@
 #ifndef UEVENTSHANDLER_H
 #define UEVENTSHANDLER_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UEventsSender.h"
 class UEvent;
@@ -125,7 +125,7 @@ class UEvent;
  * @see UThreadNode
  *
  */
-class UTILITE_EXP UEventsHandler : public UEventsSender {
+class UTILITE_EXPORT UEventsHandler : public UEventsSender {
 public:
 
 	void registerToEventsManager();
diff --git a/utilite/include/rtabmap/utilite/UEventsManager.h b/utilite/include/rtabmap/utilite/UEventsManager.h
index b4a51efae4..02a78de9f1 100644
--- a/utilite/include/rtabmap/utilite/UEventsManager.h
+++ b/utilite/include/rtabmap/utilite/UEventsManager.h
@@ -20,7 +20,7 @@
 #ifndef UEVENTSMANAGER_H
 #define UEVENTSMANAGER_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UEventsHandler.h"
 #include "rtabmap/utilite/UThreadNode.h"
@@ -75,7 +75,7 @@ class UEventDispatcher : public UThread
  * @see addHandler()
  * @see removeHandler()
  */
-class UTILITE_EXP UEventsManager : public UThread{
+class UTILITE_EXPORT UEventsManager : public UThread{
 
 public:
 
diff --git a/utilite/include/rtabmap/utilite/UEventsSender.h b/utilite/include/rtabmap/utilite/UEventsSender.h
index fc5d7eeb51..9dfe98e18f 100644
--- a/utilite/include/rtabmap/utilite/UEventsSender.h
+++ b/utilite/include/rtabmap/utilite/UEventsSender.h
@@ -8,11 +8,11 @@
 #ifndef UEVENTSSENDER_H_
 #define UEVENTSSENDER_H_
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 class UEvent;
 
-class UTILITE_EXP UEventsSender
+class UTILITE_EXPORT UEventsSender
 {
 public:
 	UEventsSender(){}
diff --git a/utilite/include/rtabmap/utilite/UFile.h b/utilite/include/rtabmap/utilite/UFile.h
index 610178fb77..c5021d41d1 100644
--- a/utilite/include/rtabmap/utilite/UFile.h
+++ b/utilite/include/rtabmap/utilite/UFile.h
@@ -20,7 +20,7 @@
 #ifndef FILE_H
 #define FILE_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UDirectory.h"
 #include <string>
@@ -30,7 +30,7 @@
  *
  * This class can be used to modify/erase files on hard drive.
  */
-class UTILITE_EXP UFile
+class UTILITE_EXPORT UFile
 {
 public:
 	/**
diff --git a/utilite/include/rtabmap/utilite/ULogger.h b/utilite/include/rtabmap/utilite/ULogger.h
index 20f2f46a7f..dd8dae4114 100644
--- a/utilite/include/rtabmap/utilite/ULogger.h
+++ b/utilite/include/rtabmap/utilite/ULogger.h
@@ -20,7 +20,7 @@
 #ifndef ULOGGER_H
 #define ULOGGER_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UMutex.h"
 #include "rtabmap/utilite/UDestroyer.h"
@@ -226,7 +226,7 @@ class ULogEvent : public UEvent
  * @see UDEBUG(), UINFO(), UWARN(), UERROR(), UFATAL()
  *
  */
-class UTILITE_EXP ULogger
+class UTILITE_EXPORT ULogger
 {
 
 public:
diff --git a/utilite/include/rtabmap/utilite/UMath.h b/utilite/include/rtabmap/utilite/UMath.h
index bd03632268..ac15c43ae7 100644
--- a/utilite/include/rtabmap/utilite/UMath.h
+++ b/utilite/include/rtabmap/utilite/UMath.h
@@ -24,8 +24,6 @@
     \brief Basic mathematics functions
 */
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
-
 #include <cmath>
 #include <list>
 #include <vector>
diff --git a/utilite/include/rtabmap/utilite/UProcessInfo.h b/utilite/include/rtabmap/utilite/UProcessInfo.h
index 1b54fd3b38..66d2b3a873 100644
--- a/utilite/include/rtabmap/utilite/UProcessInfo.h
+++ b/utilite/include/rtabmap/utilite/UProcessInfo.h
@@ -20,13 +20,13 @@
 #ifndef UPROCESSINFO_H
 #define UPROCESSINFO_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 /**
  * This class is used to get some informations
  * about the current process.
  */
-class UTILITE_EXP UProcessInfo {
+class UTILITE_EXPORT UProcessInfo {
 public:
 	UProcessInfo();
 	virtual ~UProcessInfo();
diff --git a/utilite/include/rtabmap/utilite/UThread.h b/utilite/include/rtabmap/utilite/UThread.h
index c0e3d48fe9..2d5781f2e0 100644
--- a/utilite/include/rtabmap/utilite/UThread.h
+++ b/utilite/include/rtabmap/utilite/UThread.h
@@ -20,7 +20,7 @@
 #ifndef UTHREADNODE_H
 #define UTHREADNODE_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #include "rtabmap/utilite/UThreadC.h"
 
@@ -83,7 +83,7 @@
  * @see mainLoop()
  *
  */
-class UTILITE_EXP UThread : public UThreadC<void>
+class UTILITE_EXPORT UThread : public UThreadC<void>
 {
 public:
     /**
diff --git a/utilite/include/rtabmap/utilite/UTimer.h b/utilite/include/rtabmap/utilite/UTimer.h
index 6120630d5d..42f6d2dd74 100644
--- a/utilite/include/rtabmap/utilite/UTimer.h
+++ b/utilite/include/rtabmap/utilite/UTimer.h
@@ -20,7 +20,7 @@
 #ifndef UTIMER_H
 #define UTIMER_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 
 #ifdef _WIN32
 #include <windows.h>
@@ -43,7 +43,7 @@
  *      ...
  * @endcode
  */
-class UTILITE_EXP UTimer
+class UTILITE_EXPORT UTimer
 {
 public:
     UTimer();
@@ -81,7 +81,7 @@ class UTILITE_EXP UTimer
 	 * @return double the interval in seconds.
 	 * @deprecated use elapsed() instead.
 	 */
-    UTILITE_DEPRECATED(double getInterval());
+    UTILITE_DEPRECATED double getInterval();
 
     /** 
      * This method is used to get the interval of 
diff --git a/utilite/include/rtabmap/utilite/UVariant.h b/utilite/include/rtabmap/utilite/UVariant.h
index 94b6ed18fd..faa6e26831 100644
--- a/utilite/include/rtabmap/utilite/UVariant.h
+++ b/utilite/include/rtabmap/utilite/UVariant.h
@@ -20,14 +20,14 @@
 #ifndef UVARIANT_H
 #define UVARIANT_H
 
-#include "rtabmap/utilite/UtiLiteExp.h" // DLL export/import defines
+#include "rtabmap/utilite/utilite_export.h" // DLL export/import defines
 #include <string>
 #include <vector>
 
 /**
  * Experimental class...
  */
-class UTILITE_EXP UVariant
+class UTILITE_EXPORT UVariant
 {
 public:
 	enum Type{
diff --git a/utilite/include/rtabmap/utilite/UtiLiteExp.h b/utilite/include/rtabmap/utilite/UtiLiteExp.h
deleted file mode 100644
index 3a208ecfec..0000000000
--- a/utilite/include/rtabmap/utilite/UtiLiteExp.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
-*  utilite is a cross-platform library with
-*  useful utilities for fast and small developing.
-*  Copyright (C) 2010  Mathieu Labbe
-*
-*  utilite is free library: you can redistribute it and/or modify
-*  it under the terms of the GNU Lesser General Public License as published by
-*  the Free Software Foundation, either version 3 of the License, or
-*  (at your option) any later version.
-*
-*  utilite is distributed in the hope that it will be useful,
-*  but WITHOUT ANY WARRANTY; without even the implied warranty of
-*  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-*  GNU Lesser General Public License for more details.
-*
-*  You should have received a copy of the GNU Lesser General Public License
-*  along with this program.  If not, see <http://www.gnu.org/licenses/>.
-*/
-
-#ifndef UTILITEEXP_H
-#define UTILITEEXP_H
-
-/**
- * Used mainly on Windows for dynamic linked libraries (dll).
- */
-#if defined(_WIN32)
-  #if defined(rtabmap_utilite_EXPORTS)
-    #define UTILITE_EXP   __declspec( dllexport )
-  #else
-    #define UTILITE_EXP   __declspec( dllimport )
-  #endif
-#else
-  #define UTILITE_EXP
-#endif
-
-#ifdef __GNUC__
-#define UTILITE_DEPRECATED(func) func __attribute__ ((deprecated))
-#elif defined(_MSC_VER)
-#define UTILITE_DEPRECATED(func) __declspec(deprecated) func
-#else
-#pragma message("WARNING: You need to implement DEPRECATED for this compiler")
-#define UTILITE_DEPRECATED(func) func
-#endif
-
-#endif
-
diff --git a/utilite/include/rtabmap/utilite/Win32/UThreadC.h b/utilite/include/rtabmap/utilite/Win32/UThreadC.h
index 356b1f9f2e..5395e7f70c 100644
--- a/utilite/include/rtabmap/utilite/Win32/UThreadC.h
+++ b/utilite/include/rtabmap/utilite/Win32/UThreadC.h
@@ -36,6 +36,7 @@
 #ifndef _U_Thread_Win32_
 #define _U_Thread_Win32_
 
+#include "rtabmap/utilite/utilite_export.h"
 #include "rtabmap/utilite/Win32/UWin32.h"
 #include "rtabmap/utilite/USemaphore.h"
 #include "rtabmap/utilite/UMutex.h"
@@ -87,7 +88,7 @@ template
 <
   typename Thread_T
 >
-class UTILITE_EXP UThreadC
+class UTILITE_EXPORT UThreadC
 {
   private:
     struct Instance;
@@ -241,7 +242,7 @@ class UTILITE_EXP UThreadC
 //  Explicit Specialization of void
 //
 template<>
-class UTILITE_EXP UThreadC<void>
+class UTILITE_EXPORT UThreadC<void>
 {
   private:
     struct Instance;
diff --git a/utilite/include/rtabmap/utilite/Win32/UWin32.h b/utilite/include/rtabmap/utilite/Win32/UWin32.h
index d21a745125..49d02b6955 100644
--- a/utilite/include/rtabmap/utilite/Win32/UWin32.h
+++ b/utilite/include/rtabmap/utilite/Win32/UWin32.h
@@ -9,8 +9,6 @@
 #ifndef _U_Win32_
 #define _U_Win32_
 
-#include "rtabmap/utilite/UtiLiteExp.h"
-
   #if !defined(_WINDOWS_)
   // WIN32 Excludes
   #ifdef WIN32_LEAN_AND_MEAN
diff --git a/utilite/src/CMakeLists.txt b/utilite/src/CMakeLists.txt
index f174fc2a39..a7b353fd30 100644
--- a/utilite/src/CMakeLists.txt
+++ b/utilite/src/CMakeLists.txt
@@ -13,36 +13,58 @@ SET(SRC_FILES
     UVariant.cpp
 )
 
-SET(INCLUDE_DIRS
-	${CMAKE_CURRENT_SOURCE_DIR}/../include
-	${PTHREADS_INCLUDE_DIR}
-)
+ADD_LIBRARY(rtabmap_utilite ${SRC_FILES})
 
-# Make sure the compiler can find include files from our library.
-INCLUDE_DIRECTORIES(${INCLUDE_DIRS})
+generate_export_header(rtabmap_utilite 
+  BASE_NAME utilite)
+
+target_include_directories(rtabmap_utilite PUBLIC 
+  "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/../include;${CMAKE_CURRENT_BINARY_DIR}/include;${PTHREADS_INCLUDE_DIR}>"
+  "$<INSTALL_INTERFACE:${INSTALL_INCLUDE_DIR};${PTHREADS_INCLUDE_DIR}>")
 
-ADD_LIBRARY(rtabmap_utilite ${SRC_FILES})
 IF(MINGW)
-    TARGET_LINK_LIBRARIES(rtabmap_utilite ${PTHREADS_LIBRARY} "-lpsapi")
+    TARGET_LINK_LIBRARIES(rtabmap_utilite PRIVATE ${PTHREADS_LIBRARY} "-lpsapi")
 ELSEIF(WIN32 OR MSVC)
 	FIND_LIBRARY(PSAPI_LIBRARIES NAMES psapi libpsapi.dll.a libpsapi.a libpsapi.lib )
-	TARGET_LINK_LIBRARIES(rtabmap_utilite ${PSAPI_LIBRARIES})
+	TARGET_LINK_LIBRARIES(rtabmap_utilite PRIVATE ${PSAPI_LIBRARIES})
 ELSE()
-    TARGET_LINK_LIBRARIES(rtabmap_utilite ${PTHREADS_LIBRARY})
+    TARGET_LINK_LIBRARIES(rtabmap_utilite PRIVATE ${PTHREADS_LIBRARY})
 ENDIF()
 
-
 SET_TARGET_PROPERTIES(
-     rtabmap_utilite
+     rtabmap_utilite 
    PROPERTIES
      VERSION ${RTABMAP_VERSION}
      SOVERSION ${RTABMAP_MAJOR_VERSION}.${RTABMAP_MINOR_VERSION}
 )
-
-INSTALL(TARGETS rtabmap_utilite
+INSTALL(TARGETS rtabmap_utilite EXPORT rtabmap_utiliteTargets
         RUNTIME DESTINATION "${CMAKE_INSTALL_BINDIR}" COMPONENT runtime
         LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel
         ARCHIVE DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT devel)
-		
-install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/../include/ DESTINATION "${INSTALL_INCLUDE_DIR}" COMPONENT devel FILES_MATCHING PATTERN "*.h" PATTERN ".svn" EXCLUDE)
 
+configure_file(
+  ${CMAKE_CURRENT_BINARY_DIR}/utilite_export.h
+  ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}/utilite/utilite_export.h
+  COPYONLY)
+
+install(
+  DIRECTORY 
+    ${CMAKE_CURRENT_SOURCE_DIR}/../include/${PROJECT_PREFIX}
+    ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_PREFIX}
+  DESTINATION 
+    "${INSTALL_INCLUDE_DIR}" 
+  COMPONENT 
+    devel 
+  FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp")
+
+export(EXPORT rtabmap_utiliteTargets
+  FILE "${CMAKE_CURRENT_BINARY_DIR}/../../${PROJECT_NAME}_utiliteTargets.cmake"
+)
+install(EXPORT rtabmap_utiliteTargets
+  FILE
+    ${PROJECT_NAME}_utiliteTargets.cmake
+  DESTINATION
+    ${INSTALL_CMAKE_DIR}
+  COMPONENT
+    devel
+)
\ No newline at end of file