Classes | Typedefs | Functions
rtabmap::util2d Namespace Reference

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, float *alphaOut, float *betaOut)
 Automatic brightness and contrast optimization with optional histogram clipping. More...
 
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 &parameters=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)
 
void RTABMAP_EXP HSVtoRGB (float *r, float *g, float *b, float h, float s, float v)
 
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 Documentation

typedef float rtabmap::util2d::acctype

Definition at line 356 of file util2d.cpp.

Definition at line 357 of file util2d.cpp.

Function Documentation

cv::Mat rtabmap::util2d::brightnessAndContrastAuto ( const cv::Mat &  src,
const cv::Mat &  mask,
float  clipLowHistPercent,
float  clipHighHistPercent,
float *  alphaOut,
float *  betaOut 
)

Automatic brightness and contrast optimization with optional histogram clipping.

Parameters
[in]

Definition at line 1942 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 371 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 1113 of file util2d.cpp.

cv::Rect rtabmap::util2d::computeRoi ( const cv::Size &  imageSize,
const std::string &  roiRatios 
)

Definition at line 1118 of file util2d.cpp.

cv::Rect rtabmap::util2d::computeRoi ( const cv::Mat &  image,
const std::vector< float > &  roiRatios 
)

Definition at line 1150 of file util2d.cpp.

cv::Rect rtabmap::util2d::computeRoi ( const cv::Size &  imageSize,
const std::vector< float > &  roiRatios 
)

Definition at line 1155 of file util2d.cpp.

cv::Mat rtabmap::util2d::cvtDepthFromFloat ( const cv::Mat &  depth32F)

Definition at line 892 of file util2d.cpp.

cv::Mat rtabmap::util2d::cvtDepthToFloat ( const cv::Mat &  depth16U)

Definition at line 928 of file util2d.cpp.

cv::Mat rtabmap::util2d::decimate ( const cv::Mat &  image,
int  d 
)

Definition at line 1201 of file util2d.cpp.

cv::Mat rtabmap::util2d::depthFromDisparity ( const cv::Mat &  disparity,
float  fx,
float  baseline,
int  type = CV_32FC1 
)

Definition at line 763 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 867 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 808 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 845 of file util2d.cpp.

cv::Mat rtabmap::util2d::disparityFromStereoImages ( const cv::Mat &  leftImage,
const cv::Mat &  rightImage,
const ParametersMap parameters = ParametersMap() 
)

Definition at line 738 of file util2d.cpp.

cv::Mat rtabmap::util2d::exposureFusion ( const std::vector< cv::Mat > &  images)

Definition at line 2027 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 1814 of file util2d.cpp.

cv::Mat rtabmap::util2d::fillDepthHoles ( const cv::Mat &  depth,
int  maximumHoleSize = 1,
float  errorRatio = 0.02f 
)

Definition at line 1439 of file util2d.cpp.

void rtabmap::util2d::fillRegisteredDepthHoles ( cv::Mat &  depthRegistered,
bool  vertical,
bool  horizontal,
bool  fillDoubleHoles = false 
)

Definition at line 1598 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 947 of file util2d.cpp.

void rtabmap::util2d::HSVtoRGB ( float *  r,
float *  g,
float *  b,
float  h,
float  s,
float  v 
)

Definition at line 2047 of file util2d.cpp.

cv::Mat rtabmap::util2d::interpolate ( const cv::Mat &  image,
int  factor,
float  depthErrorRatio = 0.02f 
)

Definition at line 1250 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 1362 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.



rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:09