Skip to content

Commit

Permalink
Refactored RegistrationIcp: libpointmatcher yaml config usage / integ…
Browse files Browse the repository at this point in the history
…rated CCCoreLib (#704)

* Refactored RegistrationIcp so that libpointmatcher yaml can work with icp odometry (we can then avoid refiltering data with local map of F2M). All data filtering (including libpointmatcher DataFilters) are done at the beginning of the function.

* ICP: Restored ref and data scans order for libpointmatcher (seems more stable this way).

* Fixed compilation error without libpointmatcher

* CCCoreLib integration (Icp/Strategy=2). Icp/PMForce4DoF is now Icp/Force4DoF. Icp/PM is now Icp/Strategy. Icp/PMOutlierRatio is now Icp/OutlierRatio.

* Fixed build without CCCoreLib

* Cleanup RegistrationIcp from third party functions.

* Preferences: disable libpointmatcher and cccorlib options if not available
  • Loading branch information
matlabbe authored Mar 27, 2021
1 parent c4d127c commit 06e85e1
Show file tree
Hide file tree
Showing 18 changed files with 2,279 additions and 1,812 deletions.
25 changes: 22 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,7 @@ option(WITH_CERES "Include Ceres support" ON)
option(WITH_VERTIGO "Include Vertigo support" ON)
option(WITH_CVSBA "Include cvsba support" ON)
option(WITH_POINTMATCHER "Include libpointmatcher support" ON)
option(WITH_CCCORELIB "Include CCCoreLib support" ON)
option(WITH_LOAM "Include LOAM support" ON)
option(WITH_FLYCAPTURE2 "Include FlyCapture2/Triclops support" ON)
option(WITH_ZED "Include ZED sdk support" ON)
Expand Down Expand Up @@ -460,6 +461,13 @@ IF(libpointmatcher_FOUND OR GTSAM_FOUND)
ENDIF(WIN32)
ENDIF(libpointmatcher_FOUND OR GTSAM_FOUND)

IF(WITH_CCCORELIB)
find_package(CCCoreLib QUIET)
IF(CCCoreLib_FOUND)
MESSAGE(STATUS "Found CCCoreLib: ${CCCoreLib_INCLUDE_DIRS}")
ENDIF(CCCoreLib_FOUND)
ENDIF(WITH_CCCORELIB)

IF(WITH_LOAM)
find_package(loam_velodyne QUIET)
IF(loam_velodyne_FOUND)
Expand Down Expand Up @@ -642,8 +650,8 @@ IF(WITH_ORB_SLAM AND NOT G2O_FOUND)
ENDIF(WITH_ORB_SLAM AND NOT G2O_FOUND)

IF(NOT MSVC)
IF(loam_velodyne_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND)
#LOAM, PCL>=1.10 and latest g2o require c++14
IF(loam_velodyne_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND OR CCCoreLib_FOUND)
#LOAM, PCL>=1.10, latest g2o and CCCoreLib require c++14
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
IF(COMPILER_SUPPORTS_CXX14)
Expand All @@ -652,7 +660,7 @@ IF(NOT MSVC)
ELSE()
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++14 support. Please use a different C++ compiler if you want to use LOAM, latest PCL or g2o.")
ENDIF()
ENDIF(loam_velodyne_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND)
ENDIF(loam_velodyne_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND OR CCCoreLib_FOUND)

IF( (NOT (${CMAKE_CXX_STANDARD} STREQUAL "14")) AND (
G2O_FOUND OR
Expand Down Expand Up @@ -764,6 +772,9 @@ ENDIF()
IF(NOT libpointmatcher_FOUND)
SET(POINTMATCHER "//")
ENDIF(NOT libpointmatcher_FOUND)
IF(NOT CCCoreLib_FOUND)
SET(CCCORELIB "//")
ENDIF(NOT CCCoreLib_FOUND)
IF(NOT FastCV_FOUND)
SET(FASTCV "//")
ENDIF(NOT FastCV_FOUND)
Expand Down Expand Up @@ -1254,6 +1265,14 @@ ELSE()
MESSAGE(STATUS " *With libpointmatcher = NO (libpointmatcher not found)")
ENDIF()

IF(CCCoreLib_FOUND)
MESSAGE(STATUS " *With CCCoreLib = YES (License: GPLv2)")
ELSEIF(NOT WITH_POINTMATCHER)
MESSAGE(STATUS " *With CCCoreLib = NO (WITH_CCCORELIB=OFF)")
ELSE()
MESSAGE(STATUS " *With CCCoreLib = NO (CCCoreLib not found)")
ENDIF()

MESSAGE(STATUS "")
MESSAGE(STATUS " Reconstruction Approaches:")
IF(octomap_FOUND)
Expand Down
1 change: 1 addition & 0 deletions Version.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
@K4A@#define RTABMAP_K4A
@CVSBA@#define RTABMAP_CVSBA
@POINTMATCHER@#define RTABMAP_POINTMATCHER
@CCCORELIB@#define RTABMAP_CCCORELIB
@FASTCV@#define RTABMAP_FASTCV
@PDAL@#define RTABMAP_PDAL
@LOAM@#define RTABMAP_LOAM
Expand Down
18 changes: 11 additions & 7 deletions corelib/include/rtabmap/core/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -637,6 +637,11 @@ class RTABMAP_EXP Parameters
RTABMAP_PARAM(GMS, ThresholdFactor, double, 6.0, "The higher, the less matches.");

// ICP registration parameters
#ifdef RTABMAP_POINTMATCHER
RTABMAP_PARAM(Icp, Strategy, int, 1, "ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
#else
RTABMAP_PARAM(Icp, Strategy, int, 0, "ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
#endif
RTABMAP_PARAM(Icp, MaxTranslation, float, 0.2, "Maximum ICP translation correction accepted (m).");
RTABMAP_PARAM(Icp, MaxRotation, float, 0.78, "Maximum ICP rotation correction accepted (rad).");
RTABMAP_PARAM(Icp, VoxelSize, float, 0.05, "Uniform sampling voxel size (0=disabled).");
Expand All @@ -651,6 +656,7 @@ class RTABMAP_EXP Parameters
RTABMAP_PARAM(Icp, Iterations, int, 30, "Max iterations.");
RTABMAP_PARAM(Icp, Epsilon, float, 0, "Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.");
RTABMAP_PARAM(Icp, CorrespondenceRatio, float, 0.1, "Ratio of matching correspondences to accept the transform.");
RTABMAP_PARAM(Icp, Force4DoF, bool, false, uFormat("Limit ICP to x, y, z and yaw DoF. Available if %s > 0.", kIcpStrategy().c_str()));
#ifdef RTABMAP_POINTMATCHER
RTABMAP_PARAM(Icp, PointToPlane, bool, true, "Use point to plane ICP.");
#else
Expand All @@ -661,19 +667,17 @@ class RTABMAP_EXP Parameters
RTABMAP_PARAM(Icp, PointToPlaneGroundNormalsUp, float, 0.0, "Invert normals on ground if they are pointing down (useful for ring-like 3D LiDARs). 0 means disabled, 1 means only normals perfectly aligned with -z axis. This is only done with 3D scans.");
RTABMAP_PARAM(Icp, PointToPlaneMinComplexity, float, 0.02, uFormat("Minimum structural complexity (0.0=low, 1.0=high) of the scan to do PointToPlane registration, otherwise PointToPoint registration is done instead and strategy from %s is used. This check is done only when %s=true.", kIcpPointToPlaneLowComplexityStrategy().c_str(), kIcpPointToPlane().c_str()));
RTABMAP_PARAM(Icp, PointToPlaneLowComplexityStrategy, int, 1, uFormat("If structural complexity is below %s: set to 0 to so that the transform is automatically rejected, set to 1 to limit ICP correction in axes with most constraints (e.g., for a corridor-like environment, the resulting transform will be limited in y and yaw, x will taken from the guess), set to 2 to accept \"as is\" the transform computed by PointToPoint.", kIcpPointToPlaneMinComplexity().c_str()));
RTABMAP_PARAM(Icp, OutlierRatio, float, 0.85, uFormat("Outlier ratio used with %s>0. For libpointmatcher, this parameter set TrimmedDistOutlierFilter/ratio for convenience when configuration file is not set. For CCCoreLib, this parameter set the \"finalOverlapRatio\". The value should be between 0 and 1.", kIcpStrategy().c_str()));

// libpointmatcher
#ifdef RTABMAP_POINTMATCHER
RTABMAP_PARAM(Icp, PM, bool, true, "Use libpointmatcher for ICP registration instead of PCL's implementation.");
#else
RTABMAP_PARAM(Icp, PM, bool, false, "Use libpointmatcher for ICP registration instead of PCL's implementation.");
#endif
RTABMAP_PARAM_STR(Icp, PMConfig, "", uFormat("Configuration file (*.yaml) used by libpointmatcher. Note that data filters set for libpointmatcher are done after filtering done by rtabmap (i.e., %s, %s), so make sure to disable those in rtabmap if you want to use only those from libpointmatcher. Parameters %s, %s and %s are also ignored if configuration file is set.", kIcpVoxelSize().c_str(), kIcpDownsamplingStep().c_str(), kIcpIterations().c_str(), kIcpEpsilon().c_str(), kIcpMaxCorrespondenceDistance().c_str()).c_str());
RTABMAP_PARAM(Icp, PMMatcherKnn, int, 1, "KDTreeMatcher/knn: number of nearest neighbors to consider it the reference. For convenience when configuration file is not set.");
RTABMAP_PARAM(Icp, PMMatcherEpsilon, float, 0.0, "KDTreeMatcher/epsilon: approximation to use for the nearest-neighbor search. For convenience when configuration file is not set.");
RTABMAP_PARAM(Icp, PMMatcherIntensity, bool, false, uFormat("KDTreeMatcher: among nearest neighbors, keep only the one with the most similar intensity. This only work with %s>1.", kIcpPMMatcherKnn().c_str()));
RTABMAP_PARAM(Icp, PMOutlierRatio, float, 0.85, "TrimmedDistOutlierFilter/ratio: For convenience when configuration file is not set. For kinect-like point cloud, use 0.65.");
RTABMAP_PARAM(Icp, PMForce4DoF, bool, false, "Limit ICP to x, y, z and yaw DoF.");

RTABMAP_PARAM(Icp, CCSamplingLimit, unsigned int, 50000, "Maximum number of points per cloud (they are randomly resampled below this limit otherwise).");
RTABMAP_PARAM(Icp, CCFilterOutFarthestPoints, bool, false, "If true, the algorithm will automatically ignore farthest points from the reference, for better convergence.");
RTABMAP_PARAM(Icp, CCMaxFinalRMS, float, 0.2, "Maximum final RMS error.");

// Stereo disparity
RTABMAP_PARAM(Stereo, WinWidth, int, 15, "Window width.");
Expand Down
11 changes: 8 additions & 3 deletions corelib/include/rtabmap/core/RegistrationIcp.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ class RTABMAP_EXP RegistrationIcp : public Registration
virtual float getMinGeometryCorrespondencesRatioImpl() const {return _correspondenceRatio;}

private:
int _strategy;
float _maxTranslation;
float _maxRotation;
float _voxelSize;
Expand All @@ -66,20 +67,24 @@ class RTABMAP_EXP RegistrationIcp : public Registration
int _maxIterations;
float _epsilon;
float _correspondenceRatio;
bool _force4DoF;
bool _pointToPlane;
int _pointToPlaneK;
float _pointToPlaneRadius;
float _pointToPlaneGroundNormalsUp;
float _pointToPlaneMinComplexity;
int _pointToPlaneLowComplexityStrategy;
bool _libpointmatcher;
std::string _libpointmatcherConfig;
int _libpointmatcherKnn;
float _libpointmatcherEpsilon;
bool _libpointmatcherIntensity;
float _libpointmatcherOutlierRatio;
bool _libpointmatcherForce4DoF;
float _outlierRatio;
unsigned int _ccSamplingLimit;
bool _ccFilterOutFarthestPoints;
double _ccMaxFinalRMS;

void * _libpointmatcherICP;
void * _libpointmatcherICPFilters;
};

}
Expand Down
7 changes: 7 additions & 0 deletions corelib/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -433,6 +433,13 @@ IF(libpointmatcher_FOUND)
)
ENDIF(libpointmatcher_FOUND)

IF(CCCoreLib_FOUND)
SET(LIBRARIES
${LIBRARIES}
CCCoreLib::CCCoreLib
)
ENDIF(CCCoreLib_FOUND)

IF(FastCV_FOUND)
SET(INCLUDE_DIRS
${INCLUDE_DIRS}
Expand Down
8 changes: 6 additions & 2 deletions corelib/src/Memory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3075,7 +3075,7 @@ Transform Memory::computeIcpTransformMulti(
Transform t;
if(!fromScan.isEmpty() && !toScan.isEmpty())
{
Transform guess = poses.at(fromId).inverse() * poses.at(toId);
Transform guess = poses.at(toId).inverse() * poses.at(fromId);
float guessNorm = guess.getNorm();
if(fromScan.rangeMax() > 0.0f && toScan.rangeMax() > 0.0f &&
guessNorm > fromScan.rangeMax() + toScan.rangeMax())
Expand Down Expand Up @@ -3214,7 +3214,11 @@ Transform Memory::computeIcpTransformMulti(
fromScan.rangeMax(),
fromScan.is2d()?Transform(0,0,fromScan.localTransform().z(),0,0,0):Transform::getIdentity()));

t = _registrationIcpMulti->computeTransformation(fromS->sensorData(), assembledData, guess, info);
t = _registrationIcpMulti->computeTransformation(assembledData, fromS->sensorData(), guess, info);
if(!t.isNull())
{
t = t.inverse();
}
}

return t;
Expand Down
1 change: 1 addition & 0 deletions corelib/src/Odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,7 @@ Transform Odometry::process(SensorData & data, const Transform & guessIn, Odomet
kpts[i].octave += log2value;
}
data.setFeatures(kpts, decimatedData.keypoints3D(), decimatedData.descriptors());
data.setLaserScan(decimatedData.laserScanRaw());

if(info)
{
Expand Down
10 changes: 10 additions & 0 deletions corelib/src/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,6 +244,10 @@ const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemo

removedParameters_.insert(std::make_pair("RGBD/SavedLocalizationIgnored", std::make_pair(true, Parameters::kRGBDStartAtOrigin())));

removedParameters_.insert(std::make_pair("Icp/PMForce4DoF", std::make_pair(true, Parameters::kIcpForce4DoF())));
removedParameters_.insert(std::make_pair("Icp/PM", std::make_pair(true, Parameters::kIcpStrategy()))); // convert "true" to "1"
removedParameters_.insert(std::make_pair("Icp/PMOutlierRatio", std::make_pair(true, Parameters::kIcpOutlierRatio())));

// 0.20.
removedParameters_.insert(std::make_pair("SuperGlue/Path", std::make_pair(true, Parameters::kPyMatcherPath())));
removedParameters_.insert(std::make_pair("SuperGlue/Iterations", std::make_pair(true, Parameters::kPyMatcherIterations())));
Expand Down Expand Up @@ -784,6 +788,12 @@ ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParam
std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
#else
std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
#endif
str = "With CCCoreLib:";
#ifdef RTABMAP_CCCORELIB
std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
#else
std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
#endif
str = "With octomap:";
#ifdef RTABMAP_OCTOMAP
Expand Down
Loading

0 comments on commit 06e85e1

Please sign in to comment.