util2d.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 // SSD: Sum of Squared Differences
00045 float RTABMAP_EXP ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00046 // SAD: Sum of Absolute intensity Differences
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); // SSD by default, otherwise it is SAD
00060 
00061 // exactly as cv::calcOpticalFlowPyrLK but it should be called with pyramid (from cv::buildOpticalFlowPyramid()) and delta drops the y error.
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); // CV_32FC1 or CV_16UC1
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, //ratio
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 // Registration Depth to RGB (return registered depth image)
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 } // namespace util3d
00156 } // namespace rtabmap
00157 
00158 #endif /* UTIL2D_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:32