Go to the documentation of this file.
31 #include <rtabmap/core/rtabmap_core_export.h>
33 #include <opencv2/core/core.hpp>
46 float RTABMAP_CORE_EXPORT
ssd(
const cv::Mat & windowLeft,
const cv::Mat & windowRight);
48 float RTABMAP_CORE_EXPORT
sad(
const cv::Mat & windowLeft,
const cv::Mat & windowRight);
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),
58 float minDisparity = 0.0
f,
59 float maxDisparity = 64.0
f,
60 bool ssdApproach =
true);
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 = 1
e-4 );
72 const cv::Mat & leftImage,
73 const cv::Mat & rightImage,
81 const cv::Mat & leftImage,
82 const cv::Mat & rightImage,
83 const std::vector<cv::Point2f> & leftCorners,
88 int flowIterations = 20,
89 double flowEps = 0.02);
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);
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,
108 const cv::Mat & depthImage,
111 float depthErrorRatio = 0.02
f,
112 bool estWithNeighborsIfNull =
false);
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);
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.02
f);
124 const cv::Mat & depth,
125 const cv::Mat & depthK,
126 const cv::Size & colorSize,
127 const cv::Mat & colorK,
131 const cv::Mat & depth,
132 int maximumHoleSize = 1,
133 float errorRatio = 0.02
f);
136 cv::Mat & depthRegistered,
139 bool fillDoubleHoles =
false);
142 const cv::Mat & depth,
143 float sigmaS = 15.0
f,
144 float sigmaR = 0.05
f,
145 bool earlyDivision =
false);
149 const cv::Mat &
mask,
150 float clipLowHistPercent=0,
151 float clipHighHistPercent=0,
152 float * alphaOut = 0,
153 float * betaOut = 0);
156 const std::vector<cv::Mat> & images);
158 void RTABMAP_CORE_EXPORT
HSVtoRGB(
float *r,
float *
g,
float *
b,
float h,
float s,
float v );
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);
167 std::vector<int> RTABMAP_CORE_EXPORT
SSC(
168 const std::vector<cv::KeyPoint> & keypoints,
int maxKeypoints,
float tolerance,
int cols,
int rows);
cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat &image, const std::string &roiRatios)
GLM_FUNC_DECL genIType mask(genIType const &count)
void RTABMAP_CORE_EXPORT HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
void RTABMAP_CORE_EXPORT fillRegisteredDepthHoles(cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false)
cv::Mat RTABMAP_CORE_EXPORT interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
float RTABMAP_CORE_EXPORT sad(const cv::Mat &windowLeft, const cv::Mat &windowRight)
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)
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.
cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat(const cv::Mat &depth16U)
cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoImages(const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap ¶meters=ParametersMap())
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.
std::map< std::string, std::string > ParametersMap
cv::Mat RTABMAP_CORE_EXPORT decimate(const cv::Mat &image, int d)
cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
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)
float RTABMAP_CORE_EXPORT ssd(const cv::Mat &windowLeft, const cv::Mat &windowRight)
cv::Mat RTABMAP_CORE_EXPORT depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
float RTABMAP_CORE_EXPORT getDepth(const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat(const cv::Mat &depth32F)
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)
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)
Array< int, Dynamic, 1 > v
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)
std::vector< int > RTABMAP_CORE_EXPORT SSC(const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, float tolerance, int cols, int rows)
cv::Mat RTABMAP_CORE_EXPORT exposureFusion(const std::vector< cv::Mat > &images)
EIGEN_DONT_INLINE void transform(const Quaternion< Scalar > &t, Data &data)
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)
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)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:23