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 
00037 namespace rtabmap
00038 {
00039 
00040 namespace util2d
00041 {
00042 
00043 // SSD: Sum of Squared Differences
00044 float RTABMAP_EXP ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
00045 // SAD: Sum of Absolute intensity Differences
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); // SSD by default, otherwise it is SAD
00059 
00060 // exactly as cv::calcOpticalFlowPyrLK but it should be called with pyramid (from cv::buildOpticalFlowPyramid()) and delta drops the y error.
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); // CV_32FC1 or CV_16UC1
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 // Registration Depth to RGB (return registered depth image)
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 } // namespace util3d
00134 } // namespace rtabmap
00135 
00136 #endif /* UTIL2D_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28