39 #include <opencv2/imgproc/imgproc_c.h>
40 #include <opencv2/core/version.hpp>
41 #include <opencv2/opencv_modules.hpp>
43 #ifdef RTABMAP_ORB_OCTREE
55 #if CV_MAJOR_VERSION < 3
57 #ifdef HAVE_OPENCV_GPU
58 #include <opencv2/gpu/gpu.hpp>
61 #include <opencv2/core/cuda.hpp>
64 #ifdef HAVE_OPENCV_NONFREE
65 #if CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION >=4
66 #include <opencv2/nonfree/gpu.hpp>
67 #include <opencv2/nonfree/features2d.hpp>
70 #ifdef HAVE_OPENCV_XFEATURES2D
71 #include <opencv2/xfeatures2d.hpp>
72 #include <opencv2/xfeatures2d/nonfree.hpp>
73 #include <opencv2/xfeatures2d/cuda.hpp>
75 #ifdef HAVE_OPENCV_CUDAFEATURES2D
76 #include <opencv2/cudafeatures2d.hpp>
86 std::vector<cv::KeyPoint> & keypoints,
87 const cv::Mat & depth,
96 std::vector<cv::KeyPoint> & keypoints,
97 cv::Mat & descriptors,
98 const cv::Mat & depth,
103 UASSERT(maxDepth <= 0.0f || maxDepth > minDepth);
104 if(!depth.empty() && (descriptors.empty() || descriptors.rows == (
int)keypoints.size()))
106 std::vector<cv::KeyPoint> output(keypoints.size());
107 std::vector<int> indexes(keypoints.size(), 0);
109 bool isInMM = depth.type() == CV_16UC1;
110 for(
unsigned int i=0;
i<keypoints.size(); ++
i)
112 int u =
int(keypoints[
i].pt.x+0.5f);
113 int v =
int(keypoints[
i].pt.y+0.5f);
114 if(u >=0 && u<depth.cols && v >=0 &&
v<depth.rows)
116 float d = isInMM?(
float)depth.at<
uint16_t>(
v,u)*0.001f:depth.at<
float>(
v,u);
117 if(
uIsFinite(
d) &&
d>minDepth && (maxDepth <= 0.0f ||
d < maxDepth))
119 output[oi++] = keypoints[
i];
127 if(!descriptors.empty() && (
int)keypoints.size() != descriptors.rows)
129 if(keypoints.size() == 0)
131 descriptors = cv::Mat();
135 cv::Mat newDescriptors((
int)keypoints.size(), descriptors.cols, descriptors.type());
137 for(
unsigned int i=0;
i<indexes.size(); ++
i)
141 if(descriptors.type() == CV_32FC1)
143 memcpy(newDescriptors.ptr<
float>(di++), descriptors.ptr<
float>(
i), descriptors.cols*
sizeof(
float));
147 memcpy(newDescriptors.ptr<
char>(di++), descriptors.ptr<
char>(
i), descriptors.cols*
sizeof(
char));
151 descriptors = newDescriptors;
158 std::vector<cv::KeyPoint> & keypoints,
159 cv::Mat & descriptors,
160 std::vector<cv::Point3f> & keypoints3D,
166 UASSERT(((
int)keypoints.size() == descriptors.rows || descriptors.empty()) &&
167 keypoints3D.size() == keypoints.size());
168 std::vector<cv::KeyPoint> validKeypoints(keypoints.size());
169 std::vector<cv::Point3f> validKeypoints3D(keypoints.size());
170 cv::Mat validDescriptors(descriptors.size(), descriptors.type());
173 float minDepthSqr = minDepth * minDepth;
174 float maxDepthSqr = maxDepth * maxDepth;
175 for(
unsigned int i=0;
i<keypoints3D.size(); ++
i)
177 cv::Point3f & pt = keypoints3D[
i];
180 float distSqr = pt.x*pt.x+pt.y*pt.y+pt.z*pt.z;
181 if(distSqr >= minDepthSqr && (maxDepthSqr==0.0
f || distSqr <= maxDepthSqr))
183 validKeypoints[oi] = keypoints[
i];
184 validKeypoints3D[oi] = pt;
185 if(!descriptors.empty())
187 descriptors.row(
i).copyTo(validDescriptors.row(oi));
193 UDEBUG(
"Removed %d invalid 3D points", (
int)keypoints3D.size()-oi);
194 validKeypoints.resize(oi);
195 validKeypoints3D.resize(oi);
196 keypoints = validKeypoints;
197 keypoints3D = validKeypoints3D;
198 if(!descriptors.empty())
200 descriptors = validDescriptors.rowRange(0, oi).clone();
205 std::vector<cv::KeyPoint> & keypoints,
206 const cv::Mat & disparity,
214 std::vector<cv::KeyPoint> & keypoints,
215 cv::Mat & descriptors,
216 const cv::Mat & disparity,
219 if(!disparity.empty() && minDisparity > 0.0f && (descriptors.empty() || descriptors.rows == (
int)keypoints.size()))
221 std::vector<cv::KeyPoint> output(keypoints.size());
222 std::vector<int> indexes(keypoints.size(), 0);
224 for(
unsigned int i=0;
i<keypoints.size(); ++
i)
226 int u =
int(keypoints[
i].pt.x+0.5f);
227 int v =
int(keypoints[
i].pt.y+0.5f);
228 if(u >=0 && u<disparity.cols && v >=0 &&
v<disparity.rows)
230 float d = disparity.type() == CV_16SC1?
float(disparity.at<
short>(
v,u))/16.0f:disparity.at<
float>(
v,u);
233 output[oi++] = keypoints[
i];
241 if(!descriptors.empty() && (
int)keypoints.size() != descriptors.rows)
243 if(keypoints.size() == 0)
245 descriptors = cv::Mat();
249 cv::Mat newDescriptors((
int)keypoints.size(), descriptors.cols, descriptors.type());
251 for(
unsigned int i=0;
i<indexes.size(); ++
i)
255 if(descriptors.type() == CV_32FC1)
257 memcpy(newDescriptors.ptr<
float>(di++), descriptors.ptr<
float>(
i), descriptors.cols*
sizeof(
float));
261 memcpy(newDescriptors.ptr<
char>(di++), descriptors.ptr<
char>(
i), descriptors.cols*
sizeof(
char));
265 descriptors = newDescriptors;
274 limitKeypoints(keypoints, descriptors, maxKeypoints, imageSize, ssc);
277 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
279 std::vector<cv::Point3f> keypoints3D;
280 limitKeypoints(keypoints, keypoints3D, descriptors, maxKeypoints, imageSize, ssc);
283 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
285 UASSERT_MSG((
int)keypoints.size() == descriptors.rows || descriptors.rows == 0,
uFormat(
"keypoints=%d descriptors=%d", (
int)keypoints.size(), descriptors.rows).c_str());
286 UASSERT_MSG(keypoints.size() == keypoints3D.size() || keypoints3D.size() == 0,
uFormat(
"keypoints=%d keypoints3D=%d", (
int)keypoints.size(), (
int)keypoints3D.size()).c_str());
287 if(maxKeypoints > 0 && (
int)keypoints.size() > maxKeypoints)
291 std::vector<cv::KeyPoint> kptsTmp;
292 std::vector<cv::Point3f> kpts3DTmp;
293 cv::Mat descriptorsTmp;
296 ULOGGER_DEBUG(
"too much words (%d), removing words with SSC", keypoints.size());
297 static constexpr
float tolerance = 0.1;
298 auto ResultVec =
util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height);
299 removed = keypoints.size()-ResultVec.size();
301 kptsTmp.resize(ResultVec.size());
302 if(!keypoints3D.empty())
304 kpts3DTmp.resize(ResultVec.size());
308 descriptorsTmp = cv::Mat(ResultVec.size(), descriptors.cols, descriptors.type());
310 for(
unsigned int k=0; k<ResultVec.size(); ++k)
312 kptsTmp[k] = keypoints[ResultVec[k]];
313 if(keypoints3D.size())
315 kpts3DTmp[k] = keypoints3D[ResultVec[k]];
319 if(descriptors.type() == CV_32FC1)
321 memcpy(descriptorsTmp.ptr<
float>(k), descriptors.ptr<
float>(ResultVec[k]), descriptors.cols*
sizeof(
float));
325 memcpy(descriptorsTmp.ptr<
char>(k), descriptors.ptr<
char>(ResultVec[k]), descriptors.cols*
sizeof(
char));
332 ULOGGER_DEBUG(
"too much words (%d), removing words with the hessian threshold", keypoints.size());
336 std::multimap<float, int> hessianMap;
337 for(
unsigned int i = 0;
i <keypoints.size(); ++
i)
340 hessianMap.insert(std::pair<float, int>(
fabs(keypoints[
i].response),
i));
344 removed = (
int)hessianMap.size()-maxKeypoints;
345 std::multimap<float, int>::reverse_iterator
iter = hessianMap.rbegin();
346 kptsTmp.resize(maxKeypoints);
347 if(!keypoints3D.empty())
349 kpts3DTmp.resize(maxKeypoints);
353 descriptorsTmp = cv::Mat(maxKeypoints, descriptors.cols, descriptors.type());
355 for(
unsigned int k=0; k<kptsTmp.size() &&
iter!=hessianMap.rend(); ++k, ++
iter)
357 kptsTmp[k] = keypoints[
iter->second];
358 if(keypoints3D.size())
360 kpts3DTmp[k] = keypoints3D[
iter->second];
364 if(descriptors.type() == CV_32FC1)
366 memcpy(descriptorsTmp.ptr<
float>(k), descriptors.ptr<
float>(
iter->second), descriptors.cols*
sizeof(
float));
370 memcpy(descriptorsTmp.ptr<
char>(k), descriptors.ptr<
char>(
iter->second), descriptors.cols*
sizeof(
char));
375 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, (
int)kptsTmp.size(), !ssc&&kptsTmp.size()?kptsTmp.back().response:0.0f);
378 keypoints3D = kpts3DTmp;
381 descriptors = descriptorsTmp;
386 void Feature2D::limitKeypoints(
const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
388 if(maxKeypoints > 0 && (
int)keypoints.size() > maxKeypoints)
391 float minimumHessian = 0.0f;
393 inliers.resize(keypoints.size(),
false);
396 ULOGGER_DEBUG(
"too much words (%d), removing words with SSC", keypoints.size());
397 static constexpr
float tolerance = 0.1;
398 auto ResultVec =
util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height);
399 removed = keypoints.size()-ResultVec.size();
400 for(
unsigned int k=0; k<ResultVec.size(); ++k)
402 inliers[ResultVec[k]] =
true;
407 ULOGGER_DEBUG(
"too much words (%d), removing words with the hessian threshold", keypoints.size());
411 std::multimap<float, int> hessianMap;
412 for(
unsigned int i = 0;
i<keypoints.size(); ++
i)
415 hessianMap.insert(std::pair<float, int>(
fabs(keypoints[
i].response),
i));
419 removed = (
int)hessianMap.size()-maxKeypoints;
420 std::multimap<float, int>::reverse_iterator
iter = hessianMap.rbegin();
421 for(
int k=0; k<maxKeypoints &&
iter!=hessianMap.rend(); ++k, ++
iter)
423 inliers[
iter->second] =
true;
424 minimumHessian =
iter->first;
427 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, maxKeypoints, minimumHessian);
432 ULOGGER_DEBUG(
"keeping all %d keypoints", (
int)keypoints.size());
433 inliers.resize(keypoints.size(),
true);
437 void Feature2D::limitKeypoints(
const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers,
int maxKeypoints,
const cv::Size & imageSize,
int gridRows,
int gridCols,
bool ssc)
439 if(maxKeypoints <= 0 || (
int)keypoints.size() <= maxKeypoints)
441 inliers.resize(keypoints.size(),
true);
444 UASSERT(gridCols>=1 && gridRows >=1);
445 UASSERT(imageSize.height>gridRows && imageSize.width>gridCols);
446 int rowSize = imageSize.height / gridRows;
447 int colSize = imageSize.width / gridCols;
448 int maxKeypointsPerCell = maxKeypoints / (gridRows * gridCols);
449 std::vector<std::vector<cv::KeyPoint> > keypointsPerCell(gridRows * gridCols);
450 std::vector<std::vector<int> > indexesPerCell(gridRows * gridCols);
451 for(
size_t i=0;
i<keypoints.size(); ++
i)
453 int cellRow =
int(keypoints[
i].pt.y)/rowSize;
454 int cellCol =
int(keypoints[
i].pt.x)/colSize;
455 UASSERT(cellRow >=0 && cellRow < gridRows);
456 UASSERT(cellCol >=0 && cellCol < gridCols);
458 keypointsPerCell[cellRow*gridCols + cellCol].push_back(keypoints[
i]);
459 indexesPerCell[cellRow*gridCols + cellCol].push_back(
i);
461 inliers.resize(keypoints.size(),
false);
462 for(
size_t i=0;
i<keypointsPerCell.size(); ++
i)
464 std::vector<bool> inliersCell;
465 limitKeypoints(keypointsPerCell[
i], inliersCell, maxKeypointsPerCell, cv::Size(colSize, rowSize), ssc);
466 for(
size_t j=0;
j<inliersCell.size(); ++
j)
470 inliers.at(indexesPerCell[
i][
j]) =
true;
490 maxFeatures_(
Parameters::defaultKpMaxFeatures()),
495 _subPixWinSize(
Parameters::defaultKpSubPixWinSize()),
496 _subPixIterations(
Parameters::defaultKpSubPixIterations()),
525 ParametersMap::const_iterator
iter;
526 if((
iter=parameters.find(Parameters::kKpRoiRatios())) != parameters.end())
528 std::list<std::string> strValues =
uSplit(
iter->second,
' ');
529 if(strValues.size() != 4)
531 ULOGGER_ERROR(
"The number of values must be 4 (roi=\"%s\")",
iter->second.c_str());
535 std::vector<float> tmpValues(4);
537 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
543 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
544 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
545 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
546 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
552 ULOGGER_ERROR(
"The roi ratios are not valid (roi=\"%s\")",
iter->second.c_str());
559 if((
iter=parameters.find(Parameters::kStereoOpticalFlow())) != parameters.end())
571 int type = Parameters::defaultKpDetectorStrategy();
579 #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)))
581 #ifndef RTABMAP_NONFREE
584 #if CV_MAJOR_VERSION < 3
585 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
587 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
593 #else // >= 4.4.0 >= 3.4.11
595 #ifndef RTABMAP_NONFREE
598 UWARN(
"SURF features cannot be used because OpenCV was not built with nonfree module. SIFT is used instead.");
603 UWARN(
"SURF detector cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
608 #endif // >= 4.4.0 >= 3.4.11
610 #if !defined(HAVE_OPENCV_XFEATURES2D) && CV_MAJOR_VERSION >= 3
619 UWARN(
"BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
622 #elif CV_MAJOR_VERSION < 3
625 #ifdef RTABMAP_NONFREE
626 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. SURF is used instead.");
629 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. GFTT/ORB is used instead.");
635 UWARN(
"DAISY detector/descriptor can be used only with OpenCV3. GFTT/BRIEF is used instead.");
641 #ifndef RTABMAP_ORB_OCTREE
644 UWARN(
"ORB OcTree feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
649 #ifndef RTABMAP_TORCH
652 UWARN(
"SupertPoint Torch feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
661 feature2D =
new SURF(parameters);
664 feature2D =
new SIFT(parameters);
667 feature2D =
new ORB(parameters);
682 feature2D =
new GFTT_ORB(parameters);
685 feature2D =
new BRISK(parameters);
688 feature2D =
new KAZE(parameters);
707 #ifdef RTABMAP_PYTHON
712 #ifdef RTABMAP_NONFREE
714 feature2D =
new SURF(parameters);
719 feature2D =
new ORB(parameters);
731 UASSERT(image.type() == CV_8UC1);
736 if(maskIn.type()==CV_16UC1 || maskIn.type() == CV_32FC1)
738 mask = cv::Mat::zeros(maskIn.rows, maskIn.cols, CV_8UC1);
742 if(maskIn.type()==CV_16UC1)
744 if(((
unsigned short*)maskIn.data)[
i] > 0 &&
747 value =
float(((
unsigned short*)maskIn.data)[
i])*0.001f;
752 value = ((
float*)maskIn.data)[
i];
759 ((
unsigned char*)
mask.data)[
i] = 255;
763 else if(maskIn.type()==CV_8UC1)
770 UERROR(
"Wrong mask type (%d)! Should be 8UC1, 16UC1 or 32FC1.", maskIn.type());
776 std::vector<cv::KeyPoint> keypoints;
779 if(!(globalRoi.width && globalRoi.height))
781 globalRoi = cv::Rect(0,0,image.cols, image.rows);
785 int rowSize = globalRoi.height /
gridRows_;
786 int colSize = globalRoi.width /
gridCols_;
792 cv::Rect roi(globalRoi.x +
j*colSize, globalRoi.y +
i*rowSize, colSize, rowSize);
793 std::vector<cv::KeyPoint> subKeypoints;
795 if (this->
getType() != Feature2D::Type::kFeaturePyDetector)
802 for(std::vector<cv::KeyPoint>::iterator
iter=subKeypoints.begin();
iter!=subKeypoints.end(); ++
iter)
808 keypoints.insert( keypoints.end(), subKeypoints.begin(), subKeypoints.end() );
811 UDEBUG(
"Keypoints extraction time = %f s, keypoints extracted = %d (grid=%dx%d, mask empty=%d)",
816 std::vector<cv::Point2f>
corners;
817 cv::KeyPoint::convert(keypoints,
corners);
818 cv::cornerSubPix( image,
corners,
834 const cv::Mat & image,
835 std::vector<cv::KeyPoint> & keypoints)
const
841 UASSERT(image.type() == CV_8UC1);
843 UASSERT_MSG(descriptors.rows == (
int)keypoints.size(),
uFormat(
"descriptors=%d, keypoints=%d", descriptors.rows, (
int)keypoints.size()).c_str());
844 UDEBUG(
"Descriptors extracted = %d, remaining kpts=%d", descriptors.rows, (
int)keypoints.size());
851 const std::vector<cv::KeyPoint> & keypoints)
const
853 std::vector<cv::Point3f> keypoints3D;
856 if(!
data.rightRaw().empty() && !
data.imageRaw().empty() &&
857 !
data.stereoCameraModels().empty() &&
858 data.stereoCameraModels()[0].isValidForProjection())
863 if(
data.imageRaw().channels() > 1)
865 cv::cvtColor(
data.imageRaw(), imageMono, cv::COLOR_BGR2GRAY);
869 imageMono =
data.imageRaw();
872 std::vector<cv::Point2f> leftCorners;
873 cv::KeyPoint::convert(keypoints, leftCorners);
875 std::vector<cv::Point2f> rightCorners;
877 if(
data.stereoCameraModels().size() == 1)
879 std::vector<unsigned char> status;
889 for(
size_t i=0;
i<status.size(); ++
i)
896 if(rejected > (
int)status.size()/2)
898 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! "
899 "Optical flow may have failed because images are not calibrated, "
900 "the background is too far (no disparity between the images), "
901 "maximum disparity may be too small (%f) or that exposure between "
902 "left and right images is too different.",
912 data.stereoCameraModels()[0],
919 int subImageWith = imageMono.cols /
data.stereoCameraModels().size();
920 UASSERT(imageMono.cols % subImageWith == 0);
921 std::vector<std::vector<cv::Point2f> > subLeftCorners(
data.stereoCameraModels().size());
922 std::vector<std::vector<int> > subIndex(
data.stereoCameraModels().size());
924 for(
size_t i=0;
i<leftCorners.size(); ++
i)
926 int cameraIndex =
int(leftCorners[
i].
x / subImageWith);
927 leftCorners[
i].x -= cameraIndex*subImageWith;
928 subLeftCorners[cameraIndex].push_back(leftCorners[
i]);
929 subIndex[cameraIndex].push_back(
i);
932 keypoints3D.resize(keypoints.size());
935 for(
size_t i=0;
i<
data.stereoCameraModels().
size(); ++
i)
937 if(!subLeftCorners[
i].
empty())
939 std::vector<unsigned char> status;
941 imageMono.colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
942 data.rightRaw().colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
949 data.stereoCameraModels()[
i],
956 for(
size_t i=0;
i<status.size(); ++
i)
963 total+=status.size();
967 for(
size_t j=0;
j<subKeypoints3D.size(); ++
j)
969 keypoints3D[subIndex[
i][
j]] = subKeypoints3D[
j];
976 if(rejected > total/2)
978 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! "
979 "Optical flow may have failed because images are not calibrated, "
980 "the background is too far (no disparity between the images), "
981 "maximum disparity may be too small (%f) or that exposure between "
982 "left and right images is too different.",
990 else if(!
data.depthRaw().empty() &&
data.cameraModels().size())
994 data.depthOrRightRaw(),
1008 hessianThreshold_(
Parameters::defaultSURFHessianThreshold()),
1010 nOctaveLayers_(
Parameters::defaultSURFOctaveLayers()),
1011 extended_(
Parameters::defaultSURFExtended()),
1013 gpuKeypointsRatio_(
Parameters::defaultSURFGpuKeypointsRatio()),
1014 gpuVersion_(
Parameters::defaultSURFGpuVersion())
1035 #ifdef RTABMAP_NONFREE
1036 #if CV_MAJOR_VERSION < 3
1037 if(
gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1039 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
1043 if(
gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1045 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
1055 #if CV_MAJOR_VERSION < 3
1062 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1068 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1069 std::vector<cv::KeyPoint> keypoints;
1071 #ifdef RTABMAP_NONFREE
1072 cv::Mat imgRoi(image, roi);
1076 maskRoi = cv::Mat(
mask, roi);
1080 #if CV_MAJOR_VERSION < 3
1081 cv::gpu::GpuMat imgGpu(imgRoi);
1082 cv::gpu::GpuMat maskGpu(maskRoi);
1083 (*
_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1085 cv::cuda::GpuMat imgGpu(imgRoi);
1086 cv::cuda::GpuMat maskGpu(maskRoi);
1087 (*
_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1092 _surf->detect(imgRoi, keypoints, maskRoi);
1095 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1102 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1103 cv::Mat descriptors;
1104 #ifdef RTABMAP_NONFREE
1107 #if CV_MAJOR_VERSION < 3
1108 cv::gpu::GpuMat imgGpu(image);
1109 cv::gpu::GpuMat descriptorsGPU;
1110 (*
_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU,
true);
1112 cv::cuda::GpuMat imgGpu(image);
1113 cv::cuda::GpuMat descriptorsGPU;
1114 (*
_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU,
true);
1118 if (descriptorsGPU.empty())
1119 descriptors = cv::Mat();
1122 UASSERT(descriptorsGPU.type() == CV_32F);
1123 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1124 descriptorsGPU.download(descriptors);
1129 _surf->compute(image, keypoints, descriptors);
1132 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1142 nOctaveLayers_(
Parameters::defaultSIFTNOctaveLayers()),
1143 contrastThreshold_(
Parameters::defaultSIFTContrastThreshold()),
1144 edgeThreshold_(
Parameters::defaultSIFTEdgeThreshold()),
1165 #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)))
1166 #ifdef RTABMAP_NONFREE
1167 #if CV_MAJOR_VERSION < 3
1173 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1175 #else // >=4.4, >=3.4.11
1182 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1183 std::vector<cv::KeyPoint> keypoints;
1184 cv::Mat imgRoi(image, roi);
1188 maskRoi = cv::Mat(
mask, roi);
1190 #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)))
1191 #ifdef RTABMAP_NONFREE
1192 _sift->detect(imgRoi, keypoints, maskRoi);
1194 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1196 #else // >=4.4, >=3.4.11
1197 _sift->detect(imgRoi, keypoints, maskRoi);
1204 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1205 cv::Mat descriptors;
1206 #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)))
1207 #ifdef RTABMAP_NONFREE
1208 _sift->compute(image, keypoints, descriptors);
1210 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1212 #else // >=4.4, >=3.4.11
1213 _sift->compute(image, keypoints, descriptors);
1217 UDEBUG(
"Performing RootSIFT...");
1221 for(
int i=0;
i<descriptors.rows; ++
i)
1226 descriptors.row(
i) = descriptors.row(
i) / cv::sum(descriptors.row(
i))[0];
1227 cv::sqrt(descriptors.row(
i), descriptors.row(
i));
1237 scaleFactor_(
Parameters::defaultORBScaleFactor()),
1239 edgeThreshold_(
Parameters::defaultORBEdgeThreshold()),
1240 firstLevel_(
Parameters::defaultORBFirstLevel()),
1242 scoreType_(
Parameters::defaultORBScoreType()),
1243 patchSize_(
Parameters::defaultORBPatchSize()),
1245 fastThreshold_(
Parameters::defaultFASTThreshold()),
1246 nonmaxSuppresion_(
Parameters::defaultFASTNonmaxSuppression())
1271 #if CV_MAJOR_VERSION < 3
1272 #ifdef HAVE_OPENCV_GPU
1273 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1275 UWARN(
"GPU version of ORB not available! Using CPU version instead...");
1281 UWARN(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1286 #ifndef HAVE_OPENCV_CUDAFEATURES2D
1289 UWARN(
"GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1293 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1295 UWARN(
"GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1301 #if CV_MAJOR_VERSION < 3
1302 #ifdef HAVE_OPENCV_GPU
1306 UFATAL(
"not supposed to be here");
1309 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1316 #if CV_MAJOR_VERSION < 3
1318 #elif CV_MAJOR_VERSION > 3
1328 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1329 std::vector<cv::KeyPoint> keypoints;
1330 cv::Mat imgRoi(image, roi);
1334 maskRoi = cv::Mat(
mask, roi);
1339 #if CV_MAJOR_VERSION < 3
1340 #ifdef HAVE_OPENCV_GPU
1341 cv::gpu::GpuMat imgGpu(imgRoi);
1342 cv::gpu::GpuMat maskGpu(maskRoi);
1343 (*
_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1345 UERROR(
"Cannot use ORBGPU because OpenCV is not built with gpu module.");
1348 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1349 cv::cuda::GpuMat d_image(imgRoi);
1350 cv::cuda::GpuMat d_mask(maskRoi);
1352 _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(),
false);
1353 }
catch (cv::Exception&
e) {
1354 const char* err_msg =
e.what();
1355 UWARN(
"OpenCV exception caught: %s", err_msg);
1362 _orb->detect(imgRoi, keypoints, maskRoi);
1370 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1371 cv::Mat descriptors;
1379 #if CV_MAJOR_VERSION < 3
1380 #ifdef HAVE_OPENCV_GPU
1381 cv::gpu::GpuMat imgGpu(image);
1382 cv::gpu::GpuMat descriptorsGPU;
1383 (*
_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1385 if (descriptorsGPU.empty())
1386 descriptors = cv::Mat();
1389 UASSERT(descriptorsGPU.type() == CV_32F);
1390 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1391 descriptorsGPU.download(descriptors);
1394 UERROR(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1397 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1398 cv::cuda::GpuMat d_image(image);
1399 cv::cuda::GpuMat d_descriptors;
1401 _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors,
true);
1402 }
catch (cv::Exception&
e) {
1403 const char* err_msg =
e.what();
1404 UWARN(
"OpenCV exception caught: %s", err_msg);
1407 if (d_descriptors.empty())
1408 descriptors = cv::Mat();
1411 UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1412 d_descriptors.download(descriptors);
1419 _orb->compute(image, keypoints, descriptors);
1430 nonmaxSuppression_(
Parameters::defaultFASTNonmaxSuppression()),
1432 gpuKeypointsRatio_(
Parameters::defaultFASTGpuKeypointsRatio()),
1433 minThreshold_(
Parameters::defaultFASTMinThreshold()),
1434 maxThreshold_(
Parameters::defaultFASTMaxThreshold()),
1435 gridRows_(
Parameters::defaultFASTGridRows()),
1436 gridCols_(
Parameters::defaultFASTGridCols()),
1439 fastCVMaxFeatures_(10000),
1440 fastCVLastImageHeight_(0)
1442 #ifdef RTABMAP_FASTCV
1443 char sVersion[128] = { 0 };
1444 fcvGetVersion(sVersion, 128);
1445 UINFO(
"fastcv version = %s", sVersion);
1447 if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1449 UERROR(
"fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1459 UERROR(
"could not alloc fastcv mem, using opencv fast instead!");
1483 #ifdef RTABMAP_FASTCV
1518 #if CV_MAJOR_VERSION < 3
1519 #ifdef HAVE_OPENCV_GPU
1520 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1522 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1528 UWARN(
"GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1533 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1534 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1536 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1542 UWARN(
"GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1549 #if CV_MAJOR_VERSION < 3
1550 #ifdef HAVE_OPENCV_GPU
1553 UFATAL(
"not supposed to be here!");
1556 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1557 UFATAL(
"not implemented");
1563 #if CV_MAJOR_VERSION < 3
1574 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1579 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1592 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1593 std::vector<cv::KeyPoint> keypoints;
1595 #ifdef RTABMAP_FASTCV
1613 UERROR(
"could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().
c_str());
1625 fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0,
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1629 fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(),
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1631 UDEBUG(
"number of corners found = %d:", nCorners);
1632 keypoints.resize(nCorners);
1637 keypoints[
i].size = 3;
1651 UWARN(
"RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. "
1652 "Please set %s to 0. This message will only appear once.",
1653 Parameters::kFASTCV().
c_str());
1657 cv::Mat imgRoi(image, roi);
1661 maskRoi = cv::Mat(
mask, roi);
1665 #if CV_MAJOR_VERSION < 3
1666 #ifdef HAVE_OPENCV_GPU
1667 cv::gpu::GpuMat imgGpu(imgRoi);
1668 cv::gpu::GpuMat maskGpu(maskRoi);
1669 (*
_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1671 UERROR(
"Cannot use FAST GPU because OpenCV is not built with gpu module.");
1674 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1675 UFATAL(
"not implemented");
1681 _fast->detect(imgRoi, keypoints, maskRoi);
1705 #if CV_MAJOR_VERSION < 3
1708 #ifdef HAVE_OPENCV_XFEATURES2D
1711 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1718 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1719 cv::Mat descriptors;
1720 #if CV_MAJOR_VERSION < 3
1721 _brief->compute(image, keypoints, descriptors);
1723 #ifdef HAVE_OPENCV_XFEATURES2D
1724 _brief->compute(image, keypoints, descriptors);
1726 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1737 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1738 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1739 patternScale_(
Parameters::defaultFREAKPatternScale()),
1740 nOctaves_(
Parameters::defaultFREAKNOctaves())
1758 #if CV_MAJOR_VERSION < 3
1761 #ifdef HAVE_OPENCV_XFEATURES2D
1764 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1771 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1772 cv::Mat descriptors;
1773 #if CV_MAJOR_VERSION < 3
1774 _freak->compute(image, keypoints, descriptors);
1776 #ifdef HAVE_OPENCV_XFEATURES2D
1777 _freak->compute(image, keypoints, descriptors);
1779 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1789 _qualityLevel(
Parameters::defaultGFTTQualityLevel()),
1790 _minDistance(
Parameters::defaultGFTTMinDistance()),
1791 _blockSize(
Parameters::defaultGFTTBlockSize()),
1792 _useHarrisDetector(
Parameters::defaultGFTTUseHarrisDetector()),
1812 #if CV_MAJOR_VERSION < 3
1821 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1822 std::vector<cv::KeyPoint> keypoints;
1823 cv::Mat imgRoi(image, roi);
1827 maskRoi = cv::Mat(
mask, roi);
1829 _gftt->detect(imgRoi, keypoints, maskRoi);
1852 #if CV_MAJOR_VERSION < 3
1855 #ifdef HAVE_OPENCV_XFEATURES2D
1858 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1865 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1866 cv::Mat descriptors;
1867 #if CV_MAJOR_VERSION < 3
1868 _brief->compute(image, keypoints, descriptors);
1870 #ifdef HAVE_OPENCV_XFEATURES2D
1871 _brief->compute(image, keypoints, descriptors);
1873 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1884 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1885 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1886 patternScale_(
Parameters::defaultFREAKPatternScale()),
1887 nOctaves_(
Parameters::defaultFREAKNOctaves())
1905 #if CV_MAJOR_VERSION < 3
1908 #ifdef HAVE_OPENCV_XFEATURES2D
1911 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1918 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1919 cv::Mat descriptors;
1920 #if CV_MAJOR_VERSION < 3
1921 _freak->compute(image, keypoints, descriptors);
1923 #ifdef HAVE_OPENCV_XFEATURES2D
1924 _freak->compute(image, keypoints, descriptors);
1926 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1937 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1938 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1939 patternScale_(
Parameters::defaultFREAKPatternScale()),
1940 nOctaves_(
Parameters::defaultFREAKNOctaves())
1958 #if CV_MAJOR_VERSION < 3
1961 #ifdef HAVE_OPENCV_XFEATURES2D
1964 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1971 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1972 cv::Mat descriptors;
1973 #if CV_MAJOR_VERSION < 3
1974 _freak->compute(image, keypoints, descriptors);
1976 #ifdef HAVE_OPENCV_XFEATURES2D
1977 _freak->compute(image, keypoints, descriptors);
1979 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2007 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2017 patternScale_(
Parameters::defaultBRISKPatternScale())
2034 #if CV_MAJOR_VERSION < 3
2043 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2044 std::vector<cv::KeyPoint> keypoints;
2045 cv::Mat imgRoi(image, roi);
2049 maskRoi = cv::Mat(
mask, roi);
2051 brisk_->detect(imgRoi, keypoints, maskRoi);
2057 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2058 cv::Mat descriptors;
2059 brisk_->compute(image, keypoints, descriptors);
2067 extended_(
Parameters::defaultKAZEExtended()),
2070 nOctaves_(
Parameters::defaultKAZENOctaves()),
2071 nOctaveLayers_(
Parameters::defaultKAZENOctaveLayers()),
2072 diffusivity_(
Parameters::defaultKAZEDiffusivity())
2092 #if CV_MAJOR_VERSION > 3
2094 #elif CV_MAJOR_VERSION > 2
2097 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2103 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2104 std::vector<cv::KeyPoint> keypoints;
2105 #if CV_MAJOR_VERSION > 2
2106 cv::Mat imgRoi(image, roi);
2110 maskRoi = cv::Mat(
mask, roi);
2112 kaze_->detect(imgRoi, keypoints, maskRoi);
2114 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2121 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2122 cv::Mat descriptors;
2123 #if CV_MAJOR_VERSION > 2
2124 kaze_->compute(image, keypoints, descriptors);
2126 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2135 scaleFactor_(
Parameters::defaultORBScaleFactor()),
2137 patchSize_(
Parameters::defaultORBPatchSize()),
2138 edgeThreshold_(
Parameters::defaultORBEdgeThreshold()),
2139 fastThreshold_(
Parameters::defaultFASTThreshold()),
2140 fastMinThreshold_(
Parameters::defaultFASTMinThreshold())
2161 #ifdef RTABMAP_ORB_OCTREE
2164 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2170 std::vector<cv::KeyPoint> keypoints;
2172 #ifdef RTABMAP_ORB_OCTREE
2173 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2174 cv::Mat imgRoi(image, roi);
2178 maskRoi = cv::Mat(
mask, roi);
2184 if(!keypoints.empty() && !maskRoi.empty())
2186 std::vector<cv::KeyPoint> validKeypoints;
2187 validKeypoints.reserve(keypoints.size());
2188 cv::Mat validDescriptors;
2189 for(
size_t i=0;
i<keypoints.size(); ++
i)
2191 if(maskRoi.at<
unsigned char>(keypoints[
i].pt.y+roi.y, keypoints[
i].pt.x+roi.x) != 0)
2193 validKeypoints.push_back(keypoints[
i]);
2197 keypoints = validKeypoints;
2206 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2213 #ifdef RTABMAP_ORB_OCTREE
2216 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2225 path_(
Parameters::defaultSuperPointModelPath()),
2228 minDistance_(
Parameters::defaultSuperPointNMSRadius()),
2242 std::string previousPath =
path_;
2243 #ifdef RTABMAP_TORCH
2244 bool previousCuda =
cuda_;
2252 #ifdef RTABMAP_TORCH
2264 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2270 #ifdef RTABMAP_TORCH
2271 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2272 if(roi.x!=0 || roi.y !=0)
2274 UERROR(
"SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2275 roi.x, roi.y, roi.width, roi.height,
2276 Parameters::kKpRoiRatios().c_str(),
2277 Parameters::kVisRoiRatios().c_str(),
2278 Parameters::kVisGridRows().c_str(),
2279 Parameters::kVisGridCols().c_str(),
2280 Parameters::kKpGridRows().c_str(),
2281 Parameters::kKpGridCols().c_str());
2282 return std::vector<cv::KeyPoint>();
2286 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2287 return std::vector<cv::KeyPoint>();
2293 #ifdef RTABMAP_TORCH
2294 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2297 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2308 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2309 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2310 patternScale_(
Parameters::defaultFREAKPatternScale()),
2311 nOctaves_(
Parameters::defaultFREAKNOctaves())
2329 #ifdef HAVE_OPENCV_XFEATURES2D
2330 _daisy = CV_DAISY::create();
2332 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2338 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2339 cv::Mat descriptors;
2340 #ifdef HAVE_OPENCV_XFEATURES2D
2341 _daisy->compute(image, keypoints, descriptors);
2343 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2353 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2354 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2355 patternScale_(
Parameters::defaultFREAKPatternScale()),
2356 nOctaves_(
Parameters::defaultFREAKNOctaves())
2374 #ifdef HAVE_OPENCV_XFEATURES2D
2375 _daisy = CV_DAISY::create();
2377 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2383 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2384 cv::Mat descriptors;
2385 #ifdef HAVE_OPENCV_XFEATURES2D
2386 _daisy->compute(image, keypoints, descriptors);
2388 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");