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);
231 if(d!=0.0
f &&
uIsFinite(d) && d >= minDisparity)
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;
279 std::vector<cv::Point3f> keypoints3D;
280 limitKeypoints(keypoints, keypoints3D, descriptors, maxKeypoints);
283 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors,
int maxKeypoints)
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)
290 ULOGGER_DEBUG(
"too much words (%d), removing words with the hessian threshold", keypoints.size());
294 std::multimap<float, int> hessianMap;
295 for(
unsigned int i = 0; i <keypoints.size(); ++i)
298 hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
302 int removed = (int)hessianMap.size()-maxKeypoints;
303 std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
304 std::vector<cv::KeyPoint> kptsTmp(maxKeypoints);
305 std::vector<cv::Point3f> kpts3DTmp;
306 if(!keypoints3D.empty())
308 kpts3DTmp.resize(maxKeypoints);
310 cv::Mat descriptorsTmp;
313 descriptorsTmp = cv::Mat(maxKeypoints, descriptors.cols, descriptors.type());
315 for(
unsigned int k=0; k < kptsTmp.size() && iter!=hessianMap.rend(); ++k, ++iter)
317 kptsTmp[k] = keypoints[iter->second];
318 if(keypoints3D.size())
320 kpts3DTmp[k] = keypoints3D[iter->second];
324 if(descriptors.type() == CV_32FC1)
326 memcpy(descriptorsTmp.ptr<
float>(k), descriptors.ptr<
float>(iter->second), descriptors.cols*
sizeof(
float));
330 memcpy(descriptorsTmp.ptr<
char>(k), descriptors.ptr<
char>(iter->second), descriptors.cols*
sizeof(
char));
334 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, (
int)kptsTmp.size(), kptsTmp.size()?kptsTmp.back().response:0.0f);
337 keypoints3D = kpts3DTmp;
340 descriptors = descriptorsTmp;
347 if(maxKeypoints > 0 && (
int)keypoints.size() > maxKeypoints)
350 ULOGGER_DEBUG(
"too much words (%d), removing words with the hessian threshold", (
int)keypoints.size());
354 std::multimap<float, int> hessianMap;
355 for(
unsigned int i = 0; i <keypoints.size(); ++i)
358 hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
362 int removed = (int)hessianMap.size()-maxKeypoints;
363 std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
364 inliers.resize(keypoints.size(),
false);
365 float minimumHessian = 0.0f;
366 for(
int k=0; k < maxKeypoints && iter!=hessianMap.rend(); ++k, ++iter)
368 inliers[iter->second] =
true;
369 minimumHessian = iter->first;
371 ULOGGER_DEBUG(
"%d keypoints removed, (kept %d), minimum response=%f", removed, maxKeypoints, minimumHessian);
376 ULOGGER_DEBUG(
"keeping all %d keypoints", (
int)keypoints.size());
377 inliers.resize(keypoints.size(),
true);
381 void Feature2D::limitKeypoints(
const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers,
int maxKeypoints,
const cv::Size & imageSize,
int gridRows,
int gridCols)
383 if(maxKeypoints <= 0 || (
int)keypoints.size() <= maxKeypoints)
385 inliers.resize(keypoints.size(),
true);
388 UASSERT(gridCols>=1 && gridRows >=1);
389 UASSERT(imageSize.height>gridRows && imageSize.width>gridCols);
390 int rowSize = imageSize.height / gridRows;
391 int colSize = imageSize.width / gridCols;
392 int maxKeypointsPerCell = maxKeypoints / (gridRows * gridCols);
393 std::vector<std::vector<cv::KeyPoint> > keypointsPerCell(gridRows * gridCols);
394 std::vector<std::vector<int> > indexesPerCell(gridRows * gridCols);
395 for(
size_t i=0; i<keypoints.size(); ++i)
397 int cellRow = int(keypoints[i].pt.y)/rowSize;
398 int cellCol = int(keypoints[i].pt.x)/colSize;
399 UASSERT(cellRow >=0 && cellRow < gridRows);
400 UASSERT(cellCol >=0 && cellCol < gridCols);
402 keypointsPerCell[cellRow*gridCols + cellCol].push_back(keypoints[i]);
403 indexesPerCell[cellRow*gridCols + cellCol].push_back(i);
405 inliers.resize(keypoints.size(),
false);
406 for(
size_t i=0; i<keypointsPerCell.size(); ++i)
408 std::vector<bool> inliersCell;
409 limitKeypoints(keypointsPerCell[i], inliersCell, maxKeypointsPerCell);
410 for(
size_t j=0; j<inliersCell.size(); ++j)
414 inliers.at(indexesPerCell[i][j]) =
true;
467 ParametersMap::const_iterator iter;
468 if((iter=parameters.find(Parameters::kKpRoiRatios())) != parameters.end())
470 std::list<std::string> strValues =
uSplit(iter->second,
' ');
471 if(strValues.size() != 4)
473 ULOGGER_ERROR(
"The number of values must be 4 (roi=\"%s\")", iter->second.c_str());
477 std::vector<float> tmpValues(4);
479 for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
485 if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0
f-tmpValues[1] &&
486 tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0
f-tmpValues[0] &&
487 tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0
f-tmpValues[3] &&
488 tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0
f-tmpValues[2])
494 ULOGGER_ERROR(
"The roi ratios are not valid (roi=\"%s\")", iter->second.c_str());
501 if((iter=parameters.find(Parameters::kStereoOpticalFlow())) != parameters.end())
513 int type = Parameters::defaultKpDetectorStrategy();
521 #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))) 523 #ifndef RTABMAP_NONFREE 526 #if CV_MAJOR_VERSION < 3 527 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
529 UWARN(
"SURF and SIFT features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
535 #else // >= 4.4.0 >= 3.4.11 537 #ifndef RTABMAP_NONFREE 540 UWARN(
"SURF features cannot be used because OpenCV was not built with nonfree module. SIFT is used instead.");
545 UWARN(
"SURF detector cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
550 #endif // >= 4.4.0 >= 3.4.11 552 #if !defined(HAVE_OPENCV_XFEATURES2D) && CV_MAJOR_VERSION >= 3 561 UWARN(
"BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
564 #elif CV_MAJOR_VERSION < 3 567 #ifdef RTABMAP_NONFREE 568 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. SURF is used instead.");
571 UWARN(
"KAZE detector/descriptor can be used only with OpenCV3. GFTT/ORB is used instead.");
577 UWARN(
"DAISY detector/descriptor can be used only with OpenCV3. GFTT/BRIEF is used instead.");
583 #ifndef RTABMAP_ORB_OCTREE 586 UWARN(
"ORB OcTree feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
591 #ifndef RTABMAP_TORCH 594 UWARN(
"SupertPoint Torch feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
603 feature2D =
new SURF(parameters);
606 feature2D =
new SIFT(parameters);
609 feature2D =
new ORB(parameters);
624 feature2D =
new GFTT_ORB(parameters);
627 feature2D =
new BRISK(parameters);
630 feature2D =
new KAZE(parameters);
649 #ifdef RTABMAP_PYTHON 654 #ifdef RTABMAP_NONFREE 656 feature2D =
new SURF(parameters);
661 feature2D =
new ORB(parameters);
673 UASSERT(image.type() == CV_8UC1);
678 if(maskIn.type()==CV_16UC1 || maskIn.type() == CV_32FC1)
680 mask = cv::Mat::zeros(maskIn.rows, maskIn.cols, CV_8UC1);
681 for(
int i=0; i<(int)mask.total(); ++i)
684 if(maskIn.type()==CV_16UC1)
686 if(((
unsigned short*)maskIn.data)[i] > 0 &&
689 value = float(((
unsigned short*)maskIn.data)[i])*0.001f;
694 value = ((
float*)maskIn.data)[i];
701 ((
unsigned char*)mask.data)[i] = 255;
705 else if(maskIn.type()==CV_8UC1)
712 UERROR(
"Wrong mask type (%d)! Should be 8UC1, 16UC1 or 32FC1.", maskIn.type());
716 UASSERT(mask.empty() || (mask.cols == image.cols && mask.rows == image.rows));
718 std::vector<cv::KeyPoint> keypoints;
721 if(!(globalRoi.width && globalRoi.height))
723 globalRoi = cv::Rect(0,0,image.cols, image.rows);
727 int rowSize = globalRoi.height /
gridRows_;
728 int colSize = globalRoi.width /
gridCols_;
734 cv::Rect roi(globalRoi.x + j*colSize, globalRoi.y + i*rowSize, colSize, rowSize);
735 std::vector<cv::KeyPoint> sub_keypoints;
741 for(std::vector<cv::KeyPoint>::iterator iter=sub_keypoints.begin(); iter!=sub_keypoints.end(); ++iter)
747 keypoints.insert( keypoints.end(), sub_keypoints.begin(), sub_keypoints.end() );
750 UDEBUG(
"Keypoints extraction time = %f s, keypoints extracted = %d (grid=%dx%d, mask empty=%d)",
755 std::vector<cv::Point2f> corners;
756 cv::KeyPoint::convert(keypoints, corners);
757 cv::cornerSubPix( image, corners,
762 for(
unsigned int i=0;i<corners.size(); ++i)
764 keypoints[i].pt = corners[i];
773 const cv::Mat & image,
774 std::vector<cv::KeyPoint> & keypoints)
const 780 UASSERT(image.type() == CV_8UC1);
782 UASSERT_MSG(descriptors.rows == (
int)keypoints.size(),
uFormat(
"descriptors=%d, keypoints=%d", descriptors.rows, (
int)keypoints.size()).c_str());
783 UDEBUG(
"Descriptors extracted = %d, remaining kpts=%d", descriptors.rows, (
int)keypoints.size());
790 const std::vector<cv::KeyPoint> & keypoints)
const 792 std::vector<cv::Point3f> keypoints3D;
804 cv::cvtColor(data.
imageRaw(), imageMono, cv::COLOR_BGR2GRAY);
811 std::vector<cv::Point2f> leftCorners;
812 cv::KeyPoint::convert(keypoints, leftCorners);
814 std::vector<cv::Point2f> rightCorners;
818 std::vector<unsigned char> status;
828 for(
size_t i=0; i<status.size(); ++i)
835 if(rejected > (
int)status.size()/2)
837 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! " 838 "Optical flow may have failed because images are not calibrated, " 839 "the background is too far (no disparity between the images), " 840 "maximum disparity may be too small (%f) or that exposure between " 841 "left and right images is too different.",
859 UASSERT(imageMono.cols % subImageWith == 0);
860 std::vector<std::vector<cv::Point2f> > subLeftCorners(data.
stereoCameraModels().size());
863 for(
size_t i=0; i<leftCorners.size(); ++i)
865 int cameraIndex = int(leftCorners[i].
x / subImageWith);
866 leftCorners[i].x -= cameraIndex*subImageWith;
867 subLeftCorners[cameraIndex].push_back(leftCorners[i]);
868 subIndex[cameraIndex].push_back(i);
871 keypoints3D.resize(keypoints.size());
876 if(!subLeftCorners[i].empty())
878 std::vector<unsigned char> status;
880 imageMono.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
881 data.
rightRaw().colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
895 for(
size_t i=0; i<status.size(); ++i)
902 total+=status.size();
905 UASSERT(subIndex[i].size() == subKeypoints3D.size());
906 for(
size_t j=0; j<subKeypoints3D.size(); ++j)
908 keypoints3D[subIndex[i][j]] = subKeypoints3D[j];
915 if(rejected > total/2)
917 UWARN(
"A large number (%d/%d) of stereo correspondences are rejected! " 918 "Optical flow may have failed because images are not calibrated, " 919 "the background is too far (no disparity between the images), " 920 "maximum disparity may be too small (%f) or that exposure between " 921 "left and right images is too different.",
947 hessianThreshold_(
Parameters::defaultSURFHessianThreshold()),
949 nOctaveLayers_(
Parameters::defaultSURFOctaveLayers()),
952 gpuKeypointsRatio_(
Parameters::defaultSURFGpuKeypointsRatio()),
953 gpuVersion_(
Parameters::defaultSURFGpuVersion())
974 #ifdef RTABMAP_NONFREE 975 #if CV_MAJOR_VERSION < 3 976 if(
gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
978 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
982 if(
gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
984 UWARN(
"GPU version of SURF not available! Using CPU version instead...");
994 #if CV_MAJOR_VERSION < 3 1001 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1007 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1008 std::vector<cv::KeyPoint> keypoints;
1010 #ifdef RTABMAP_NONFREE 1011 cv::Mat imgRoi(image, roi);
1015 maskRoi = cv::Mat(mask, roi);
1019 #if CV_MAJOR_VERSION < 3 1020 cv::gpu::GpuMat imgGpu(imgRoi);
1021 cv::gpu::GpuMat maskGpu(maskRoi);
1022 (*
_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1024 cv::cuda::GpuMat imgGpu(imgRoi);
1025 cv::cuda::GpuMat maskGpu(maskRoi);
1026 (*
_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1031 _surf->detect(imgRoi, keypoints, maskRoi);
1034 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1041 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1042 cv::Mat descriptors;
1043 #ifdef RTABMAP_NONFREE 1046 #if CV_MAJOR_VERSION < 3 1047 cv::gpu::GpuMat imgGpu(image);
1048 cv::gpu::GpuMat descriptorsGPU;
1049 (*
_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU,
true);
1051 cv::cuda::GpuMat imgGpu(image);
1052 cv::cuda::GpuMat descriptorsGPU;
1053 (*
_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU,
true);
1057 if (descriptorsGPU.empty())
1058 descriptors = cv::Mat();
1061 UASSERT(descriptorsGPU.type() == CV_32F);
1062 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1063 descriptorsGPU.download(descriptors);
1068 _surf->compute(image, keypoints, descriptors);
1071 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1082 contrastThreshold_(
Parameters::defaultSIFTContrastThreshold()),
1083 edgeThreshold_(
Parameters::defaultSIFTEdgeThreshold()),
1104 #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))) 1105 #ifdef RTABMAP_NONFREE 1106 #if CV_MAJOR_VERSION < 3 1112 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1114 #else // >=4.4, >=3.4.11 1121 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1122 std::vector<cv::KeyPoint> keypoints;
1123 cv::Mat imgRoi(image, roi);
1127 maskRoi = cv::Mat(mask, roi);
1129 #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))) 1130 #ifdef RTABMAP_NONFREE 1131 _sift->detect(imgRoi, keypoints, maskRoi);
1133 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1135 #else // >=4.4, >=3.4.11 1136 _sift->detect(imgRoi, keypoints, maskRoi);
1143 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1144 cv::Mat descriptors;
1145 #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))) 1146 #ifdef RTABMAP_NONFREE 1147 _sift->compute(image, keypoints, descriptors);
1149 UWARN(
"RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1151 #else // >=4.4, >=3.4.11 1152 _sift->compute(image, keypoints, descriptors);
1156 UDEBUG(
"Performing RootSIFT...");
1160 for(
int i=0; i<descriptors.rows; ++i)
1165 descriptors.row(i) = descriptors.row(i) / cv::sum(descriptors.row(i))[0];
1166 cv::sqrt(descriptors.row(i), descriptors.row(i));
1176 scaleFactor_(
Parameters::defaultORBScaleFactor()),
1179 firstLevel_(
Parameters::defaultORBFirstLevel()),
1181 scoreType_(
Parameters::defaultORBScoreType()),
1182 patchSize_(
Parameters::defaultORBPatchSize()),
1184 fastThreshold_(
Parameters::defaultFASTThreshold()),
1185 nonmaxSuppresion_(
Parameters::defaultFASTNonmaxSuppression())
1210 #if CV_MAJOR_VERSION < 3 1211 #ifdef HAVE_OPENCV_GPU 1212 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1214 UWARN(
"GPU version of ORB not available! Using CPU version instead...");
1220 UWARN(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1225 #ifndef HAVE_OPENCV_CUDAFEATURES2D 1228 UWARN(
"GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1232 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1234 UWARN(
"GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1240 #if CV_MAJOR_VERSION < 3 1241 #ifdef HAVE_OPENCV_GPU 1245 UFATAL(
"not supposed to be here");
1248 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1255 #if CV_MAJOR_VERSION < 3 1257 #elif CV_MAJOR_VERSION > 3 1267 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1268 std::vector<cv::KeyPoint> keypoints;
1269 cv::Mat imgRoi(image, roi);
1273 maskRoi = cv::Mat(mask, roi);
1278 #if CV_MAJOR_VERSION < 3 1279 #ifdef HAVE_OPENCV_GPU 1280 cv::gpu::GpuMat imgGpu(imgRoi);
1281 cv::gpu::GpuMat maskGpu(maskRoi);
1282 (*
_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1284 UERROR(
"Cannot use ORBGPU because OpenCV is not built with gpu module.");
1287 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1288 cv::cuda::GpuMat d_image(imgRoi);
1289 cv::cuda::GpuMat d_mask(maskRoi);
1291 _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(),
false);
1292 }
catch (cv::Exception&
e) {
1293 const char* err_msg = e.what();
1294 UWARN(
"OpenCV exception caught: %s", err_msg);
1301 _orb->detect(imgRoi, keypoints, maskRoi);
1309 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1310 cv::Mat descriptors;
1318 #if CV_MAJOR_VERSION < 3 1319 #ifdef HAVE_OPENCV_GPU 1320 cv::gpu::GpuMat imgGpu(image);
1321 cv::gpu::GpuMat descriptorsGPU;
1322 (*
_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1324 if (descriptorsGPU.empty())
1325 descriptors = cv::Mat();
1328 UASSERT(descriptorsGPU.type() == CV_32F);
1329 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1330 descriptorsGPU.download(descriptors);
1333 UERROR(
"GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1336 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1337 cv::cuda::GpuMat d_image(image);
1338 cv::cuda::GpuMat d_descriptors;
1340 _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors,
true);
1341 }
catch (cv::Exception&
e) {
1342 const char* err_msg = e.what();
1343 UWARN(
"OpenCV exception caught: %s", err_msg);
1346 if (d_descriptors.empty())
1347 descriptors = cv::Mat();
1350 UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1351 d_descriptors.download(descriptors);
1358 _orb->compute(image, keypoints, descriptors);
1368 threshold_(
Parameters::defaultFASTThreshold()),
1369 nonmaxSuppression_(
Parameters::defaultFASTNonmaxSuppression()),
1371 gpuKeypointsRatio_(
Parameters::defaultFASTGpuKeypointsRatio()),
1372 minThreshold_(
Parameters::defaultFASTMinThreshold()),
1373 maxThreshold_(
Parameters::defaultFASTMaxThreshold()),
1378 fastCVMaxFeatures_(10000),
1379 fastCVLastImageHeight_(0)
1381 #ifdef RTABMAP_FASTCV 1382 char sVersion[128] = { 0 };
1383 fcvGetVersion(sVersion, 128);
1384 UINFO(
"fastcv version = %s", sVersion);
1386 if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1388 UERROR(
"fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1398 UERROR(
"could not alloc fastcv mem, using opencv fast instead!");
1422 #ifdef RTABMAP_FASTCV 1457 #if CV_MAJOR_VERSION < 3 1458 #ifdef HAVE_OPENCV_GPU 1459 if(
gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1461 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1467 UWARN(
"GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1472 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1473 if(
gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1475 UWARN(
"GPU version of FAST not available! Using CPU version instead...");
1481 UWARN(
"GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1488 #if CV_MAJOR_VERSION < 3 1489 #ifdef HAVE_OPENCV_GPU 1492 UFATAL(
"not supposed to be here!");
1495 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1496 UFATAL(
"not implemented");
1502 #if CV_MAJOR_VERSION < 3 1513 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1514 Parameters::kFASTGridRows().c_str(),
gridRows_, Parameters::kFASTGridCols().c_str());
1518 UWARN(
"Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1519 Parameters::kFASTGridCols().c_str(),
gridCols_, Parameters::kFASTGridRows().c_str());
1531 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1532 std::vector<cv::KeyPoint> keypoints;
1534 #ifdef RTABMAP_FASTCV 1552 UERROR(
"could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().c_str());
1564 fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0,
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1568 fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(),
threshold_, 0,
fastCVCorners_,
fastCVCornerScores_,
fastCVMaxFeatures_, &nCorners,
nonmaxSuppression_?1:0,
fastCVTempBuf_);
1570 UDEBUG(
"number of corners found = %d:", nCorners);
1571 keypoints.resize(nCorners);
1572 for (
uint32_t i = 0; i < nCorners; i++)
1576 keypoints[i].size = 3;
1590 UWARN(
"RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. " 1591 "Please set %s to 0. This message will only appear once.",
1592 Parameters::kFASTCV().c_str());
1596 cv::Mat imgRoi(image, roi);
1600 maskRoi = cv::Mat(mask, roi);
1604 #if CV_MAJOR_VERSION < 3 1605 #ifdef HAVE_OPENCV_GPU 1606 cv::gpu::GpuMat imgGpu(imgRoi);
1607 cv::gpu::GpuMat maskGpu(maskRoi);
1608 (*
_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1610 UERROR(
"Cannot use FAST GPU because OpenCV is not built with gpu module.");
1613 #ifdef HAVE_OPENCV_CUDAFEATURES2D 1614 UFATAL(
"not implemented");
1620 _fast->detect(imgRoi, keypoints, maskRoi);
1644 #if CV_MAJOR_VERSION < 3 1647 #ifdef HAVE_OPENCV_XFEATURES2D 1650 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1657 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1658 cv::Mat descriptors;
1659 #if CV_MAJOR_VERSION < 3 1660 _brief->compute(image, keypoints, descriptors);
1662 #ifdef HAVE_OPENCV_XFEATURES2D 1663 _brief->compute(image, keypoints, descriptors);
1665 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1676 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1677 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1678 patternScale_(
Parameters::defaultFREAKPatternScale()),
1679 nOctaves_(
Parameters::defaultFREAKNOctaves())
1697 #if CV_MAJOR_VERSION < 3 1700 #ifdef HAVE_OPENCV_XFEATURES2D 1703 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1710 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1711 cv::Mat descriptors;
1712 #if CV_MAJOR_VERSION < 3 1713 _freak->compute(image, keypoints, descriptors);
1715 #ifdef HAVE_OPENCV_XFEATURES2D 1716 _freak->compute(image, keypoints, descriptors);
1718 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1728 _qualityLevel(
Parameters::defaultGFTTQualityLevel()),
1729 _minDistance(
Parameters::defaultGFTTMinDistance()),
1730 _blockSize(
Parameters::defaultGFTTBlockSize()),
1731 _useHarrisDetector(
Parameters::defaultGFTTUseHarrisDetector()),
1751 #if CV_MAJOR_VERSION < 3 1760 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1761 std::vector<cv::KeyPoint> keypoints;
1762 cv::Mat imgRoi(image, roi);
1766 maskRoi = cv::Mat(mask, roi);
1768 _gftt->detect(imgRoi, keypoints, maskRoi);
1791 #if CV_MAJOR_VERSION < 3 1794 #ifdef HAVE_OPENCV_XFEATURES2D 1797 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1804 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1805 cv::Mat descriptors;
1806 #if CV_MAJOR_VERSION < 3 1807 _brief->compute(image, keypoints, descriptors);
1809 #ifdef HAVE_OPENCV_XFEATURES2D 1810 _brief->compute(image, keypoints, descriptors);
1812 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1823 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
1824 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
1825 patternScale_(
Parameters::defaultFREAKPatternScale()),
1826 nOctaves_(
Parameters::defaultFREAKNOctaves())
1844 #if CV_MAJOR_VERSION < 3 1847 #ifdef HAVE_OPENCV_XFEATURES2D 1850 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1857 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1858 cv::Mat descriptors;
1859 #if CV_MAJOR_VERSION < 3 1860 _freak->compute(image, keypoints, descriptors);
1862 #ifdef HAVE_OPENCV_XFEATURES2D 1863 _freak->compute(image, keypoints, descriptors);
1865 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1897 #if CV_MAJOR_VERSION < 3 1900 #ifdef HAVE_OPENCV_XFEATURES2D 1903 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1910 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1911 cv::Mat descriptors;
1912 #if CV_MAJOR_VERSION < 3 1913 _freak->compute(image, keypoints, descriptors);
1915 #ifdef HAVE_OPENCV_XFEATURES2D 1916 _freak->compute(image, keypoints, descriptors);
1918 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1946 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1956 patternScale_(
Parameters::defaultBRISKPatternScale())
1973 #if CV_MAJOR_VERSION < 3 1982 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1983 std::vector<cv::KeyPoint> keypoints;
1984 cv::Mat imgRoi(image, roi);
1988 maskRoi = cv::Mat(mask, roi);
1990 brisk_->detect(imgRoi, keypoints, maskRoi);
1996 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1997 cv::Mat descriptors;
1998 brisk_->compute(image, keypoints, descriptors);
2006 extended_(
Parameters::defaultKAZEExtended()),
2008 threshold_(
Parameters::defaultKAZEThreshold()),
2009 nOctaves_(
Parameters::defaultKAZENOctaves()),
2010 nOctaveLayers_(
Parameters::defaultKAZENOctaveLayers()),
2011 diffusivity_(
Parameters::defaultKAZEDiffusivity())
2031 #if CV_MAJOR_VERSION > 3 2033 #elif CV_MAJOR_VERSION > 2 2036 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2042 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2043 std::vector<cv::KeyPoint> keypoints;
2044 #if CV_MAJOR_VERSION > 2 2045 cv::Mat imgRoi(image, roi);
2049 maskRoi = cv::Mat(mask, roi);
2051 kaze_->detect(imgRoi, keypoints, maskRoi);
2053 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2060 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2061 cv::Mat descriptors;
2062 #if CV_MAJOR_VERSION > 2 2063 kaze_->compute(image, keypoints, descriptors);
2065 UWARN(
"RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2074 scaleFactor_(
Parameters::defaultORBScaleFactor()),
2076 patchSize_(
Parameters::defaultORBPatchSize()),
2077 edgeThreshold_(
Parameters::defaultORBEdgeThreshold()),
2078 fastThreshold_(
Parameters::defaultFASTThreshold()),
2079 fastMinThreshold_(
Parameters::defaultFASTMinThreshold())
2100 #ifdef RTABMAP_ORB_OCTREE 2103 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2109 std::vector<cv::KeyPoint> keypoints;
2111 #ifdef RTABMAP_ORB_OCTREE 2112 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2113 cv::Mat imgRoi(image, roi);
2117 maskRoi = cv::Mat(mask, roi);
2127 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2134 #ifdef RTABMAP_ORB_OCTREE 2137 UWARN(
"RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2146 path_(
Parameters::defaultSuperPointModelPath()),
2147 threshold_(
Parameters::defaultSuperPointThreshold()),
2149 minDistance_(
Parameters::defaultSuperPointNMSRadius()),
2163 std::string previousPath =
path_;
2164 #ifdef RTABMAP_TORCH 2165 bool previousCuda =
cuda_;
2173 #ifdef RTABMAP_TORCH 2185 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2191 #ifdef RTABMAP_TORCH 2192 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2193 if(roi.x!=0 || roi.y !=0)
2195 UERROR(
"SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2196 roi.x, roi.y, roi.width, roi.height,
2197 Parameters::kKpRoiRatios().c_str(),
2198 Parameters::kVisRoiRatios().c_str(),
2199 Parameters::kVisGridRows().c_str(),
2200 Parameters::kVisGridCols().c_str(),
2201 Parameters::kKpGridRows().c_str(),
2202 Parameters::kKpGridCols().c_str());
2203 return std::vector<cv::KeyPoint>();
2207 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2208 return std::vector<cv::KeyPoint>();
2214 #ifdef RTABMAP_TORCH 2215 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2218 UWARN(
"RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2229 orientationNormalized_(
Parameters::defaultFREAKOrientationNormalized()),
2230 scaleNormalized_(
Parameters::defaultFREAKScaleNormalized()),
2231 patternScale_(
Parameters::defaultFREAKPatternScale()),
2232 nOctaves_(
Parameters::defaultFREAKNOctaves())
2250 #ifdef HAVE_OPENCV_XFEATURES2D 2251 _daisy = CV_DAISY::create();
2253 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2259 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2260 cv::Mat descriptors;
2261 #ifdef HAVE_OPENCV_XFEATURES2D 2262 _daisy->compute(image, keypoints, descriptors);
2264 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2295 #ifdef HAVE_OPENCV_XFEATURES2D 2296 _daisy = CV_DAISY::create();
2298 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2304 UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2305 cv::Mat descriptors;
2306 #ifdef HAVE_OPENCV_XFEATURES2D 2307 _daisy->compute(image, keypoints, descriptors);
2309 UWARN(
"RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
GLM_FUNC_DECL genIType mask(genIType const &count)
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
int fastCVLastImageHeight_
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
float maxDisparity() const
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const =0
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap ¶meters)
virtual std::vector< cv::Point2f > computeCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status) const
static void limitKeypoints(std::vector< cv::KeyPoint > &keypoints, int maxKeypoints)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
double gpuKeypointsRatio_
FAST_BRIEF(const ParametersMap ¶meters=ParametersMap())
GFTT_DAISY(const ParametersMap ¶meters=ParametersMap())
virtual void parseParameters(const ParametersMap ¶meters)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
SURF_DAISY(const ParametersMap ¶meters=ParametersMap())
virtual void parseParameters(const ParametersMap ¶meters)
cv::Ptr< CV_FREAK > _freak
GFTT_FREAK(const ParametersMap ¶meters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
uint32_t * fastCVCornerScores_
virtual void parseParameters(const ParametersMap ¶meters)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap ¶meters)
cv::Ptr< CV_FREAK > _freak
const cv::Mat & depthOrRightRaw() const
cv::BriefDescriptorExtractor CV_BRIEF
cv::Ptr< ORBextractor > _orb
GLM_FUNC_DECL genType e()
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
float UTILITE_EXP uStr2Float(const std::string &str)
uint32_t * fastCVCorners_
const std::vector< StereoCameraModel > & stereoCameraModels() const
std::map< std::string, std::string > ParametersMap
double contrastThreshold_
std::vector< float > _roiRatios
Basic mathematics functions.
cv::Ptr< CV_BRISK > brisk_
cv::Ptr< CV_ORB_GPU > _gpuOrb
Some conversion functions.
cv::FastFeatureDetector CV_FAST
Feature2D(const ParametersMap ¶meters=ParametersMap())
std::vector< cv::KeyPoint > generateKeypoints(const cv::Mat &image, const cv::Mat &mask=cv::Mat())
bool orientationNormalized_
SuperPointTorch(const ParametersMap ¶meters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
bool uIsFinite(const T &value)
cv::Ptr< CV_FAST_GPU > _gpuFast
#define UASSERT(condition)
std::vector< cv::Point3f > generateKeypoints3D(const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap ¶meters)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
static void filterKeypointsByDisparity(std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, float minDisparity)
BRISK(const ParametersMap ¶meters=ParametersMap())
const std::vector< CameraModel > & cameraModels() const
cv::Ptr< SPDetector > superPoint_
static Feature2D * create(const ParametersMap ¶meters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
#define ULOGGER_DEBUG(...)
virtual void parseParameters(const ParametersMap ¶meters)
#define UASSERT_MSG(condition, msg_str)
bool orientationNormalized_
const cv::Mat & imageRaw() const
virtual void parseParameters(const ParametersMap ¶meters)
cv::Ptr< CV_FREAK > _freak
SURF_FREAK(const ParametersMap ¶meters=ParametersMap())
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
FAST(const ParametersMap ¶meters=ParametersMap())
virtual void parseParameters(const ParametersMap ¶meters)
virtual void parseParameters(const ParametersMap ¶meters)
virtual void parseParameters(const ParametersMap ¶meters)
static void filterKeypointsByDepth(std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, float minDepth, float maxDepth)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
bool orientationNormalized_
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
virtual void parseParameters(const ParametersMap ¶meters)
KAZE(const ParametersMap ¶meters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::gpu::SURF_GPU CV_SURF_GPU
static ULogger::Level level()
static cv::Rect computeRoi(const cv::Mat &image, const std::string &roiRatios)
SIFT(const ParametersMap ¶meters=ParametersMap())
static Stereo * create(const ParametersMap ¶meters=ParametersMap())
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
cv::Ptr< CV_BRIEF > _brief
FAST_FREAK(const ParametersMap ¶meters=ParametersMap())
cv::Mat generateDescriptors(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
bool orientationNormalized_
virtual void parseParameters(const ParametersMap ¶meters)
ORBOctree(const ParametersMap ¶meters=ParametersMap())
ORB(const ParametersMap ¶meters=ParametersMap())
cv::Ptr< CV_BRIEF > _brief
virtual void parseParameters(const ParametersMap ¶meters)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap ¶meters)
GFTT(const ParametersMap ¶meters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
ULogger class and convenient macros.
SURF(const ParametersMap ¶meters=ParametersMap())
virtual void parseParameters(const ParametersMap ¶meters)
GFTT_BRIEF(const ParametersMap ¶meters=ParametersMap())
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
cv::gpu::ORB_GPU CV_ORB_GPU
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())=0
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap ¶meters)
GFTT_ORB(const ParametersMap ¶meters=ParametersMap())
bool orientationNormalized_
virtual ~SuperPointTorch()
cv::gpu::FAST_GPU CV_FAST_GPU
int getMaxFeatures() const
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
#define ULOGGER_ERROR(...)
std::vector< cv::Point3f > RTABMAP_EXP generateKeypoints3DDepth(const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, const CameraModel &cameraModel, float minDepth=0, float maxDepth=0)
cv::Ptr< cv::FeatureDetector > _fast
std::string UTILITE_EXP uFormat(const char *fmt,...)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
ParametersMap parameters_
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
virtual void parseParameters(const ParametersMap ¶meters)
virtual void parseParameters(const ParametersMap ¶meters)
std::vector< cv::Point3f > RTABMAP_EXP generateKeypoints3DStereo(const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const StereoCameraModel &model, const std::vector< unsigned char > &mask=std::vector< unsigned char >(), float minDepth=0, float maxDepth=0)
cv::Ptr< CV_SURF_GPU > _gpuSurf