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 UTIL2D_H_
00029 #define UTIL2D_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032
00033 #include <opencv2/core/core.hpp>
00034 #include <rtabmap/core/Transform.h>
00035 #include <rtabmap/core/Parameters.h>
00036
00037 namespace rtabmap
00038 {
00039
00040 namespace util2d
00041 {
00042
00043
00044 float RTABMAP_EXP ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00045
00046 float RTABMAP_EXP sad(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00047
00048 std::vector<cv::Point2f> RTABMAP_EXP calcStereoCorrespondences(
00049 const cv::Mat & leftImage,
00050 const cv::Mat & rightImage,
00051 const std::vector<cv::Point2f> & leftCorners,
00052 std::vector<unsigned char> & status,
00053 cv::Size winSize = cv::Size(6,3),
00054 int maxLevel = 3,
00055 int iterations = 5,
00056 int minDisparity = 0,
00057 int maxDisparity = 64,
00058 bool ssdApproach = true);
00059
00060
00061 void RTABMAP_EXP calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputArray _nextImg,
00062 cv::InputArray _prevPts, cv::InputOutputArray _nextPts,
00063 cv::OutputArray _status, cv::OutputArray _err,
00064 cv::Size winSize = cv::Size(15,3), int maxLevel = 3,
00065 cv::TermCriteria criteria = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01),
00066 int flags = 0, double minEigThreshold = 1e-4 );
00067
00068
00069 cv::Mat RTABMAP_EXP disparityFromStereoImages(
00070 const cv::Mat & leftImage,
00071 const cv::Mat & rightImage,
00072 const ParametersMap & parameters = ParametersMap());
00073
00074 cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat & disparity,
00075 float fx, float baseline,
00076 int type = CV_32FC1);
00077
00078 cv::Mat RTABMAP_EXP depthFromStereoImages(
00079 const cv::Mat & leftImage,
00080 const cv::Mat & rightImage,
00081 const std::vector<cv::Point2f> & leftCorners,
00082 float fx,
00083 float baseline,
00084 int flowWinSize = 9,
00085 int flowMaxLevel = 4,
00086 int flowIterations = 20,
00087 double flowEps = 0.02);
00088
00089 cv::Mat RTABMAP_EXP disparityFromStereoCorrespondences(
00090 const cv::Size & disparitySize,
00091 const std::vector<cv::Point2f> & leftCorners,
00092 const std::vector<cv::Point2f> & rightCorners,
00093 const std::vector<unsigned char> & mask);
00094
00095 cv::Mat RTABMAP_EXP depthFromStereoCorrespondences(
00096 const cv::Mat & leftImage,
00097 const std::vector<cv::Point2f> & leftCorners,
00098 const std::vector<cv::Point2f> & rightCorners,
00099 const std::vector<unsigned char> & mask,
00100 float fx, float baseline);
00101
00102 cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat & depth32F);
00103 cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat & depth16U);
00104
00105 float RTABMAP_EXP getDepth(
00106 const cv::Mat & depthImage,
00107 float x, float y,
00108 bool smoothing,
00109 float maxZError = 0.02f,
00110 bool estWithNeighborsIfNull = false);
00111
00112 cv::Mat RTABMAP_EXP decimate(const cv::Mat & image, int d);
00113 cv::Mat RTABMAP_EXP interpolate(const cv::Mat & image, int factor, float depthErrorRatio = 0.02f);
00114
00115
00116 cv::Mat RTABMAP_EXP registerDepth(
00117 const cv::Mat & depth,
00118 const cv::Mat & depthK,
00119 const cv::Mat & colorK,
00120 const rtabmap::Transform & transform);
00121
00122 cv::Mat RTABMAP_EXP fillDepthHoles(
00123 const cv::Mat & depth,
00124 int maximumHoleSize = 1,
00125 float errorRatio = 0.02f);
00126
00127 void RTABMAP_EXP fillRegisteredDepthHoles(
00128 cv::Mat & depthRegistered,
00129 bool vertical,
00130 bool horizontal,
00131 bool fillDoubleHoles = false);
00132
00133 }
00134 }
00135
00136 #endif