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>
78 #ifdef HAVE_OPENCV_CUDAIMGPROC
79 #include <opencv2/cudaimgproc.hpp>
86 #ifdef RTABMAP_CUDASIFT
87 #include <cudasift/cudaImage.h>
88 #include <cudasift/cudaSift.h>
93 std::vector<cv::KeyPoint> & keypoints,
94 const cv::Mat & depth,
103 std::vector<cv::KeyPoint> & keypoints,
104 cv::Mat & descriptors,
105 const cv::Mat & depth,
110 UASSERT(maxDepth <= 0.0f || maxDepth > minDepth);
111 if(!depth.empty() && (descriptors.empty() || descriptors.rows == (
int)keypoints.size()))
113 std::vector<cv::KeyPoint> output(keypoints.size());
114 std::vector<int> indexes(keypoints.size(), 0);
116 bool isInMM = depth.type() == CV_16UC1;
117 for(
unsigned int i=0;
i<keypoints.size(); ++
i)
119 int u =
int(keypoints[
i].pt.x+0.5f);
120 int v =
int(keypoints[
i].pt.y+0.5f);
121 if(u >=0 && u<depth.cols && v >=0 &&
v<depth.rows)
123 float d = isInMM?(
float)depth.at<
uint16_t>(
v,u)*0.001f:depth.at<
float>(
v,u);
124 if(
uIsFinite(
d) &&
d>minDepth && (maxDepth <= 0.0f ||
d < maxDepth))
126 output[oi++] = keypoints[
i];
134 if(!descriptors.empty() && (
int)keypoints.size() != descriptors.rows)
136 if(keypoints.size() == 0)
138 descriptors = cv::Mat();
142 cv::Mat newDescriptors((
int)keypoints.size(), descriptors.cols, descriptors.type());
144 for(
unsigned int i=0;
i<indexes.size(); ++
i)
148 if(descriptors.type() == CV_32FC1)
150 memcpy(newDescriptors.ptr<
float>(di++), descriptors.ptr<
float>(
i), descriptors.cols*
sizeof(
float));
154 memcpy(newDescriptors.ptr<
char>(di++), descriptors.ptr<
char>(
i), descriptors.cols*
sizeof(
char));
158 descriptors = newDescriptors;
165 std::vector<cv::KeyPoint> & keypoints,
166 cv::Mat & descriptors,
167 std::vector<cv::Point3f> & keypoints3D,
173 UASSERT(((
int)keypoints.size() == descriptors.rows || descriptors.empty()) &&
174 keypoints3D.size() == keypoints.size());
175 std::vector<cv::KeyPoint> validKeypoints(keypoints.size());
176 std::vector<cv::Point3f> validKeypoints3D(keypoints.size());
177 cv::Mat validDescriptors(descriptors.size(), descriptors.type());
180 float minDepthSqr = minDepth * minDepth;
181 float maxDepthSqr = maxDepth * maxDepth;
182 for(
unsigned int i=0;
i<keypoints3D.size(); ++
i)
184 cv::Point3f & pt = keypoints3D[
i];
187 float distSqr = pt.x*pt.x+pt.y*pt.y+pt.z*pt.z;
188 if(distSqr >= minDepthSqr && (maxDepthSqr==0.0
f || distSqr <= maxDepthSqr))
190 validKeypoints[oi] = keypoints[
i];
191 validKeypoints3D[oi] = pt;
192 if(!descriptors.empty())
194 descriptors.row(
i).copyTo(validDescriptors.row(oi));
200 UDEBUG(
"Removed %d invalid 3D points", (
int)keypoints3D.size()-oi);
201 validKeypoints.resize(oi);
202 validKeypoints3D.resize(oi);
203 keypoints = validKeypoints;
204 keypoints3D = validKeypoints3D;
205 if(!descriptors.empty())
207 descriptors = validDescriptors.rowRange(0, oi).clone();
212 std::vector<cv::KeyPoint> & keypoints,
213 const cv::Mat & disparity,
221 std::vector<cv::KeyPoint> & keypoints,
222 cv::Mat & descriptors,
223 const cv::Mat & disparity,
226 if(!disparity.empty() && minDisparity > 0.0f && (descriptors.empty() || descriptors.rows == (
int)keypoints.size()))
228 std::vector<cv::KeyPoint> output(keypoints.size());
229 std::vector<int> indexes(keypoints.size(), 0);
231 for(
unsigned int i=0;
i<keypoints.size(); ++
i)
233 int u =
int(keypoints[
i].pt.x+0.5f);
234 int v =
int(keypoints[
i].pt.y+0.5f);
235 if(u >=0 && u<disparity.cols && v >=0 &&
v<disparity.rows)
237 float d = disparity.type() == CV_16SC1?
float(disparity.at<
short>(
v,u))/16.0f:disparity.at<
float>(
v,u);
240 output[oi++] = keypoints[
i];
248 if(!descriptors.empty() && (
int)keypoints.size() != descriptors.rows)
250 if(keypoints.size() == 0)
252 descriptors = cv::Mat();
256 cv::Mat newDescriptors((
int)keypoints.size(), descriptors.cols, descriptors.type());
258 for(
unsigned int i=0;
i<indexes.size(); ++
i)
262 if(descriptors.type() == CV_32FC1)
264 memcpy(newDescriptors.ptr<
float>(di++), descriptors.ptr<
float>(
i), descriptors.cols*
sizeof(
float));
268 memcpy(newDescriptors.ptr<
char>(di++), descriptors.ptr<
char>(
i), descriptors.cols*
sizeof(
char));
272 descriptors = newDescriptors;
281 limitKeypoints(keypoints, descriptors, maxKeypoints, imageSize, ssc);
284 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
286 std::vector<cv::Point3f> keypoints3D;
287 limitKeypoints(keypoints, keypoints3D, descriptors, maxKeypoints, imageSize, ssc);
290 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
292 UASSERT_MSG((
int)keypoints.size() == descriptors.rows || descriptors.rows == 0,
uFormat(
"keypoints=%d descriptors=%d", (
int)keypoints.size(), descriptors.rows).c_str());
293 UASSERT_MSG(keypoints.size() == keypoints3D.size() || keypoints3D.size() == 0,
uFormat(
"keypoints=%d keypoints3D=%d", (
int)keypoints.size(), (
int)keypoints3D.size()).c_str());
294 if(maxKeypoints > 0 && (
int)keypoints.size() > maxKeypoints)
298 std::vector<cv::KeyPoint> kptsTmp;
299 std::vector<cv::Point3f> kpts3DTmp;
300 cv::Mat descriptorsTmp;
303 ULOGGER_DEBUG(
"too much words (%d), removing words with SSC", keypoints.size());
306 std::vector<float> responseVector;
307 for (
unsigned int i = 0;
i < keypoints.size();
i++)
309 responseVector.push_back(keypoints[
i].response);
311 std::vector<int> indx(responseVector.size());
312 std::iota(std::begin(indx), std::end(indx), 0);
314 #if CV_MAJOR_VERSION >= 4
315 cv::sortIdx(responseVector, indx, cv::SORT_DESCENDING);
317 cv::sortIdx(responseVector, indx, CV_SORT_DESCENDING);
320 static constexpr
float tolerance = 0.1;
321 auto ResultVec =
util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height, indx);
322 removed = keypoints.size()-ResultVec.size();
324 kptsTmp.resize(ResultVec.size());
325 if(!keypoints3D.empty())
327 kpts3DTmp.resize(ResultVec.size());
331 descriptorsTmp = cv::Mat(ResultVec.size(), descriptors.cols, descriptors.type());
333 for(
unsigned int k=0; k<ResultVec.size(); ++k)
335 kptsTmp[k] = keypoints[ResultVec[k]];
336 if(keypoints3D.size())
338 kpts3DTmp[k] = keypoints3D[ResultVec[k]];
342 if(descriptors.type() == CV_32FC1)
344 memcpy(descriptorsTmp.ptr<
float>(k), descriptors.ptr<
float>(ResultVec[k]), descriptors.cols*
sizeof(
float));
348 memcpy(descriptorsTmp.ptr<
char>(k), descriptors.ptr<
char>(ResultVec[k]), descriptors.cols*
sizeof(
char));
355 ULOGGER_DEBUG(
"too many words (%d), removing words with the hessian threshold", keypoints.size());
359 std::multimap<float, int> hessianMap;
360 for(
unsigned int i = 0;
i <keypoints.size(); ++
i)
363 hessianMap.insert(std::pair<float, int>(
fabs(keypoints[
i].response),
i));
367 removed = (
int)hessianMap.size()-maxKeypoints;
368 std::multimap<float, int>::reverse_iterator
iter = hessianMap.rbegin();
369 kptsTmp.resize(maxKeypoints);
370 if(!keypoints3D.empty())
372 kpts3DTmp.resize(maxKeypoints);
376 descriptorsTmp = cv::Mat(maxKeypoints, descriptors.cols, descriptors.type());
378 for(
unsigned int k=0; k<kptsTmp.size() &&
iter!=hessianMap.rend(); ++k, ++
iter)
380 kptsTmp[k] = keypoints[
iter->second];
381 if(keypoints3D.size())
383 kpts3DTmp[k] = keypoints3D[
iter->second];
387 if(descriptors.type() == CV_32FC1)
389 memcpy(descriptorsTmp.ptr<
float>(k), descriptors.ptr<
float>(
iter->second), descriptors.cols*
sizeof(
float));
393 memcpy(descriptorsTmp.ptr<
char>(k), descriptors.ptr<
char>(
iter->second), descriptors.cols*
sizeof(
char));
398 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, (
int)kptsTmp.size(), !ssc&&kptsTmp.size()?kptsTmp.back().response:0.0f);
401 keypoints3D = kpts3DTmp;
404 descriptors = descriptorsTmp;
409 void Feature2D::limitKeypoints(
const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers,
int maxKeypoints,
const cv::Size & imageSize,
bool ssc)
411 if(maxKeypoints > 0 && (
int)keypoints.size() > maxKeypoints)
414 float minimumHessian = 0.0f;
416 inliers.resize(keypoints.size(),
false);
419 ULOGGER_DEBUG(
"too much words (%d), removing words with SSC", keypoints.size());
422 std::vector<float> responseVector;
423 for (
unsigned int i = 0;
i < keypoints.size();
i++)
425 responseVector.push_back(keypoints[
i].response);
427 std::vector<int> indx(responseVector.size());
428 std::iota(std::begin(indx), std::end(indx), 0);
430 #if CV_MAJOR_VERSION >= 4
431 cv::sortIdx(responseVector, indx, cv::SORT_DESCENDING);
433 cv::sortIdx(responseVector, indx, CV_SORT_DESCENDING);
436 static constexpr
float tolerance = 0.1;
437 auto ResultVec =
util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height, indx);
438 removed = keypoints.size()-ResultVec.size();
439 for(
unsigned int k=0; k<ResultVec.size(); ++k)
441 inliers[ResultVec[k]] =
true;
446 ULOGGER_DEBUG(
"too much words (%d), removing words with the hessian threshold", keypoints.size());
450 std::multimap<float, int> hessianMap;
451 for(
unsigned int i = 0;
i<keypoints.size(); ++
i)
454 hessianMap.insert(std::pair<float, int>(
fabs(keypoints[
i].response),
i));
458 removed = (
int)hessianMap.size()-maxKeypoints;
459 std::multimap<float, int>::reverse_iterator
iter = hessianMap.rbegin();
460 for(
int k=0; k<maxKeypoints &&
iter!=hessianMap.rend(); ++k, ++
iter)
462 inliers[
iter->second] =
true;
463 minimumHessian =
iter->first;
466 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, maxKeypoints, minimumHessian);
471 ULOGGER_DEBUG(
"keeping all %d keypoints", (
int)keypoints.size());
472 inliers.resize(keypoints.size(),
true);
476 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)
478 if(maxKeypoints <= 0 || (
int)keypoints.size() <= maxKeypoints)
480 inliers.resize(keypoints.size(),
true);
483 UASSERT(gridCols>=1 && gridRows >=1);
484 UASSERT(imageSize.height>gridRows && imageSize.width>gridCols);
485 int rowSize = imageSize.height / gridRows;
486 int colSize = imageSize.width / gridCols;
487 int maxKeypointsPerCell = maxKeypoints / (gridRows * gridCols);
488 std::vector<std::vector<cv::KeyPoint> > keypointsPerCell(gridRows * gridCols);
489 std::vector<std::vector<int> > indexesPerCell(gridRows * gridCols);
490 for(
size_t i=0;
i<keypoints.size(); ++
i)
492 int cellRow =
int(keypoints[
i].pt.y)/rowSize;
493 int cellCol =
int(keypoints[
i].pt.x)/colSize;
494 UASSERT(cellRow >=0 && cellRow < gridRows);
495 UASSERT(cellCol >=0 && cellCol < gridCols);
497 keypointsPerCell[cellRow*gridCols + cellCol].push_back(keypoints[
i]);
498 indexesPerCell[cellRow*gridCols + cellCol].push_back(
i);
500 inliers.resize(keypoints.size(),
false);
501 for(
size_t i=0;
i<keypointsPerCell.size(); ++
i)
503 std::vector<bool> inliersCell;
504 limitKeypoints(keypointsPerCell[
i], inliersCell, maxKeypointsPerCell, cv::Size(colSize, rowSize), ssc);
505 for(
size_t j=0;
j<inliersCell.size(); ++
j)
509 inliers.at(indexesPerCell[
i][
j]) =
true;
529 maxFeatures_(
Parameters::defaultKpMaxFeatures()),
534 _subPixWinSize(
Parameters::defaultKpSubPixWinSize()),
535 _subPixIterations(
Parameters::defaultKpSubPixIterations()),
564 ParametersMap::const_iterator
iter;
565 if((
iter=parameters.find(Parameters::kKpRoiRatios())) != parameters.end())
567 std::list<std::string> strValues =
uSplit(
iter->second,
' ');
568 if(strValues.size() != 4)
570 ULOGGER_ERROR(
"The number of values must be 4 (roi=\"%s\")",
iter->second.c_str());
574 std::vector<float> tmpValues(4);
576 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
582 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
583 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
584 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
585 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
591 ULOGGER_ERROR(
"The roi ratios are not valid (roi=\"%s\")",
iter->second.c_str());
598 if((
iter=parameters.find(Parameters::kStereoOpticalFlow())) != parameters.end())
610 int type = Parameters::defaultKpDetectorStrategy();
618 #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)))
620 #ifndef RTABMAP_NONFREE
623 #if CV_MAJOR_VERSION < 3
624 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
626 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
632 #else // >= 4.4.0 >= 3.4.11
634 #ifndef RTABMAP_NONFREE
637 UWARN(
"SURF features cannot be used because OpenCV was not built with nonfree module. SIFT is used instead.");
642 UWARN(
"SURF detector cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
647 #endif // >= 4.4.0 >= 3.4.11
649 #if !defined(HAVE_OPENCV_XFEATURES2D) && CV_MAJOR_VERSION >= 3
658 UWARN(
"BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
661 #elif CV_MAJOR_VERSION < 3
664 #ifdef RTABMAP_NONFREE
665 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. SURF is used instead.");
668 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. GFTT/ORB is used instead.");
674 UWARN(
"DAISY detector/descriptor can be used only with OpenCV3. GFTT/BRIEF is used instead.");
680 #ifndef RTABMAP_ORB_OCTREE
683 UWARN(
"ORB OcTree feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
688 #ifndef RTABMAP_TORCH
691 UWARN(
"SupertPoint Torch feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
700 feature2D =
new SURF(parameters);
703 feature2D =
new SIFT(parameters);
706 feature2D =
new ORB(parameters);
721 feature2D =
new GFTT_ORB(parameters);
724 feature2D =
new BRISK(parameters);
727 feature2D =
new KAZE(parameters);
746 #ifdef RTABMAP_PYTHON
751 #ifdef RTABMAP_NONFREE
753 feature2D =
new SURF(parameters);
758 feature2D =
new ORB(parameters);
770 UASSERT(image.type() == CV_8UC1);
775 if(maskIn.type()==CV_16UC1 || maskIn.type() == CV_32FC1)
777 mask = cv::Mat::zeros(maskIn.rows, maskIn.cols, CV_8UC1);
781 if(maskIn.type()==CV_16UC1)
783 if(((
unsigned short*)maskIn.data)[
i] > 0 &&
786 value =
float(((
unsigned short*)maskIn.data)[
i])*0.001f;
791 value = ((
float*)maskIn.data)[
i];
798 ((
unsigned char*)
mask.data)[
i] = 255;
802 else if(maskIn.type()==CV_8UC1)
809 UERROR(
"Wrong mask type (%d)! Should be 8UC1, 16UC1 or 32FC1.", maskIn.type());
815 std::vector<cv::KeyPoint> keypoints;
818 if(!(globalRoi.width && globalRoi.height))
820 globalRoi = cv::Rect(0,0,image.cols, image.rows);
824 int rowSize = globalRoi.height /
gridRows_;
825 int colSize = globalRoi.width /
gridCols_;
831 cv::Rect roi(globalRoi.x +
j*colSize, globalRoi.y +
i*rowSize, colSize, rowSize);
832 std::vector<cv::KeyPoint> subKeypoints;
834 if (this->
getType() != Feature2D::Type::kFeaturePyDetector)
841 for(std::vector<cv::KeyPoint>::iterator
iter=subKeypoints.begin();
iter!=subKeypoints.end(); ++
iter)
847 keypoints.insert( keypoints.end(), subKeypoints.begin(), subKeypoints.end() );
850 UDEBUG(
"Keypoints extraction time = %f s, keypoints extracted = %d (grid=%dx%d, mask empty=%d)",
855 std::vector<cv::Point2f>
corners;
856 cv::KeyPoint::convert(keypoints,
corners);
857 cv::cornerSubPix( image,
corners,
873 const cv::Mat & image,
874 std::vector<cv::KeyPoint> & keypoints)
const
880 UASSERT(image.type() == CV_8UC1);
882 UASSERT_MSG(descriptors.rows == (
int)keypoints.size(),
uFormat(
"descriptors=%d, keypoints=%d", descriptors.rows, (
int)keypoints.size()).c_str());
883 UDEBUG(
"Descriptors extracted = %d, remaining kpts=%d", descriptors.rows, (
int)keypoints.size());
890 const std::vector<cv::KeyPoint> & keypoints)
const
892 std::vector<cv::Point3f> keypoints3D;
895 if(!
data.rightRaw().empty() && !
data.imageRaw().empty() &&
896 !
data.stereoCameraModels().empty() &&
897 data.stereoCameraModels()[0].isValidForProjection())
900 cv::Mat imageLeft =
data.imageRaw();
901 cv::Mat imageRight =
data.rightRaw();
902 #ifdef HAVE_OPENCV_CUDEV
903 cv::cuda::GpuMat d_imageLeft;
904 cv::cuda::GpuMat d_imageRight;
907 d_imageLeft =
data.imageRawGpu();
908 if(d_imageLeft.empty()) {
909 d_imageLeft = cv::cuda::GpuMat(imageLeft);
912 if(d_imageLeft.channels() > 1) {
913 cv::cuda::GpuMat tmp;
914 cv::cuda::cvtColor(d_imageLeft, tmp, cv::COLOR_BGR2GRAY);
917 d_imageRight =
data.depthOrRightRawGpu();
918 if(d_imageRight.empty()) {
919 d_imageRight = cv::cuda::GpuMat(imageRight);
926 if(imageLeft.channels() > 1)
928 cv::cvtColor(
data.imageRaw(), imageLeft, cv::COLOR_BGR2GRAY);
932 std::vector<cv::Point2f> leftCorners;
933 cv::KeyPoint::convert(keypoints, leftCorners);
935 std::vector<cv::Point2f> rightCorners;
937 if(
data.stereoCameraModels().size() == 1)
939 std::vector<unsigned char> status;
940 #ifdef HAVE_OPENCV_CUDEV
962 for(
size_t i=0;
i<status.size(); ++
i)
969 if(rejected > (
int)status.size()/2)
971 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! "
972 "Optical flow may have failed because images are not calibrated, "
973 "the background is too far (no disparity between the images), "
974 "maximum disparity may be too small (%f) or that exposure between "
975 "left and right images is too different.",
985 data.stereoCameraModels()[0],
992 int subImageWith = imageLeft.cols /
data.stereoCameraModels().size();
993 UASSERT(imageLeft.cols % subImageWith == 0);
994 std::vector<std::vector<cv::Point2f> > subLeftCorners(
data.stereoCameraModels().size());
995 std::vector<std::vector<int> > subIndex(
data.stereoCameraModels().size());
997 for(
size_t i=0;
i<leftCorners.size(); ++
i)
999 int cameraIndex =
int(leftCorners[
i].
x / subImageWith);
1000 leftCorners[
i].x -= cameraIndex*subImageWith;
1001 subLeftCorners[cameraIndex].push_back(leftCorners[
i]);
1002 subIndex[cameraIndex].push_back(
i);
1005 keypoints3D.resize(keypoints.size());
1008 for(
size_t i=0;
i<
data.stereoCameraModels().
size(); ++
i)
1010 if(!subLeftCorners[
i].
empty())
1012 std::vector<unsigned char> status;
1013 #ifdef HAVE_OPENCV_CUDEV
1017 d_imageLeft.colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
1018 d_imageRight.colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
1026 imageLeft.colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
1027 imageRight.colRange(cv::Range(subImageWith*
i, subImageWith*(
i+1))),
1035 data.stereoCameraModels()[
i],
1042 for(
size_t i=0;
i<status.size(); ++
i)
1049 total+=status.size();
1053 for(
size_t j=0;
j<subKeypoints3D.size(); ++
j)
1055 keypoints3D[subIndex[
i][
j]] = subKeypoints3D[
j];
1062 if(rejected > total/2)
1064 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! "
1065 "Optical flow may have failed because images are not calibrated, "
1066 "the background is too far (no disparity between the images), "
1067 "maximum disparity may be too small (%f) or that exposure between "
1068 "left and right images is too different.",
1076 else if(!
data.depthRaw().empty() &&
data.cameraModels().size())
1080 data.depthOrRightRaw(),
1081 data.cameraModels(),
1094 hessianThreshold_(
Parameters::defaultSURFHessianThreshold()),
1096 nOctaveLayers_(
Parameters::defaultSURFOctaveLayers()),
1097 extended_(
Parameters::defaultSURFExtended()),
1099 gpuKeypointsRatio_(
Parameters::defaultSURFGpuKeypointsRatio()),
1100 gpuVersion_(
Parameters::defaultSURFGpuVersion())
1121 #ifdef RTABMAP_NONFREE
1122 #if CV_MAJOR_VERSION < 3
1123 if(
gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1125 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
1129 if(
gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1131 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
1141 #if CV_MAJOR_VERSION < 3
1148 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1154 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1155 std::vector<cv::KeyPoint> keypoints;
1157 #ifdef RTABMAP_NONFREE
1158 cv::Mat imgRoi(image, roi);
1162 maskRoi = cv::Mat(
mask, roi);
1166 #if CV_MAJOR_VERSION < 3
1167 cv::gpu::GpuMat imgGpu(imgRoi);
1168 cv::gpu::GpuMat maskGpu(maskRoi);
1169 (*
_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1171 cv::cuda::GpuMat imgGpu(imgRoi);
1172 cv::cuda::GpuMat maskGpu(maskRoi);
1173 (*
_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1178 _surf->detect(imgRoi, keypoints, maskRoi);
1181 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1188 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1189 cv::Mat descriptors;
1190 #ifdef RTABMAP_NONFREE
1193 #if CV_MAJOR_VERSION < 3
1194 cv::gpu::GpuMat imgGpu(image);
1195 cv::gpu::GpuMat descriptorsGPU;
1196 (*
_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU,
true);
1198 cv::cuda::GpuMat imgGpu(image);
1199 cv::cuda::GpuMat descriptorsGPU;
1200 (*
_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU,
true);
1204 if (descriptorsGPU.empty())
1205 descriptors = cv::Mat();
1208 UASSERT(descriptorsGPU.type() == CV_32F);
1209 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1210 descriptorsGPU.download(descriptors);
1215 _surf->compute(image, keypoints, descriptors);
1218 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1228 nOctaveLayers_(
Parameters::defaultSIFTNOctaveLayers()),
1229 contrastThreshold_(
Parameters::defaultSIFTContrastThreshold()),
1230 edgeThreshold_(
Parameters::defaultSIFTEdgeThreshold()),
1232 preciseUpscale_(
Parameters::defaultSIFTPreciseUpscale()),
1233 rootSIFT_(
Parameters::defaultSIFTRootSIFT()),
1235 guaussianThreshold_(
Parameters::defaultSIFTGaussianThreshold()),
1239 cudaSiftUpscaling_(upscale_)
1246 #ifdef RTABMAP_CUDASIFT
1273 #ifdef RTABMAP_CUDASIFT
1283 UWARN(
"No cuda device(s) detected, CudaSift is not available! Using SIFT CPU version instead.");
1287 UWARN(
"RTAB-Map is not built with CudaSift so %s cannot be used!", Parameters::kSIFTGpu().
c_str());
1294 #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)))
1295 #ifdef RTABMAP_NONFREE
1296 #if CV_MAJOR_VERSION < 3
1302 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1304 #elif CV_MAJOR_VERSION>4 || (CV_MAJOR_VERSION==4 && CV_MINOR_VERSION>=8)// >=4.8
1306 #else // >=4.4, >=3.4.11
1315 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1316 std::vector<cv::KeyPoint> keypoints;
1317 cv::Mat imgRoi(image, roi);
1321 maskRoi = cv::Mat(
mask, roi);
1323 #ifdef RTABMAP_CUDASIFT
1327 int w = imgRoi.cols;
1328 int h = imgRoi.rows;
1330 imgRoi.convertTo(img_h, CV_32FC1);
1332 img_d.Allocate(
w,
h, iAlignUp(
w, 128),
false,
NULL, (
float*)img_h.data);
1339 if(numOctaves < 1) {
1342 else if (numOctaves>7)
1349 float minScale = 0.0f;
1350 UDEBUG(
"numOctaves=%d initBlur=%f thresh=%f edgeLimit=%f minScale=%f upScale=%s w=%d h=%d", numOctaves, initBlur, thresh, edgeLimit, minScale,
upscale_?
"true":
"false",
w,
h);
1373 if(maxKeypoints == 0 || maxKeypoints >
cudaSiftData_->numPts)
1380 std::multimap<float, int> hessianMap;
1398 hessianMap.insert(std::pair<float, int>(
cudaSiftData_->h_data[
i].sharpness,
i));
1401 if((
int)hessianMap.size() < maxKeypoints)
1403 maxKeypoints = hessianMap.size();
1406 std::multimap<float, int>::reverse_iterator
iter = hessianMap.rbegin();
1407 keypoints.resize(maxKeypoints);
1409 for(
unsigned int k=0; k<keypoints.size() &&
iter!=hessianMap.rend(); ++k, ++
iter)
1411 int i =
iter->second;
1426 #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)))
1427 #ifdef RTABMAP_NONFREE
1428 sift_->detect(imgRoi, keypoints, maskRoi);
1430 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1432 #else // >=4.4, >=3.4.11
1433 sift_->detect(imgRoi, keypoints, maskRoi);
1441 #ifdef RTABMAP_CUDASIFT
1450 UERROR(
"CudaSift: keypoints size %ld is not equal to extracted descriptors size %d", keypoints.size(),
cudaSiftDescriptors_.rows);
1456 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1457 cv::Mat descriptors;
1458 #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)))
1459 #ifdef RTABMAP_NONFREE
1460 sift_->compute(image, keypoints, descriptors);
1462 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1464 #else // >=4.4, >=3.4.11
1465 sift_->compute(image, keypoints, descriptors);
1469 UDEBUG(
"Performing RootSIFT...");
1473 for(
int i=0;
i<descriptors.rows; ++
i)
1478 descriptors.row(
i) = descriptors.row(
i) / cv::sum(descriptors.row(
i))[0];
1479 cv::sqrt(descriptors.row(
i), descriptors.row(
i));
1489 scaleFactor_(
Parameters::defaultORBScaleFactor()),
1491 edgeThreshold_(
Parameters::defaultORBEdgeThreshold()),
1492 firstLevel_(
Parameters::defaultORBFirstLevel()),
1494 scoreType_(
Parameters::defaultORBScoreType()),
1495 patchSize_(
Parameters::defaultORBPatchSize()),
1497 fastThreshold_(
Parameters::defaultFASTThreshold()),
1498 nonmaxSuppresion_(
Parameters::defaultFASTNonmaxSuppression())
1523 #if CV_MAJOR_VERSION < 3
1524 #ifdef HAVE_OPENCV_GPU
1525 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1527 UWARN(
"GPU version of ORB not available! Using CPU version instead...");
1533 UWARN(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1538 #ifndef HAVE_OPENCV_CUDAFEATURES2D
1541 UWARN(
"GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1545 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1547 UWARN(
"GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1553 #if CV_MAJOR_VERSION < 3
1554 #ifdef HAVE_OPENCV_GPU
1558 UFATAL(
"not supposed to be here");
1561 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1568 #if CV_MAJOR_VERSION < 3
1570 #elif CV_MAJOR_VERSION > 3
1580 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1581 std::vector<cv::KeyPoint> keypoints;
1582 cv::Mat imgRoi(image, roi);
1586 maskRoi = cv::Mat(
mask, roi);
1591 #if CV_MAJOR_VERSION < 3
1592 #ifdef HAVE_OPENCV_GPU
1593 cv::gpu::GpuMat imgGpu(imgRoi);
1594 cv::gpu::GpuMat maskGpu(maskRoi);
1595 (*
_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1597 UERROR(
"Cannot use ORBGPU because OpenCV is not built with gpu module.");
1600 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1601 cv::cuda::GpuMat d_image(imgRoi);
1602 cv::cuda::GpuMat d_mask(maskRoi);
1604 _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(),
false);
1605 }
catch (cv::Exception&
e) {
1606 const char* err_msg =
e.what();
1607 UWARN(
"OpenCV exception caught: %s", err_msg);
1614 _orb->detect(imgRoi, keypoints, maskRoi);
1622 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1623 cv::Mat descriptors;
1631 #if CV_MAJOR_VERSION < 3
1632 #ifdef HAVE_OPENCV_GPU
1633 cv::gpu::GpuMat imgGpu(image);
1634 cv::gpu::GpuMat descriptorsGPU;
1635 (*
_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1637 if (descriptorsGPU.empty())
1638 descriptors = cv::Mat();
1641 UASSERT(descriptorsGPU.type() == CV_32F);
1642 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1643 descriptorsGPU.download(descriptors);
1646 UERROR(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1649 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1650 cv::cuda::GpuMat d_image(image);
1651 cv::cuda::GpuMat d_descriptors;
1653 _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors,
true);
1654 }
catch (cv::Exception&
e) {
1655 const char* err_msg =
e.what();
1656 UWARN(
"OpenCV exception caught: %s", err_msg);
1659 if (d_descriptors.empty())
1660 descriptors = cv::Mat();
1663 UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1664 d_descriptors.download(descriptors);
1671 _orb->compute(image, keypoints, descriptors);
1682 nonmaxSuppression_(
Parameters::defaultFASTNonmaxSuppression()),
1684 gpuKeypointsRatio_(
Parameters::defaultFASTGpuKeypointsRatio()),
1685 minThreshold_(
Parameters::defaultFASTMinThreshold()),
1686 maxThreshold_(
Parameters::defaultFASTMaxThreshold()),
1687 gridRows_(
Parameters::defaultFASTGridRows()),
1688 gridCols_(
Parameters::defaultFASTGridCols()),
1691 fastCVMaxFeatures_(10000),
1692 fastCVLastImageHeight_(0)
1694 #ifdef RTABMAP_FASTCV
1695 char sVersion[128] = { 0 };
1696 fcvGetVersion(sVersion, 128);
1697 UINFO(
"fastcv version = %s", sVersion);
1699 if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1701 UERROR(
"fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1711 UERROR(
"could not alloc fastcv mem, using opencv fast instead!");
1735 #ifdef RTABMAP_FASTCV
1770 #if CV_MAJOR_VERSION < 3
1771 #ifdef HAVE_OPENCV_GPU
1772 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1774 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1780 UWARN(
"GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1785 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1786 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1788 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1794 UWARN(
"GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1801 #if CV_MAJOR_VERSION < 3
1802 #ifdef HAVE_OPENCV_GPU
1805 UFATAL(
"not supposed to be here!");
1808 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1809 UFATAL(
"not implemented");
1815 #if CV_MAJOR_VERSION < 3
1826 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1831 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1844 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1845 std::vector<cv::KeyPoint> keypoints;
1847 #ifdef RTABMAP_FASTCV
1865 UERROR(
"could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().
c_str());
1877 fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0,
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1881 fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(),
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1883 UDEBUG(
"number of corners found = %d:", nCorners);
1884 keypoints.resize(nCorners);
1889 keypoints[
i].size = 3;
1903 UWARN(
"RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. "
1904 "Please set %s to 0. This message will only appear once.",
1905 Parameters::kFASTCV().
c_str());
1909 cv::Mat imgRoi(image, roi);
1913 maskRoi = cv::Mat(
mask, roi);
1917 #if CV_MAJOR_VERSION < 3
1918 #ifdef HAVE_OPENCV_GPU
1919 cv::gpu::GpuMat imgGpu(imgRoi);
1920 cv::gpu::GpuMat maskGpu(maskRoi);
1921 (*
_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1923 UERROR(
"Cannot use FAST GPU because OpenCV is not built with gpu module.");
1926 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1927 UFATAL(
"not implemented");
1933 _fast->detect(imgRoi, keypoints, maskRoi);
1957 #if CV_MAJOR_VERSION < 3
1960 #ifdef HAVE_OPENCV_XFEATURES2D
1963 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1970 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1971 cv::Mat descriptors;
1972 #if CV_MAJOR_VERSION < 3
1973 _brief->compute(image, keypoints, descriptors);
1975 #ifdef HAVE_OPENCV_XFEATURES2D
1976 _brief->compute(image, keypoints, descriptors);
1978 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1989 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1990 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1991 patternScale_(
Parameters::defaultFREAKPatternScale()),
1992 nOctaves_(
Parameters::defaultFREAKNOctaves())
2010 #if CV_MAJOR_VERSION < 3
2013 #ifdef HAVE_OPENCV_XFEATURES2D
2016 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2023 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2024 cv::Mat descriptors;
2025 #if CV_MAJOR_VERSION < 3
2026 _freak->compute(image, keypoints, descriptors);
2028 #ifdef HAVE_OPENCV_XFEATURES2D
2029 _freak->compute(image, keypoints, descriptors);
2031 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2041 _qualityLevel(
Parameters::defaultGFTTQualityLevel()),
2042 _minDistance(
Parameters::defaultGFTTMinDistance()),
2043 _blockSize(
Parameters::defaultGFTTBlockSize()),
2044 _useHarrisDetector(
Parameters::defaultGFTTUseHarrisDetector()),
2066 #if CV_MAJOR_VERSION < 3
2069 UWARN(
"GPU version of GFTT is not implemented for OpenCV<3! Using CPU version instead...");
2074 #ifdef HAVE_OPENCV_CUDAIMGPROC
2075 if(
_gpu && cv::cuda::getCudaEnabledDeviceCount() == 0)
2077 UWARN(
"GPU version of GFTT not available! Using CPU version instead...");
2083 UWARN(
"GPU version of GFTT not available (OpenCV cudaimageproc module)! Using CPU version instead...");
2089 #ifdef HAVE_OPENCV_CUDAIMGPROC
2092 UFATAL(
"not supposed to be here!");
2097 #if CV_MAJOR_VERSION < 3
2107 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2108 std::vector<cv::KeyPoint> keypoints;
2109 cv::Mat imgRoi(image, roi);
2113 maskRoi = cv::Mat(
mask, roi);
2116 #if CV_MAJOR_VERSION >= 3 && defined(HAVE_OPENCV_CUDAIMGPROC)
2119 cv::cuda::GpuMat imgGpu(imgRoi);
2120 cv::cuda::GpuMat maskGpu(maskRoi);
2121 cv::cuda::GpuMat cornersGpu;
2122 _gpuGftt->detect(imgGpu, cornersGpu, maskGpu);
2123 std::vector<cv::Point2f>
corners(cornersGpu.cols);
2124 cv::Mat cornersMat(1, cornersGpu.cols, CV_32FC2, (
void*)&
corners[0]);
2125 cornersGpu.download(cornersMat);
2131 _gftt->detect(imgRoi, keypoints, maskRoi);
2156 #if CV_MAJOR_VERSION < 3
2159 #ifdef HAVE_OPENCV_XFEATURES2D
2162 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2169 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2170 cv::Mat descriptors;
2171 #if CV_MAJOR_VERSION < 3
2172 _brief->compute(image, keypoints, descriptors);
2174 #ifdef HAVE_OPENCV_XFEATURES2D
2175 _brief->compute(image, keypoints, descriptors);
2177 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2188 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2189 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2190 patternScale_(
Parameters::defaultFREAKPatternScale()),
2191 nOctaves_(
Parameters::defaultFREAKNOctaves())
2209 #if CV_MAJOR_VERSION < 3
2212 #ifdef HAVE_OPENCV_XFEATURES2D
2215 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2222 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2223 cv::Mat descriptors;
2224 #if CV_MAJOR_VERSION < 3
2225 _freak->compute(image, keypoints, descriptors);
2227 #ifdef HAVE_OPENCV_XFEATURES2D
2228 _freak->compute(image, keypoints, descriptors);
2230 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2241 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2242 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2243 patternScale_(
Parameters::defaultFREAKPatternScale()),
2244 nOctaves_(
Parameters::defaultFREAKNOctaves())
2262 #if CV_MAJOR_VERSION < 3
2265 #ifdef HAVE_OPENCV_XFEATURES2D
2268 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2275 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2276 cv::Mat descriptors;
2277 #if CV_MAJOR_VERSION < 3
2278 _freak->compute(image, keypoints, descriptors);
2280 #ifdef HAVE_OPENCV_XFEATURES2D
2281 _freak->compute(image, keypoints, descriptors);
2283 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2311 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2321 patternScale_(
Parameters::defaultBRISKPatternScale())
2338 #if CV_MAJOR_VERSION < 3
2347 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2348 std::vector<cv::KeyPoint> keypoints;
2349 cv::Mat imgRoi(image, roi);
2353 maskRoi = cv::Mat(
mask, roi);
2355 brisk_->detect(imgRoi, keypoints, maskRoi);
2361 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2362 cv::Mat descriptors;
2363 brisk_->compute(image, keypoints, descriptors);
2371 extended_(
Parameters::defaultKAZEExtended()),
2374 nOctaves_(
Parameters::defaultKAZENOctaves()),
2375 nOctaveLayers_(
Parameters::defaultKAZENOctaveLayers()),
2376 diffusivity_(
Parameters::defaultKAZEDiffusivity())
2396 #if CV_MAJOR_VERSION > 3
2398 #elif CV_MAJOR_VERSION > 2
2401 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2407 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2408 std::vector<cv::KeyPoint> keypoints;
2409 #if CV_MAJOR_VERSION > 2
2410 cv::Mat imgRoi(image, roi);
2414 maskRoi = cv::Mat(
mask, roi);
2416 kaze_->detect(imgRoi, keypoints, maskRoi);
2418 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2425 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2426 cv::Mat descriptors;
2427 #if CV_MAJOR_VERSION > 2
2428 kaze_->compute(image, keypoints, descriptors);
2430 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2439 scaleFactor_(
Parameters::defaultORBScaleFactor()),
2441 patchSize_(
Parameters::defaultORBPatchSize()),
2442 edgeThreshold_(
Parameters::defaultORBEdgeThreshold()),
2443 fastThreshold_(
Parameters::defaultFASTThreshold()),
2444 fastMinThreshold_(
Parameters::defaultFASTMinThreshold())
2465 #ifdef RTABMAP_ORB_OCTREE
2468 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2474 std::vector<cv::KeyPoint> keypoints;
2476 #ifdef RTABMAP_ORB_OCTREE
2477 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2478 cv::Mat imgRoi(image, roi);
2482 maskRoi = cv::Mat(
mask, roi);
2488 if(!keypoints.empty() && !maskRoi.empty())
2490 std::vector<cv::KeyPoint> validKeypoints;
2491 validKeypoints.reserve(keypoints.size());
2492 cv::Mat validDescriptors;
2493 for(
size_t i=0;
i<keypoints.size(); ++
i)
2495 if(maskRoi.at<
unsigned char>(keypoints[
i].pt.y+roi.y, keypoints[
i].pt.x+roi.x) != 0)
2497 validKeypoints.push_back(keypoints[
i]);
2501 keypoints = validKeypoints;
2510 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2517 #ifdef RTABMAP_ORB_OCTREE
2520 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2529 path_(
Parameters::defaultSuperPointModelPath()),
2532 minDistance_(
Parameters::defaultSuperPointNMSRadius()),
2546 std::string previousPath =
path_;
2547 #ifdef RTABMAP_TORCH
2548 bool previousCuda =
cuda_;
2556 #ifdef RTABMAP_TORCH
2568 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2574 #ifdef RTABMAP_TORCH
2575 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2576 if(roi.x!=0 || roi.y !=0)
2578 UERROR(
"SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2579 roi.x, roi.y, roi.width, roi.height,
2580 Parameters::kKpRoiRatios().c_str(),
2581 Parameters::kVisRoiRatios().c_str(),
2582 Parameters::kVisGridRows().c_str(),
2583 Parameters::kVisGridCols().c_str(),
2584 Parameters::kKpGridRows().c_str(),
2585 Parameters::kKpGridCols().c_str());
2586 return std::vector<cv::KeyPoint>();
2590 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2591 return std::vector<cv::KeyPoint>();
2597 #ifdef RTABMAP_TORCH
2598 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2601 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2612 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2613 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2614 patternScale_(
Parameters::defaultFREAKPatternScale()),
2615 nOctaves_(
Parameters::defaultFREAKNOctaves())
2633 #ifdef HAVE_OPENCV_XFEATURES2D
2634 _daisy = CV_DAISY::create();
2636 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2642 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2643 cv::Mat descriptors;
2644 #ifdef HAVE_OPENCV_XFEATURES2D
2645 _daisy->compute(image, keypoints, descriptors);
2647 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2657 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2658 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2659 patternScale_(
Parameters::defaultFREAKPatternScale()),
2660 nOctaves_(
Parameters::defaultFREAKNOctaves())
2678 #ifdef HAVE_OPENCV_XFEATURES2D
2679 _daisy = CV_DAISY::create();
2681 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2687 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2688 cv::Mat descriptors;
2689 #ifdef HAVE_OPENCV_XFEATURES2D
2690 _daisy->compute(image, keypoints, descriptors);
2692 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");