Classes | Typedefs | Functions
rtabmap::util2d Namespace Reference

Classes

class  Array3D
 

Typedefs

typedef float acctype
 
typedef float itemtype
 

Functions

cv::Mat RTABMAP_CORE_EXPORT 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_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)
 
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)
 
cv::Rect RTABMAP_CORE_EXPORT computeRoi (const cv::Mat &image, const std::string &roiRatios)
 
cv::Rect RTABMAP_CORE_EXPORT computeRoi (const cv::Mat &image, const std::vector< float > &roiRatios)
 
cv::Rect RTABMAP_CORE_EXPORT computeRoi (const cv::Size &imageSize, const std::string &roiRatios)
 
cv::Rect RTABMAP_CORE_EXPORT computeRoi (const cv::Size &imageSize, const std::vector< float > &roiRatios)
 
cv::Mat RTABMAP_CORE_EXPORT cvtDepthFromFloat (const cv::Mat &depth32F)
 
cv::Mat RTABMAP_CORE_EXPORT cvtDepthToFloat (const cv::Mat &depth16U)
 
cv::Mat RTABMAP_CORE_EXPORT decimate (const cv::Mat &image, int d)
 
cv::Mat RTABMAP_CORE_EXPORT depthFromDisparity (const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
 
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)
 
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)
 
cv::Mat RTABMAP_CORE_EXPORT disparityFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap &parameters=ParametersMap())
 
cv::Mat RTABMAP_CORE_EXPORT exposureFusion (const std::vector< cv::Mat > &images)
 
cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering (const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
 
cv::Mat RTABMAP_CORE_EXPORT fillDepthHoles (const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
 
void RTABMAP_CORE_EXPORT fillRegisteredDepthHoles (cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false)
 
float RTABMAP_CORE_EXPORT getDepth (const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
 
void RTABMAP_CORE_EXPORT HSVtoRGB (float *r, float *g, float *b, float h, float s, float v)
 
cv::Mat RTABMAP_CORE_EXPORT interpolate (const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
 
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)
 
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)
 
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. More...
 
float RTABMAP_CORE_EXPORT sad (const cv::Mat &windowLeft, const cv::Mat &windowRight)
 
std::vector< int > RTABMAP_CORE_EXPORT SSC (const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, float tolerance, int cols, int rows)
 
float RTABMAP_CORE_EXPORT ssd (const cv::Mat &windowLeft, const cv::Mat &windowRight)
 

Typedef Documentation

◆ acctype

Definition at line 356 of file util2d.cpp.

◆ itemtype

Definition at line 357 of file util2d.cpp.

Function Documentation

◆ brightnessAndContrastAuto()

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.

◆ calcOpticalFlowPyrLKStereo()

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.

◆ calcStereoCorrespondences()

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.

◆ computeRoi() [1/4]

cv::Rect rtabmap::util2d::computeRoi ( const cv::Mat image,
const std::string roiRatios 
)

Definition at line 1113 of file util2d.cpp.

◆ computeRoi() [2/4]

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

Definition at line 1150 of file util2d.cpp.

◆ computeRoi() [3/4]

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

Definition at line 1118 of file util2d.cpp.

◆ computeRoi() [4/4]

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

Definition at line 1155 of file util2d.cpp.

◆ cvtDepthFromFloat()

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

Definition at line 892 of file util2d.cpp.

◆ cvtDepthToFloat()

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

Definition at line 928 of file util2d.cpp.

◆ decimate()

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

Definition at line 1201 of file util2d.cpp.

◆ depthFromDisparity()

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.

◆ depthFromStereoCorrespondences()

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.

◆ depthFromStereoImages()

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.

◆ disparityFromStereoCorrespondences()

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.

◆ disparityFromStereoImages()

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.

◆ exposureFusion()

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

Definition at line 2027 of file util2d.cpp.

◆ fastBilateralFiltering()

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.

◆ fillDepthHoles()

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

Definition at line 1439 of file util2d.cpp.

◆ fillRegisteredDepthHoles()

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

Definition at line 1598 of file util2d.cpp.

◆ getDepth()

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.

◆ HSVtoRGB()

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

Definition at line 2047 of file util2d.cpp.

◆ interpolate()

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

Definition at line 1250 of file util2d.cpp.

◆ NMS()

void rtabmap::util2d::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 at line 2096 of file util2d.cpp.

◆ registerDepth()

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.

◆ rotateImagesUpsideUpIfNecessary()

void rtabmap::util2d::rotateImagesUpsideUpIfNecessary ( CameraModel model,
cv::Mat rgb,
cv::Mat depth 
)

Rotate images and camera model so that the top of the image is up.

The roll value of local transform of the camera model is used to estimate if the images have to be rotated. If there is a pitch value higher than 45 deg, the original images and camera model will be returned (no rotation will happen). The return local transform of the camera model is updated accordingly. The distortion model is ignored and won't be transfered to modified camera model, so this function expects already rectified images.

Parameters
modela valid camera model
rgba rgb/grayscale image (set cv::Mat() if not used)
deptha depth image (set cv::Mat() if not used)

Definition at line 2282 of file util2d.cpp.

◆ sad()

float rtabmap::util2d::sad ( const cv::Mat windowLeft,
const cv::Mat windowRight 
)

Definition at line 91 of file util2d.cpp.

◆ SSC()

std::vector< int > rtabmap::util2d::SSC ( const std::vector< cv::KeyPoint > &  keypoints,
int  maxKeypoints,
float  tolerance,
int  cols,
int  rows 
)

Definition at line 2205 of file util2d.cpp.

◆ ssd()

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 Jul 1 2024 02:42:45