Classes | |
class | Array3D |
Typedefs | |
typedef float | acctype |
typedef float | itemtype |
Functions | |
cv::Mat RTABMAP_EXP | brightnessAndContrastAuto (const cv::Mat &src, const cv::Mat &mask, float clipLowHistPercent, float clipHighHistPercent) |
Automatic brightness and contrast optimization with optional histogram clipping. | |
void RTABMAP_EXP | 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) |
std::vector< cv::Point2f > RTABMAP_EXP | 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) |
cv::Rect RTABMAP_EXP | computeRoi (const cv::Mat &image, const std::string &roiRatios) |
cv::Rect RTABMAP_EXP | computeRoi (const cv::Size &imageSize, const std::string &roiRatios) |
cv::Rect RTABMAP_EXP | computeRoi (const cv::Mat &image, const std::vector< float > &roiRatios) |
cv::Rect RTABMAP_EXP | computeRoi (const cv::Size &imageSize, const std::vector< float > &roiRatios) |
cv::Mat RTABMAP_EXP | cvtDepthFromFloat (const cv::Mat &depth32F) |
cv::Mat RTABMAP_EXP | cvtDepthToFloat (const cv::Mat &depth16U) |
cv::Mat RTABMAP_EXP | decimate (const cv::Mat &image, int d) |
cv::Mat RTABMAP_EXP | depthFromDisparity (const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1) |
cv::Mat RTABMAP_EXP | 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) |
cv::Mat RTABMAP_EXP | 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_EXP | disparityFromStereoCorrespondences (const cv::Size &disparitySize, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask) |
cv::Mat RTABMAP_EXP | disparityFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap ¶meters=ParametersMap()) |
cv::Mat RTABMAP_EXP | exposureFusion (const std::vector< cv::Mat > &images) |
cv::Mat RTABMAP_EXP | fastBilateralFiltering (const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false) |
cv::Mat RTABMAP_EXP | fillDepthHoles (const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f) |
void RTABMAP_EXP | fillRegisteredDepthHoles (cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false) |
float RTABMAP_EXP | getDepth (const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false) |
cv::Mat RTABMAP_EXP | interpolate (const cv::Mat &image, int factor, float depthErrorRatio=0.02f) |
cv::Mat RTABMAP_EXP | registerDepth (const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform) |
float RTABMAP_EXP | sad (const cv::Mat &windowLeft, const cv::Mat &windowRight) |
float RTABMAP_EXP | ssd (const cv::Mat &windowLeft, const cv::Mat &windowRight) |
typedef float rtabmap::util2d::acctype |
Definition at line 352 of file util2d.cpp.
typedef float rtabmap::util2d::itemtype |
Definition at line 353 of file util2d.cpp.
cv::Mat rtabmap::util2d::brightnessAndContrastAuto | ( | const cv::Mat & | src, |
const cv::Mat & | mask, | ||
float | clipLowHistPercent, | ||
float | clipHighHistPercent | ||
) |
Automatic brightness and contrast optimization with optional histogram clipping.
[in] | Input image GRAY or BGR or BGRA | |
[out] | Destination image | |
clipHistPercent | cut wings of histogram at given percent typical=>1, 0=>Disabled |
Definition at line 1937 of file util2d.cpp.
void rtabmap::util2d::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 at line 367 of file util2d.cpp.
std::vector< cv::Point2f > rtabmap::util2d::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 at line 122 of file util2d.cpp.
cv::Rect rtabmap::util2d::computeRoi | ( | const cv::Mat & | image, |
const std::string & | roiRatios | ||
) |
Definition at line 1108 of file util2d.cpp.
cv::Rect rtabmap::util2d::computeRoi | ( | const cv::Size & | imageSize, |
const std::string & | roiRatios | ||
) |
Definition at line 1113 of file util2d.cpp.
cv::Rect rtabmap::util2d::computeRoi | ( | const cv::Mat & | image, |
const std::vector< float > & | roiRatios | ||
) |
Definition at line 1145 of file util2d.cpp.
cv::Rect rtabmap::util2d::computeRoi | ( | const cv::Size & | imageSize, |
const std::vector< float > & | roiRatios | ||
) |
Definition at line 1150 of file util2d.cpp.
cv::Mat rtabmap::util2d::cvtDepthFromFloat | ( | const cv::Mat & | depth32F | ) |
Definition at line 887 of file util2d.cpp.
cv::Mat rtabmap::util2d::cvtDepthToFloat | ( | const cv::Mat & | depth16U | ) |
Definition at line 923 of file util2d.cpp.
cv::Mat rtabmap::util2d::decimate | ( | const cv::Mat & | image, |
int | d | ||
) |
Definition at line 1196 of file util2d.cpp.
cv::Mat rtabmap::util2d::depthFromDisparity | ( | const cv::Mat & | disparity, |
float | fx, | ||
float | baseline, | ||
int | type = CV_32FC1 |
||
) |
Definition at line 758 of file util2d.cpp.
cv::Mat rtabmap::util2d::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 at line 862 of file util2d.cpp.
cv::Mat rtabmap::util2d::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 at line 803 of file util2d.cpp.
cv::Mat rtabmap::util2d::disparityFromStereoCorrespondences | ( | const cv::Size & | disparitySize, |
const std::vector< cv::Point2f > & | leftCorners, | ||
const std::vector< cv::Point2f > & | rightCorners, | ||
const std::vector< unsigned char > & | mask | ||
) |
Definition at line 840 of file util2d.cpp.
cv::Mat rtabmap::util2d::disparityFromStereoImages | ( | const cv::Mat & | leftImage, |
const cv::Mat & | rightImage, | ||
const ParametersMap & | parameters = ParametersMap() |
||
) |
Definition at line 734 of file util2d.cpp.
cv::Mat rtabmap::util2d::exposureFusion | ( | const std::vector< cv::Mat > & | images | ) |
Definition at line 2012 of file util2d.cpp.
cv::Mat rtabmap::util2d::fastBilateralFiltering | ( | const cv::Mat & | depth, |
float | sigmaS, | ||
float | sigmaR, | ||
bool | earlyDivision | ||
) |
Converted pcl::FastBilateralFiltering class to 2d depth image
Definition at line 1809 of file util2d.cpp.
cv::Mat rtabmap::util2d::fillDepthHoles | ( | const cv::Mat & | depth, |
int | maximumHoleSize = 1 , |
||
float | errorRatio = 0.02f |
||
) |
Definition at line 1434 of file util2d.cpp.
void rtabmap::util2d::fillRegisteredDepthHoles | ( | cv::Mat & | depthRegistered, |
bool | vertical, | ||
bool | horizontal, | ||
bool | fillDoubleHoles = false |
||
) |
Definition at line 1593 of file util2d.cpp.
float rtabmap::util2d::getDepth | ( | const cv::Mat & | depthImage, |
float | x, | ||
float | y, | ||
bool | smoothing, | ||
float | depthErrorRatio = 0.02f , |
||
bool | estWithNeighborsIfNull = false |
||
) |
Definition at line 942 of file util2d.cpp.
cv::Mat rtabmap::util2d::interpolate | ( | const cv::Mat & | image, |
int | factor, | ||
float | depthErrorRatio = 0.02f |
||
) |
Definition at line 1245 of file util2d.cpp.
cv::Mat rtabmap::util2d::registerDepth | ( | const cv::Mat & | depth, |
const cv::Mat & | depthK, | ||
const cv::Size & | colorSize, | ||
const cv::Mat & | colorK, | ||
const rtabmap::Transform & | transform | ||
) |
Definition at line 1357 of file util2d.cpp.
float rtabmap::util2d::sad | ( | const cv::Mat & | windowLeft, |
const cv::Mat & | windowRight | ||
) |
Definition at line 91 of file util2d.cpp.
float rtabmap::util2d::ssd | ( | const cv::Mat & | windowLeft, |
const cv::Mat & | windowRight | ||
) |
Definition at line 56 of file util2d.cpp.