util2d.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL2D_H_
29 #define UTIL2D_H_
30 
31 #include <rtabmap/core/rtabmap_core_export.h>
32 
33 #include <opencv2/core/core.hpp>
34 #include <rtabmap/core/Transform.h>
37 #include <vector>
38 
39 namespace rtabmap
40 {
41 
42 namespace util2d
43 {
44 
45 // SSD: Sum of Squared Differences
46 float RTABMAP_CORE_EXPORT ssd(const cv::Mat & windowLeft, const cv::Mat & windowRight);
47 // SAD: Sum of Absolute intensity Differences
48 float RTABMAP_CORE_EXPORT sad(const cv::Mat & windowLeft, const cv::Mat & windowRight);
49 
50 std::vector<cv::Point2f> RTABMAP_CORE_EXPORT calcStereoCorrespondences(
51  const cv::Mat & leftImage,
52  const cv::Mat & rightImage,
53  const std::vector<cv::Point2f> & leftCorners,
54  std::vector<unsigned char> & status,
55  cv::Size winSize = cv::Size(6,3),
56  int maxLevel = 3,
57  int iterations = 5,
58  float minDisparity = 0.0f,
59  float maxDisparity = 64.0f,
60  bool ssdApproach = true); // SSD by default, otherwise it is SAD
61 
62 // exactly as cv::calcOpticalFlowPyrLK but it should be called with pyramid (from cv::buildOpticalFlowPyramid()) and delta drops the y error.
63 void RTABMAP_CORE_EXPORT calcOpticalFlowPyrLKStereo( cv::InputArray _prevImg, cv::InputArray _nextImg,
64  cv::InputArray _prevPts, cv::InputOutputArray _nextPts,
65  cv::OutputArray _status, cv::OutputArray _err,
66  cv::Size winSize = cv::Size(15,3), int maxLevel = 3,
67  cv::TermCriteria criteria = cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01),
68  int flags = 0, double minEigThreshold = 1e-4 );
69 
70 
71 cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoImages(
72  const cv::Mat & leftImage,
73  const cv::Mat & rightImage,
74  const ParametersMap & parameters = ParametersMap());
75 
76 cv::Mat RTABMAP_CORE_EXPORT depthFromDisparity(const cv::Mat & disparity,
77  float fx, float baseline,
78  int type = CV_32FC1); // CV_32FC1 or CV_16UC1
79 
80 cv::Mat RTABMAP_CORE_EXPORT depthFromStereoImages(
81  const cv::Mat & leftImage,
82  const cv::Mat & rightImage,
83  const std::vector<cv::Point2f> & leftCorners,
84  float fx,
85  float baseline,
86  int flowWinSize = 9,
87  int flowMaxLevel = 4,
88  int flowIterations = 20,
89  double flowEps = 0.02);
90 
91 cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoCorrespondences(
92  const cv::Size & disparitySize,
93  const std::vector<cv::Point2f> & leftCorners,
94  const std::vector<cv::Point2f> & rightCorners,
95  const std::vector<unsigned char> & mask);
96 
97 cv::Mat RTABMAP_CORE_EXPORT depthFromStereoCorrespondences(
98  const cv::Mat & leftImage,
99  const std::vector<cv::Point2f> & leftCorners,
100  const std::vector<cv::Point2f> & rightCorners,
101  const std::vector<unsigned char> & mask,
102  float fx, float baseline);
103 
104 cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat & depth32F);
105 cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat(const cv::Mat & depth16U);
106 
107 float RTABMAP_CORE_EXPORT getDepth(
108  const cv::Mat & depthImage,
109  float x, float y,
110  bool smoothing,
111  float depthErrorRatio = 0.02f, //ratio
112  bool estWithNeighborsIfNull = false);
113 
114 cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat & image, const std::string & roiRatios);
115 cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Size & imageSize, const std::string & roiRatios);
116 cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios);
117 cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Size & imageSize, const std::vector<float> & roiRatios);
118 
119 cv::Mat RTABMAP_CORE_EXPORT decimate(const cv::Mat & image, int d);
120 cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat & image, int factor, float depthErrorRatio = 0.02f);
121 
122 // Registration Depth to RGB (return registered depth image)
123 cv::Mat RTABMAP_CORE_EXPORT registerDepth(
124  const cv::Mat & depth,
125  const cv::Mat & depthK,
126  const cv::Size & colorSize,
127  const cv::Mat & colorK,
128  const rtabmap::Transform & transform);
129 
130 cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(
131  const cv::Mat & depth,
132  int maximumHoleSize = 1,
133  float errorRatio = 0.02f);
134 
135 void RTABMAP_CORE_EXPORT fillRegisteredDepthHoles(
136  cv::Mat & depthRegistered,
137  bool vertical,
138  bool horizontal,
139  bool fillDoubleHoles = false);
140 
141 cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering(
142  const cv::Mat & depth,
143  float sigmaS = 15.0f,
144  float sigmaR = 0.05f,
145  bool earlyDivision = false);
146 
147 cv::Mat RTABMAP_CORE_EXPORT brightnessAndContrastAuto(
148  const cv::Mat & src,
149  const cv::Mat & mask,
150  float clipLowHistPercent=0,
151  float clipHighHistPercent=0,
152  float * alphaOut = 0,
153  float * betaOut = 0);
154 
155 cv::Mat RTABMAP_CORE_EXPORT exposureFusion(
156  const std::vector<cv::Mat> & images);
157 
158 void RTABMAP_CORE_EXPORT HSVtoRGB( float *r, float *g, float *b, float h, float s, float v );
159 
160 void RTABMAP_CORE_EXPORT NMS(
161  const std::vector<cv::KeyPoint> & ptsIn,
162  const cv::Mat & descriptorsIn,
163  std::vector<cv::KeyPoint> & ptsOut,
164  cv::Mat & descriptorsOut,
165  int border, int dist_thresh, int img_width, int img_height);
166 
167 std::vector<int> RTABMAP_CORE_EXPORT SSC(
168  const std::vector<cv::KeyPoint> & keypoints, int maxKeypoints, float tolerance, int cols, int rows);
169 
184 void RTABMAP_CORE_EXPORT rotateImagesUpsideUpIfNecessary(
185  CameraModel & model,
186  cv::Mat & rgb,
187  cv::Mat & depth);
188 
189 } // namespace util3d
190 } // namespace rtabmap
191 
192 #endif /* UTIL2D_H_ */
rtabmap::util2d::computeRoi
cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: util2d.cpp:1113
glm::mask
GLM_FUNC_DECL genIType mask(genIType const &count)
rtabmap::util2d::HSVtoRGB
void RTABMAP_CORE_EXPORT HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
Definition: util2d.cpp:2047
rtabmap::util2d::fillRegisteredDepthHoles
void RTABMAP_CORE_EXPORT fillRegisteredDepthHoles(cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false)
Definition: util2d.cpp:1598
rtabmap::util2d::interpolate
cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
Definition: util2d.cpp:1250
s
RealScalar s
rtabmap::util2d::sad
float RTABMAP_CORE_EXPORT sad(const cv::Mat &windowLeft, const cv::Mat &windowRight)
Definition: util2d.cpp:91
b
Array< int, 3, 1 > b
fx
const double fx
h
const double h
rtabmap::CameraModel
Definition: CameraModel.h:38
Transform.h
type
rtabmap::util2d::registerDepth
cv::Mat RTABMAP_CORE_EXPORT registerDepth(const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform)
Definition: util2d.cpp:1362
y
Matrix3f y
rtabmap::util2d::brightnessAndContrastAuto
cv::Mat RTABMAP_CORE_EXPORT brightnessAndContrastAuto(const cv::Mat &src, const cv::Mat &mask, float clipLowHistPercent=0, float clipHighHistPercent=0, float *alphaOut=0, float *betaOut=0)
Automatic brightness and contrast optimization with optional histogram clipping.
Definition: util2d.cpp:1942
rtabmap::util2d::cvtDepthToFloat
cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat(const cv::Mat &depth16U)
Definition: util2d.cpp:928
rtabmap::util2d::disparityFromStereoImages
cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoImages(const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap &parameters=ParametersMap())
Definition: util2d.cpp:738
rtabmap::util2d::rotateImagesUpsideUpIfNecessary
void RTABMAP_CORE_EXPORT rotateImagesUpsideUpIfNecessary(CameraModel &model, cv::Mat &rgb, cv::Mat &depth)
Rotate images and camera model so that the top of the image is up.
Definition: util2d.cpp:2282
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rows
int rows
rtabmap::util2d::decimate
cv::Mat RTABMAP_CORE_EXPORT decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1201
Parameters.h
rtabmap::util2d::fillDepthHoles
cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
Definition: util2d.cpp:1439
g
float g
rtabmap::util2d::fastBilateralFiltering
cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1814
rtabmap::util2d::calcStereoCorrespondences
std::vector< cv::Point2f > RTABMAP_CORE_EXPORT calcStereoCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status, cv::Size winSize=cv::Size(6, 3), int maxLevel=3, int iterations=5, float minDisparity=0.0f, float maxDisparity=64.0f, bool ssdApproach=true)
Definition: util2d.cpp:122
d
d
x
x
rtabmap::util2d::ssd
float RTABMAP_CORE_EXPORT ssd(const cv::Mat &windowLeft, const cv::Mat &windowRight)
Definition: util2d.cpp:56
rtabmap::util2d::depthFromDisparity
cv::Mat RTABMAP_CORE_EXPORT depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
Definition: util2d.cpp:763
rtabmap::util2d::getDepth
float RTABMAP_CORE_EXPORT getDepth(const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
Definition: util2d.cpp:947
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
rtabmap::Transform
Definition: Transform.h:41
rtabmap::util2d::cvtDepthFromFloat
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat &depth32F)
Definition: util2d.cpp:892
rtabmap::util2d::calcOpticalFlowPyrLKStereo
void RTABMAP_CORE_EXPORT calcOpticalFlowPyrLKStereo(cv::InputArray _prevImg, cv::InputArray _nextImg, cv::InputArray _prevPts, cv::InputOutputArray _nextPts, cv::OutputArray _status, cv::OutputArray _err, cv::Size winSize=cv::Size(15, 3), int maxLevel=3, cv::TermCriteria criteria=cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01), int flags=0, double minEigThreshold=1e-4)
Definition: util2d.cpp:371
rtabmap::util2d::depthFromStereoCorrespondences
cv::Mat RTABMAP_CORE_EXPORT depthFromStereoCorrespondences(const cv::Mat &leftImage, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask, float fx, float baseline)
Definition: util2d.cpp:867
v
Array< int, Dynamic, 1 > v
rtabmap::util2d::NMS
void RTABMAP_CORE_EXPORT NMS(const std::vector< cv::KeyPoint > &ptsIn, const cv::Mat &descriptorsIn, std::vector< cv::KeyPoint > &ptsOut, cv::Mat &descriptorsOut, int border, int dist_thresh, int img_width, int img_height)
Definition: util2d.cpp:2096
rtabmap::util2d::SSC
std::vector< int > RTABMAP_CORE_EXPORT SSC(const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, float tolerance, int cols, int rows)
Definition: util2d.cpp:2205
CameraModel.h
rtabmap::util2d::exposureFusion
cv::Mat RTABMAP_CORE_EXPORT exposureFusion(const std::vector< cv::Mat > &images)
Definition: util2d.cpp:2027
transform
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
cols
int cols
rtabmap::util2d::depthFromStereoImages
cv::Mat RTABMAP_CORE_EXPORT depthFromStereoImages(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, float fx, float baseline, int flowWinSize=9, int flowMaxLevel=4, int flowIterations=20, double flowEps=0.02)
Definition: util2d.cpp:808
rtabmap
Definition: CameraARCore.cpp:35
trace.model
model
Definition: trace.py:4
rtabmap::util2d::disparityFromStereoCorrespondences
cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoCorrespondences(const cv::Size &disparitySize, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask)
Definition: util2d.cpp:845
baseline
double baseline


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:23