28 #ifndef UTIL3D_FEATURES_H_ 29 #define UTIL3D_FEATURES_H_ 33 #include <opencv2/calib3d/calib3d.hpp> 48 const std::vector<cv::KeyPoint> & keypoints,
49 const cv::Mat & depth,
50 const CameraModel & cameraModel,
55 const std::vector<cv::KeyPoint> & keypoints,
56 const cv::Mat & depth,
57 const std::vector<CameraModel> & cameraModels,
62 const std::vector<cv::KeyPoint> & keypoints,
63 const cv::Mat & disparity,
64 const StereoCameraModel & stereoCameraModel,
69 const std::vector<cv::Point2f> & leftCorners,
70 const std::vector<cv::Point2f> & rightCorners,
71 const StereoCameraModel &
model,
72 const std::vector<unsigned char> &
mask = std::vector<unsigned char>(),
77 const std::map<int, cv::KeyPoint> & kpts,
78 const std::map<int, cv::KeyPoint> & previousKpts,
79 const CameraModel & cameraModel,
80 Transform & cameraTransform,
81 float ransacReprojThreshold = 3.0f,
82 float ransacConfidence = 0.99f,
83 const std::map<int, cv::Point3f> & refGuess3D = std::map<int, cv::Point3f>(),
84 double * variance = 0,
85 std::vector<int> * matchesOut = 0);
88 const std::list<int> & wordIds,
89 const std::vector<cv::KeyPoint> & keypoints);
GLM_FUNC_DECL genIType mask(genIType const &count)
std::map< int, cv::Point3f > RTABMAP_EXP generateWords3DMono(const std::map< int, cv::KeyPoint > &kpts, const std::map< int, cv::KeyPoint > &previousKpts, const CameraModel &cameraModel, Transform &cameraTransform, float ransacReprojThreshold=3.0f, float ransacConfidence=0.99f, const std::map< int, cv::Point3f > &refGuess3D=std::map< int, cv::Point3f >(), double *variance=0, std::vector< int > *matchesOut=0)
std::multimap< int, cv::KeyPoint > RTABMAP_EXP aggregate(const std::list< int > &wordIds, const std::vector< cv::KeyPoint > &keypoints)
std::vector< cv::Point3f > RTABMAP_EXP generateKeypoints3DDisparity(const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, const StereoCameraModel &stereoCameraModel, float minDepth=0, float maxDepth=0)
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)
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)