00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef UTIL3D_CORRESPONDENCES_H_
00029 #define UTIL3D_CORRESPONDENCES_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032
00033 #include <pcl/point_cloud.h>
00034 #include <pcl/point_types.h>
00035 #include <opencv2/features2d/features2d.hpp>
00036 #include <set>
00037 #include <map>
00038 #include <list>
00039
00040 namespace rtabmap
00041 {
00042
00043 namespace util3d
00044 {
00045
00046
00047 void RTABMAP_EXP findCorrespondences(
00048 const std::multimap<int, cv::KeyPoint> & wordsA,
00049 const std::multimap<int, cv::KeyPoint> & wordsB,
00050 std::list<std::pair<cv::Point2f, cv::Point2f> > & pairs);
00051
00052 void RTABMAP_EXP findCorrespondences(
00053 const std::multimap<int, cv::Point3f> & words1,
00054 const std::multimap<int, cv::Point3f> & words2,
00055 std::vector<cv::Point3f> & inliers1,
00056 std::vector<cv::Point3f> & inliers2,
00057 float maxDepth,
00058 std::vector<int> * uniqueCorrespondences = 0);
00059
00060 void RTABMAP_EXP findCorrespondences(
00061 const std::map<int, cv::Point3f> & words1,
00062 const std::map<int, cv::Point3f> & words2,
00063 std::vector<cv::Point3f> & inliers1,
00064 std::vector<cv::Point3f> & inliers2,
00065 float maxDepth,
00066 std::vector<int> * correspondences = 0);
00067
00068
00069 void RTABMAP_EXP extractXYZCorrespondences(const std::multimap<int, pcl::PointXYZ> & words1,
00070 const std::multimap<int, pcl::PointXYZ> & words2,
00071 pcl::PointCloud<pcl::PointXYZ> & cloud1,
00072 pcl::PointCloud<pcl::PointXYZ> & cloud2);
00073
00074 void RTABMAP_EXP extractXYZCorrespondencesRANSAC(const std::multimap<int, pcl::PointXYZ> & words1,
00075 const std::multimap<int, pcl::PointXYZ> & words2,
00076 pcl::PointCloud<pcl::PointXYZ> & cloud1,
00077 pcl::PointCloud<pcl::PointXYZ> & cloud2);
00078
00079 void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
00080 const cv::Mat & depthImage1,
00081 const cv::Mat & depthImage2,
00082 float cx, float cy,
00083 float fx, float fy,
00084 float maxDepth,
00085 pcl::PointCloud<pcl::PointXYZ> & cloud1,
00086 pcl::PointCloud<pcl::PointXYZ> & cloud2);
00087
00088 void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
00089 const pcl::PointCloud<pcl::PointXYZ> & cloud1,
00090 const pcl::PointCloud<pcl::PointXYZ> & cloud2,
00091 pcl::PointCloud<pcl::PointXYZ> & inliers1,
00092 pcl::PointCloud<pcl::PointXYZ> & inliers2,
00093 char depthAxis);
00094 void RTABMAP_EXP extractXYZCorrespondences(const std::list<std::pair<cv::Point2f, cv::Point2f> > & correspondences,
00095 const pcl::PointCloud<pcl::PointXYZRGB> & cloud1,
00096 const pcl::PointCloud<pcl::PointXYZRGB> & cloud2,
00097 pcl::PointCloud<pcl::PointXYZ> & inliers1,
00098 pcl::PointCloud<pcl::PointXYZ> & inliers2,
00099 char depthAxis);
00100
00101 int RTABMAP_EXP countUniquePairs(const std::multimap<int, pcl::PointXYZ> & wordsA,
00102 const std::multimap<int, pcl::PointXYZ> & wordsB);
00103
00104 void RTABMAP_EXP filterMaxDepth(pcl::PointCloud<pcl::PointXYZ> & inliers1,
00105 pcl::PointCloud<pcl::PointXYZ> & inliers2,
00106 float maxDepth,
00107 char depthAxis,
00108 bool removeDuplicates);
00109
00110 }
00111 }
00112
00113 #endif