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 #include <vector>
00037
00038 namespace rtabmap
00039 {
00040
00041 namespace util2d
00042 {
00043
00044
00045 float RTABMAP_EXP ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00046
00047 float RTABMAP_EXP sad(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00048
00049 std::vector<cv::Point2f> RTABMAP_EXP calcStereoCorrespondences(
00050 const cv::Mat & leftImage,
00051 const cv::Mat & rightImage,
00052 const std::vector<cv::Point2f> & leftCorners,
00053 std::vector<unsigned char> & status,
00054 cv::Size winSize = cv::Size(6,3),
00055 int maxLevel = 3,
00056 int iterations = 5,
00057 float minDisparity = 0.0f,
00058 float maxDisparity = 64.0f,
00059 bool ssdApproach = true);
00060
00061
00062 void RTABMAP_EXP calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputArray _nextImg,
00063 cv::InputArray _prevPts, cv::InputOutputArray _nextPts,
00064 cv::OutputArray _status, cv::OutputArray _err,
00065 cv::Size winSize = cv::Size(15,3), int maxLevel = 3,
00066 cv::TermCriteria criteria = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01),
00067 int flags = 0, double minEigThreshold = 1e-4 );
00068
00069
00070 cv::Mat RTABMAP_EXP disparityFromStereoImages(
00071 const cv::Mat & leftImage,
00072 const cv::Mat & rightImage,
00073 const ParametersMap & parameters = ParametersMap());
00074
00075 cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat & disparity,
00076 float fx, float baseline,
00077 int type = CV_32FC1);
00078
00079 cv::Mat RTABMAP_EXP depthFromStereoImages(
00080 const cv::Mat & leftImage,
00081 const cv::Mat & rightImage,
00082 const std::vector<cv::Point2f> & leftCorners,
00083 float fx,
00084 float baseline,
00085 int flowWinSize = 9,
00086 int flowMaxLevel = 4,
00087 int flowIterations = 20,
00088 double flowEps = 0.02);
00089
00090 cv::Mat RTABMAP_EXP disparityFromStereoCorrespondences(
00091 const cv::Size & disparitySize,
00092 const std::vector<cv::Point2f> & leftCorners,
00093 const std::vector<cv::Point2f> & rightCorners,
00094 const std::vector<unsigned char> & mask);
00095
00096 cv::Mat RTABMAP_EXP depthFromStereoCorrespondences(
00097 const cv::Mat & leftImage,
00098 const std::vector<cv::Point2f> & leftCorners,
00099 const std::vector<cv::Point2f> & rightCorners,
00100 const std::vector<unsigned char> & mask,
00101 float fx, float baseline);
00102
00103 cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat & depth32F);
00104 cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat & depth16U);
00105
00106 float RTABMAP_EXP getDepth(
00107 const cv::Mat & depthImage,
00108 float x, float y,
00109 bool smoothing,
00110 float depthErrorRatio = 0.02f,
00111 bool estWithNeighborsIfNull = false);
00112
00113 cv::Rect RTABMAP_EXP computeRoi(const cv::Mat & image, const std::string & roiRatios);
00114 cv::Rect RTABMAP_EXP computeRoi(const cv::Size & imageSize, const std::string & roiRatios);
00115 cv::Rect RTABMAP_EXP computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
00116 cv::Rect RTABMAP_EXP computeRoi(const cv::Size & imageSize, const std::vector<float> & roiRatios);
00117
00118 cv::Mat RTABMAP_EXP decimate(const cv::Mat & image, int d);
00119 cv::Mat RTABMAP_EXP interpolate(const cv::Mat & image, int factor, float depthErrorRatio = 0.02f);
00120
00121
00122 cv::Mat RTABMAP_EXP registerDepth(
00123 const cv::Mat & depth,
00124 const cv::Mat & depthK,
00125 const cv::Size & colorSize,
00126 const cv::Mat & colorK,
00127 const rtabmap::Transform & transform);
00128
00129 cv::Mat RTABMAP_EXP fillDepthHoles(
00130 const cv::Mat & depth,
00131 int maximumHoleSize = 1,
00132 float errorRatio = 0.02f);
00133
00134 void RTABMAP_EXP fillRegisteredDepthHoles(
00135 cv::Mat & depthRegistered,
00136 bool vertical,
00137 bool horizontal,
00138 bool fillDoubleHoles = false);
00139
00140 cv::Mat RTABMAP_EXP fastBilateralFiltering(
00141 const cv::Mat & depth,
00142 float sigmaS = 15.0f,
00143 float sigmaR = 0.05f,
00144 bool earlyDivision = false);
00145
00146 cv::Mat RTABMAP_EXP brightnessAndContrastAuto(
00147 const cv::Mat & src,
00148 const cv::Mat & mask,
00149 float clipLowHistPercent=0,
00150 float clipHighHistPercent=0);
00151
00152 cv::Mat RTABMAP_EXP exposureFusion(
00153 const std::vector<cv::Mat> & images);
00154
00155 }
00156 }
00157
00158 #endif