diff --git a/corelib/include/rtabmap/core/Features2d.h b/corelib/include/rtabmap/core/Features2d.h index f26f84be73..1dcf1c86a1 100644 --- a/corelib/include/rtabmap/core/Features2d.h +++ b/corelib/include/rtabmap/core/Features2d.h @@ -246,6 +246,7 @@ class RTABMAP_CORE_EXPORT Feature2D { bool SSC_; float _maxDepth; // 0=inf float _minDepth; + float _floorFilterHeight; // 0=disabled std::vector _roiRatios; // size 4 int _subPixWinSize; int _subPixIterations; diff --git a/corelib/include/rtabmap/core/Memory.h b/corelib/include/rtabmap/core/Memory.h index 145aeb1936..5b91dcf225 100644 --- a/corelib/include/rtabmap/core/Memory.h +++ b/corelib/include/rtabmap/core/Memory.h @@ -314,6 +314,7 @@ class RTABMAP_CORE_EXPORT Memory bool _badSignaturesIgnored; bool _mapLabelsAdded; bool _depthAsMask; + float _maskFloorThreshold; bool _stereoFromMotion; unsigned int _imagePreDecimation; unsigned int _imagePostDecimation; diff --git a/corelib/include/rtabmap/core/Parameters.h b/corelib/include/rtabmap/core/Parameters.h index ee4da294d5..ea84f583b2 100644 --- a/corelib/include/rtabmap/core/Parameters.h +++ b/corelib/include/rtabmap/core/Parameters.h @@ -221,6 +221,7 @@ class RTABMAP_CORE_EXPORT Parameters RTABMAP_PARAM(Mem, BadSignaturesIgnored, bool, false, "Bad signatures are ignored."); RTABMAP_PARAM(Mem, InitWMWithAllNodes, bool, false, "Initialize the Working Memory with all nodes in Long-Term Memory. When false, it is initialized with nodes of the previous session."); RTABMAP_PARAM(Mem, DepthAsMask, bool, true, "Use depth image as mask when extracting features for vocabulary."); + RTABMAP_PARAM(Mem, DepthMaskFloorThr, float, 0.0, uFormat("Filter floor from depth mask below specified threshold (m) before extracting features. 0 means disabled, negative means remove all objects above the floor threshold instead. Ignored if %s is false.", kMemDepthAsMask().c_str())); RTABMAP_PARAM(Mem, StereoFromMotion, bool, false, uFormat("Triangulate features without depth using stereo from motion (odometry). It would be ignored if %s is true and the feature detector used supports masking.", kMemDepthAsMask().c_str())); RTABMAP_PARAM(Mem, ImagePreDecimation, unsigned int, 1, uFormat("Decimation of the RGB image before visual feature detection. If depth size is larger than decimated RGB size, depth is decimated to be always at most equal to RGB size. If %s is true and if depth is smaller than decimated RGB, depth may be interpolated to match RGB size for feature detection.",kMemDepthAsMask().c_str())); RTABMAP_PARAM(Mem, ImagePostDecimation, unsigned int, 1, uFormat("Decimation of the RGB image before saving it to database. If depth size is larger than decimated RGB size, depth is decimated to be always at most equal to RGB size. Decimation is done from the original image. If set to same value than %s, data already decimated is saved (no need to re-decimate the image).", kMemImagePreDecimation().c_str())); @@ -703,6 +704,7 @@ class RTABMAP_CORE_EXPORT Parameters RTABMAP_PARAM(Vis, MaxDepth, float, 0, "Max depth of the features (0 means no limit)."); RTABMAP_PARAM(Vis, MinDepth, float, 0, "Min depth of the features (0 means no limit)."); RTABMAP_PARAM(Vis, DepthAsMask, bool, true, "Use depth image as mask when extracting features."); + RTABMAP_PARAM(Vis, DepthMaskFloorThr, float, 0.0, uFormat("Filter floor from depth mask below specified threshold (m) before extracting features. 0 means disabled, negative means remove all objects above the floor threshold instead. Ignored if %s is false.", kVisDepthAsMask().c_str())); RTABMAP_PARAM_STR(Vis, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom]."); RTABMAP_PARAM(Vis, SubPixWinSize, int, 3, "See cv::cornerSubPix()."); RTABMAP_PARAM(Vis, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining."); diff --git a/corelib/include/rtabmap/core/RegistrationVis.h b/corelib/include/rtabmap/core/RegistrationVis.h index 520be30a89..abcfa3f821 100644 --- a/corelib/include/rtabmap/core/RegistrationVis.h +++ b/corelib/include/rtabmap/core/RegistrationVis.h @@ -101,6 +101,7 @@ class RTABMAP_CORE_EXPORT RegistrationVis : public Registration bool _guessMatchToProjection; int _bundleAdjustment; bool _depthAsMask; + float _maskFloorThreshold; float _minInliersDistributionThr; float _maxInliersMeanDistance; diff --git a/corelib/include/rtabmap/core/util3d.h b/corelib/include/rtabmap/core/util3d.h index 9cba8724da..390fe14cac 100644 --- a/corelib/include/rtabmap/core/util3d.h +++ b/corelib/include/rtabmap/core/util3d.h @@ -364,6 +364,22 @@ void RTABMAP_CORE_EXPORT fillProjectedCloudHoles( bool verticalDirection, bool fillToBorder); +/** + * @brief Remove values below a floor threshold in a depth image. + * + * @param depth the depth image to filter (can be a multi-camera depth image). + * @param cameraModels corresponding camera model(s) to depth image, with valid + * local transform between base frame to camera frame. + * @param threshold height from base frame at which pixels below it are set to 0. + * @param depthBelow depth image of the pixels below the floor theshold. + * @return cv::Mat depth image of the pixels above the floor theshold. + */ +cv::Mat RTABMAP_CORE_EXPORT filterFloor( + const cv::Mat & depth, + const std::vector & cameraModels, + float threshold, + cv::Mat * depthBelow = 0); + /** * For each point, return pixel of the best camera (NodeID->CameraIndex) * looking at it based on the policy and parameters diff --git a/corelib/src/Features2d.cpp b/corelib/src/Features2d.cpp index 73e54471f4..5aa67230ef 100644 --- a/corelib/src/Features2d.cpp +++ b/corelib/src/Features2d.cpp @@ -1315,6 +1315,11 @@ std::vector SIFT::generateKeypointsImpl(const cv::Mat & image, con UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U); std::vector keypoints; cv::Mat imgRoi(image, roi); + cv::Mat maskRoi; + if(!mask.empty()) + { + maskRoi = cv::Mat(mask, roi); + } #ifdef RTABMAP_CUDASIFT if(gpu_) { @@ -1383,6 +1388,12 @@ std::vector SIFT::generateKeypointsImpl(const cv::Mat & image, con //std::cout << cv::Mat(1, 128*4, CV_8UC1, desc) << std::endl; continue; } + // Ignore keypoints not in the mask + if(!maskRoi.empty() && maskRoi.at(cudaSiftData_->h_data[i].ypos, cudaSiftData_->h_data[i].xpos) == 0) + { + continue; + } + //Keep track of the data, to be easier to manage the data in the next step hessianMap.insert(std::pair(cudaSiftData_->h_data[i].sharpness, i)); } @@ -1412,12 +1423,6 @@ std::vector SIFT::generateKeypointsImpl(const cv::Mat & image, con else #endif { - cv::Mat maskRoi; - if(!mask.empty()) - { - maskRoi = cv::Mat(mask, roi); - } - #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11))) #ifdef RTABMAP_NONFREE sift_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints diff --git a/corelib/src/Memory.cpp b/corelib/src/Memory.cpp index 0357fbba6b..2ed9232486 100644 --- a/corelib/src/Memory.cpp +++ b/corelib/src/Memory.cpp @@ -91,6 +91,7 @@ Memory::Memory(const ParametersMap & parameters) : _badSignaturesIgnored(Parameters::defaultMemBadSignaturesIgnored()), _mapLabelsAdded(Parameters::defaultMemMapLabelsAdded()), _depthAsMask(Parameters::defaultMemDepthAsMask()), + _maskFloorThreshold(Parameters::defaultMemDepthMaskFloorThr()), _stereoFromMotion(Parameters::defaultMemStereoFromMotion()), _imagePreDecimation(Parameters::defaultMemImagePreDecimation()), _imagePostDecimation(Parameters::defaultMemImagePostDecimation()), @@ -576,6 +577,7 @@ void Memory::parseParameters(const ParametersMap & parameters) Parameters::parse(params, Parameters::kMemTransferSortingByWeightId(), _transferSortingByWeightId); Parameters::parse(params, Parameters::kMemSTMSize(), _maxStMemSize); Parameters::parse(params, Parameters::kMemDepthAsMask(), _depthAsMask); + Parameters::parse(params, Parameters::kMemDepthMaskFloorThr(), _maskFloorThreshold); Parameters::parse(params, Parameters::kMemStereoFromMotion(), _stereoFromMotion); Parameters::parse(params, Parameters::kMemImagePreDecimation(), _imagePreDecimation); Parameters::parse(params, Parameters::kMemImagePostDecimation(), _imagePostDecimation); @@ -4884,7 +4886,26 @@ Signature * Memory::createSignature(const SensorData & inputData, const Transfor imageMono.cols % decimatedData.depthRaw().cols == 0 && imageMono.rows/decimatedData.depthRaw().rows == imageMono.cols/decimatedData.depthRaw().cols) { - depthMask = util2d::interpolate(decimatedData.depthRaw(), imageMono.rows/decimatedData.depthRaw().rows, 0.1f); + depthMask = decimatedData.depthRaw(); + + if(_maskFloorThreshold != 0.0f) + { + UASSERT(!decimatedData.cameraModels().empty()); + UDEBUG("Masking floor (threshold=%f)", _maskFloorThreshold); + if(_maskFloorThreshold<0.0f) + { + cv::Mat depthBelow; + util3d::filterFloor(depthMask, decimatedData.cameraModels(), _maskFloorThreshold*-1.0f, &depthBelow); + depthMask = depthBelow; + } + else + { + depthMask = util3d::filterFloor(depthMask, decimatedData.cameraModels(), _maskFloorThreshold); + } + UDEBUG("Masking floor done."); + } + + depthMask = util2d::interpolate(depthMask, imageMono.rows/depthMask.rows, 0.1f); } else { diff --git a/corelib/src/RegistrationVis.cpp b/corelib/src/RegistrationVis.cpp index c16ee76677..fc4ce0caee 100644 --- a/corelib/src/RegistrationVis.cpp +++ b/corelib/src/RegistrationVis.cpp @@ -94,6 +94,7 @@ RegistrationVis::RegistrationVis(const ParametersMap & parameters, Registration _guessMatchToProjection(Parameters::defaultVisCorGuessMatchToProjection()), _bundleAdjustment(Parameters::defaultVisBundleAdjustment()), _depthAsMask(Parameters::defaultVisDepthAsMask()), + _maskFloorThreshold(Parameters::defaultVisDepthMaskFloorThr()), _minInliersDistributionThr(Parameters::defaultVisMinInliersDistribution()), _maxInliersMeanDistance(Parameters::defaultVisMeanInliersDistance()), _detectorFrom(0), @@ -155,6 +156,7 @@ void RegistrationVis::parseParameters(const ParametersMap & parameters) Parameters::parse(parameters, Parameters::kVisCorGuessMatchToProjection(), _guessMatchToProjection); Parameters::parse(parameters, Parameters::kVisBundleAdjustment(), _bundleAdjustment); Parameters::parse(parameters, Parameters::kVisDepthAsMask(), _depthAsMask); + Parameters::parse(parameters, Parameters::kVisDepthMaskFloorThr(), _maskFloorThreshold); Parameters::parse(parameters, Parameters::kVisMinInliersDistribution(), _minInliersDistributionThr); Parameters::parse(parameters, Parameters::kVisMeanInliersDistance(), _maxInliersMeanDistance); uInsert(_bundleParameters, parameters); @@ -423,13 +425,32 @@ Transform RegistrationVis::computeTransformationImpl( imageFrom.cols % fromSignature.sensorData().depthRaw().cols == 0 && imageFrom.rows/fromSignature.sensorData().depthRaw().rows == fromSignature.sensorData().imageRaw().cols/fromSignature.sensorData().depthRaw().cols) { - depthMask = util2d::interpolate(fromSignature.sensorData().depthRaw(), fromSignature.sensorData().imageRaw().rows/fromSignature.sensorData().depthRaw().rows, 0.1f); + depthMask = fromSignature.sensorData().depthRaw(); + + if(_maskFloorThreshold != 0.0f) + { + UASSERT(!fromSignature.sensorData().cameraModels().empty()); + UDEBUG("Masking floor (threshold=%f)", _maskFloorThreshold); + if(_maskFloorThreshold<0.0f) + { + cv::Mat depthBelow; + util3d::filterFloor(depthMask, fromSignature.sensorData().cameraModels(), _maskFloorThreshold*-1.0f, &depthBelow); + depthMask = depthBelow; + } + else + { + depthMask = util3d::filterFloor(depthMask, fromSignature.sensorData().cameraModels(), _maskFloorThreshold); + } + UDEBUG("Masking floor done."); + } + + depthMask = util2d::interpolate(depthMask, imageFrom.rows/depthMask.rows, 0.1f); } else { UWARN("%s is true, but RGB size (%dx%d) modulo depth size (%dx%d) is not 0. Ignoring depth mask for feature detection.", Parameters::kVisDepthAsMask().c_str(), - fromSignature.sensorData().imageRaw().rows, fromSignature.sensorData().imageRaw().cols, + imageFrom.rows, imageFrom.cols, fromSignature.sensorData().depthRaw().rows, fromSignature.sensorData().depthRaw().cols); } } @@ -770,13 +791,32 @@ Transform RegistrationVis::computeTransformationImpl( imageTo.cols % toSignature.sensorData().depthRaw().cols == 0 && imageTo.rows/toSignature.sensorData().depthRaw().rows == imageTo.cols/toSignature.sensorData().depthRaw().cols) { - depthMask = util2d::interpolate(toSignature.sensorData().depthRaw(), imageTo.rows/toSignature.sensorData().depthRaw().rows, 0.1f); + depthMask = toSignature.sensorData().depthRaw(); + + if(_maskFloorThreshold != 0.0f) + { + UASSERT(!toSignature.sensorData().cameraModels().empty()); + UDEBUG("Masking floor (threshold=%f)", _maskFloorThreshold); + if(_maskFloorThreshold<0.0f) + { + cv::Mat depthBelow; + util3d::filterFloor(depthMask, toSignature.sensorData().cameraModels(), _maskFloorThreshold*-1.0f, &depthBelow); + depthMask = depthBelow; + } + else + { + depthMask = util3d::filterFloor(depthMask, toSignature.sensorData().cameraModels(), _maskFloorThreshold); + } + UDEBUG("Masking floor done."); + } + + depthMask = util2d::interpolate(depthMask, imageTo.rows/depthMask.rows, 0.1f); } else { UWARN("%s is true, but RGB size (%dx%d) modulo depth size (%dx%d) is not 0. Ignoring depth mask for feature detection.", Parameters::kVisDepthAsMask().c_str(), - toSignature.sensorData().imageRaw().rows, toSignature.sensorData().imageRaw().cols, + imageTo.rows, imageTo.cols, toSignature.sensorData().depthRaw().rows, toSignature.sensorData().depthRaw().cols); } } diff --git a/corelib/src/util3d.cpp b/corelib/src/util3d.cpp index 606dfa6996..0fa213294a 100644 --- a/corelib/src/util3d.cpp +++ b/corelib/src/util3d.cpp @@ -3007,6 +3007,115 @@ void fillProjectedCloudHoles(cv::Mat & registeredDepth, bool verticalDirection, } } +cv::Mat filterFloor(const cv::Mat & depth, const std::vector & cameraModels, float threshold, cv::Mat * depthBelow) +{ + cv::Mat output = depth.clone(); + if(depth.empty()) + { + return output; + } + if(depthBelow) + { + *depthBelow = cv::Mat::zeros(output.size(), output.type()); + } + + UASSERT(!cameraModels.empty()); + UASSERT(cameraModels[0].isValidForReprojection()); + // Support camera model with different resolution than depth image + float rgbToDepthFactorX = float(cameraModels[0].imageWidth()) / float(output.cols/cameraModels.size()); + float rgbToDepthFactorY = float(cameraModels[0].imageHeight()) / float(output.rows); + int depthWidth = output.cols/cameraModels.size(); + UASSERT(depthWidth*(int)cameraModels.size() == output.cols); + + // for each camera + for(size_t i=0; i0) + { + // Make sure all models are the same resolution + UASSERT(cam.imageWidth() == cameraModels[i-1].imageWidth()); + UASSERT(cam.imageHeight() == cameraModels[i-1].imageHeight()); + } + + float depthFx = cam.fx() / rgbToDepthFactorX; + float depthFy = cam.fy() / rgbToDepthFactorY; + float depthCx = cam.cx() / rgbToDepthFactorX; + float depthCy = cam.cy() / rgbToDepthFactorY; + + cv::Mat subImage = output.colRange(cv::Range(i*depthWidth, (i+1)*depthWidth)); + cv::Mat subImageBelow; + if(depthBelow) + subImageBelow = depthBelow->colRange(cv::Range(i*depthWidth, (i+1)*depthWidth)); + + for(int y=0; y 0) + { + float d = float(ptr[x])/1000.0f; + cv::Point3f pt; + pt.x = (x - depthCx) * d / depthFx; + pt.y = (y - depthCy) * d / depthFy; + pt.z = d; + pt = util3d::transformPoint(pt, localTransform); + if(pt.z < threshold) + { + if(ptrBelow) + { + ptrBelow[x] = ptr[x]; + } + ptr[x] = 0; + } + } + } + } + else // CV_32FC1 + { + float * ptr = (float *)subImage.row(y).ptr(); + float * ptrBelow = 0; + if(depthBelow) + { + ptrBelow = (float *)subImageBelow.row(y).ptr(); + } + for(int x=0; x 0.0f) + { + float & d = ptr[x]; + cv::Point3f pt; + pt.x = (x - depthCx) * d / depthFx; + pt.y = (y - depthCy) * d / depthFy; + pt.z = d; + pt = util3d::transformPoint(pt, localTransform); + if(pt.z < threshold) + { + if(ptrBelow) + { + ptrBelow[x] = ptr[x]; + } + d = 0; + } + } + } + } + } + } + return output; +} + class ProjectionInfo { public: ProjectionInfo(): diff --git a/guilib/src/ParametersToolBox.cpp b/guilib/src/ParametersToolBox.cpp index 1bd583d25e..47fa560aea 100644 --- a/guilib/src/ParametersToolBox.cpp +++ b/guilib/src/ParametersToolBox.cpp @@ -405,7 +405,8 @@ void ParametersToolBox::addParameter(QVBoxLayout * layout, // set minimum for selected parameters if(key.compare(Parameters::kGridMinGroundHeight().c_str()) == 0 || key.compare(Parameters::kGridMaxGroundHeight().c_str()) == 0 || - key.compare(Parameters::kGridMaxObstacleHeight().c_str()) == 0) + key.compare(Parameters::kGridMaxObstacleHeight().c_str()) == 0 || + key.compare(Parameters::kVisDepthMaskFloorThr().c_str()) == 0) { widget->setMinimum(-1000000.0); } diff --git a/guilib/src/PreferencesDialog.cpp b/guilib/src/PreferencesDialog.cpp index 39e606cbf6..ddbe25892a 100644 --- a/guilib/src/PreferencesDialog.cpp +++ b/guilib/src/PreferencesDialog.cpp @@ -1057,6 +1057,7 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) : _ui->surf_doubleSpinBox_maxDepth->setObjectName(Parameters::kKpMaxDepth().c_str()); _ui->surf_doubleSpinBox_minDepth->setObjectName(Parameters::kKpMinDepth().c_str()); _ui->checkBox_memDepthAsMask->setObjectName(Parameters::kMemDepthAsMask().c_str()); + _ui->doubleSpinBox_memDepthMaskFloorThr->setObjectName(Parameters::kMemDepthMaskFloorThr().c_str()); _ui->checkBox_memStereoFromMotion->setObjectName(Parameters::kMemStereoFromMotion().c_str()); _ui->surf_spinBox_wordsPerImageTarget->setObjectName(Parameters::kKpMaxFeatures().c_str()); _ui->checkBox_kp_ssc->setObjectName(Parameters::kKpSSC().c_str()); @@ -1289,6 +1290,7 @@ PreferencesDialog::PreferencesDialog(QWidget * parent) : _ui->loopClosure_bowMaxDepth->setObjectName(Parameters::kVisMaxDepth().c_str()); _ui->loopClosure_bowMinDepth->setObjectName(Parameters::kVisMinDepth().c_str()); _ui->checkBox_visDepthAsMask->setObjectName(Parameters::kVisDepthAsMask().c_str()); + _ui->doubleSpinBox_visDepthMaskFloorThr->setObjectName(Parameters::kVisDepthMaskFloorThr().c_str()); _ui->loopClosure_roi->setObjectName(Parameters::kVisRoiRatios().c_str()); _ui->subpix_winSize->setObjectName(Parameters::kVisSubPixWinSize().c_str()); _ui->subpix_iterations->setObjectName(Parameters::kVisSubPixIterations().c_str()); diff --git a/guilib/src/ui/preferencesDialog.ui b/guilib/src/ui/preferencesDialog.ui index dfe86d428b..a8b2dc1fb6 100644 --- a/guilib/src/ui/preferencesDialog.ui +++ b/guilib/src/ui/preferencesDialog.ui @@ -95,7 +95,7 @@ QFrame::Raised - 3 + 9 @@ -10666,29 +10666,10 @@ If set to false, classic RTAB-Map loop closure detection is done using only imag - - - - 0 means that the response (hessian) threshold -used for the detector will not be adapted. -Otherwise, the threshold is modified to -generate the number of words requested. - - - Maximum words per image (0=no maximum). Setting to -1 will disable features extraction, so disabling loop closure detection indirectly. - - - true - - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - - - - - + + - Bad signature ratio (less than Ratio x AverageWordsPerImage = bad). + Maximum words depth (0 means inf). Only used when a depth image is provided. Applied before "Maximum words per image". true @@ -10698,48 +10679,26 @@ generate the number of words requested. - - - - Top ROI ratio (0 = no change). - - - true + + + + % - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + 0 - - - - 2 - + + - 0.000000000000000 + -1 - 1.000000000000000 - - - 0.050000000000000 + 2000 - 0.250000000000000 - - - - - - - Minimum words depth. Only used when a depth image is provided. Applied before "Maximum words per image". - - - true - - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + 500 @@ -10827,17 +10786,23 @@ generate the number of words requested. - - - + + + + Number of columns of the grid used to extract uniformly "max words / grid cells" features from each cell. + + true + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + - - + + - ROI ratios [left, right, top, bottom] between 0 and 1. + Minimum words depth. Only used when a depth image is provided. Applied before "Maximum words per image". true @@ -10847,10 +10812,10 @@ generate the number of words requested. - - + + - Maximum words depth (0 means inf). Only used when a depth image is provided. Applied before "Maximum words per image". + If true, SSC (Suppression via Square Covering) is applied to limit keypoints. true @@ -10860,20 +10825,36 @@ generate the number of words requested. - - - - % - + + - 0 + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.050000000000000 + + + 0.250000000000000 - - + + + + true + + + + + - Visual word type. + Triangulate features without depth using stereo from motion (odometry). It would be ignored if depth as mask is checked and the feature detector used supports masking. true @@ -10883,6 +10864,16 @@ generate the number of words requested. + + + + % + + + 0 + + + @@ -10905,30 +10896,36 @@ generate the number of words requested. - - - - -1 + + + + Use depth image as mask when extracting features. - - 2000 + + true - - 500 + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - - + + - + Right ROI ratio (0 = no change). + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - - + + - If true, SSC (Suppression via Square Covering) is applied to limit keypoints. + Top ROI ratio (0 = no change). true @@ -10938,20 +10935,29 @@ generate the number of words requested. - - - - % + + + + 0 means that the response (hessian) threshold +used for the detector will not be adapted. +Otherwise, the threshold is modified to +generate the number of words requested. - - 0 + + Maximum words per image (0=no maximum). Setting to -1 will disable features extraction, so disabling loop closure detection indirectly. + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - - + + - Left ROI ratio (0 = no change). + Visual word type. true @@ -10962,9 +10968,9 @@ generate the number of words requested. - + - Right ROI ratio (0 = no change). + Left ROI ratio (0 = no change). true @@ -10974,8 +10980,8 @@ generate the number of words requested. - - + + % @@ -10984,8 +10990,41 @@ generate the number of words requested. - - + + + + 1 + + + 99 + + + 1 + + + + + + + + + + + + + + ROI ratios [left, right, top, bottom] between 0 and 1. + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + + + + % @@ -10994,10 +11033,17 @@ generate the number of words requested. - - + + - Bottom ROI ratio (0 = no change). + + + + + + + + Bad signature ratio (less than Ratio x AverageWordsPerImage = bad). true @@ -11007,6 +11053,13 @@ generate the number of words requested. + + + + + + + @@ -11029,7 +11082,7 @@ generate the number of words requested. - + Number of rows of the grid used to extract uniformly "max words / grid cells" features from each cell. @@ -11042,20 +11095,20 @@ generate the number of words requested. - - - - 1 + + + + Bottom ROI ratio (0 = no change). - - 99 + + true - - 1 + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - + 1 @@ -11068,10 +11121,10 @@ generate the number of words requested. - - + + - Number of columns of the grid used to extract uniformly "max words / grid cells" features from each cell. + Filter floor from depth mask. 0 means disabled, negative means keeping pixels below the floor theshold instead. true @@ -11081,43 +11134,25 @@ generate the number of words requested. - - - - Use depth image as mask when extracting features. - - - true - - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + + + m - - - - - - + + 2 - - - - - - Triangulate features without depth using stereo from motion (odometry). It would be ignored if depth as mask is checked and the feature detector used supports masking. + + -99.000000000000000 - - true + + 99.000000000000000 - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + 0.050000000000000 - - - - - - + + 0.000000000000000 @@ -22553,10 +22588,10 @@ Lower the ratio -> higher the precision. - - + + - Maximum feature depth. + Use depth image as mask when extracting features. true @@ -22566,10 +22601,10 @@ Lower the ratio -> higher the precision. - - + + - ROI ratios [left right top bottom] between 0 and 1. + If true, SSC (Suppression via Square Covering) is applied to limit keypoints. true @@ -22579,20 +22614,36 @@ Lower the ratio -> higher the precision. - - + + + + Maximum feature depth. + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + - - + + + + 1 + - 999999 + 99 + + + 1 - - + + - Max features extracted from the images (0 means inf). + Minimum feature depth. true @@ -22602,6 +22653,32 @@ Lower the ratio -> higher the precision. + + + + Number of rows of the grid used to extract uniformly "max features / grid cells" features from each cell. + + + true + + + Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse + + + + + + + m + + + 0.000000000000000 + + + 0.100000000000000 + + + @@ -22609,10 +22686,17 @@ Lower the ratio -> higher the precision. - - + + - If true, SSC (Suppression via Square Covering) is applied to limit keypoints. + + + + + + + + Number of columns of the grid used to extract uniformly "max features / grid cells" features from each cell. true @@ -22622,10 +22706,17 @@ Lower the ratio -> higher the precision. - - + + + + 999999 + + + + + - Minimum feature depth. + Max features extracted from the images (0 means inf). true @@ -22725,19 +22816,6 @@ Lower the ratio -> higher the precision. - - - - m - - - 0.000000000000000 - - - 60.000000000000000 - - - @@ -22748,8 +22826,8 @@ Lower the ratio -> higher the precision. - - + + m @@ -22757,11 +22835,14 @@ Lower the ratio -> higher the precision. 0.000000000000000 - 0.100000000000000 + 60.000000000000000 + + + 1 @@ -22775,9 +22856,9 @@ Lower the ratio -> higher the precision. - + - Number of rows of the grid used to extract uniformly "max features / grid cells" features from each cell. + ROI ratios [left right top bottom] between 0 and 1. true @@ -22787,10 +22868,10 @@ Lower the ratio -> higher the precision. - - + + - Number of columns of the grid used to extract uniformly "max features / grid cells" features from each cell. + Filter floor from depth mask. 0 means disabled, negative means keeping pixels below the floor theshold instead. true @@ -22800,36 +22881,19 @@ Lower the ratio -> higher the precision. - - + + + + m + - 1 + -99.000000000000000 - - 99 + + 0.050000000000000 - 1 - - - - - - - Use depth image as mask when extracting features. - - - true - - - Qt::LinksAccessibleByMouse|Qt::TextSelectableByMouse - - - - - - - + 0.000000000000000