#include "rtabmap/core/util2d.h"
#include <rtabmap/utilite/ULogger.h>
#include <rtabmap/utilite/UMath.h>
#include <rtabmap/utilite/UConversion.h>
#include <rtabmap/utilite/UTimer.h>
#include <rtabmap/utilite/UStl.h>
#include <rtabmap/core/util3d_transforms.h>
#include <rtabmap/core/StereoDense.h>
#include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/video/tracking.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/types_c.h>
#include <map>
#include <Eigen/Core>
Go to the source code of this file.
Classes | |
class | rtabmap::util2d::Array3D |
Namespaces | |
namespace | rtabmap |
namespace | rtabmap::util2d |
Defines | |
#define | CV_DESCALE(x, n) (((x) + (1 << ((n)-1))) >> (n)) |
Typedefs | |
typedef float | rtabmap::util2d::acctype |
typedef float | rtabmap::util2d::itemtype |
Functions | |
cv::Mat RTABMAP_EXP | rtabmap::util2d::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 | 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) |
std::vector< cv::Point2f > RTABMAP_EXP | 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) |
cv::Rect RTABMAP_EXP | rtabmap::util2d::computeRoi (const cv::Mat &image, const std::string &roiRatios) |
cv::Rect RTABMAP_EXP | rtabmap::util2d::computeRoi (const cv::Size &imageSize, const std::string &roiRatios) |
cv::Rect RTABMAP_EXP | rtabmap::util2d::computeRoi (const cv::Mat &image, const std::vector< float > &roiRatios) |
cv::Rect RTABMAP_EXP | rtabmap::util2d::computeRoi (const cv::Size &imageSize, const std::vector< float > &roiRatios) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::cvtDepthFromFloat (const cv::Mat &depth32F) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::cvtDepthToFloat (const cv::Mat &depth16U) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::decimate (const cv::Mat &image, int d) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::depthFromDisparity (const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1) |
cv::Mat RTABMAP_EXP | 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) |
cv::Mat RTABMAP_EXP | 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) |
cv::Mat RTABMAP_EXP | 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) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::disparityFromStereoImages (const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap ¶meters=ParametersMap()) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::exposureFusion (const std::vector< cv::Mat > &images) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::fastBilateralFiltering (const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::fillDepthHoles (const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f) |
void RTABMAP_EXP | rtabmap::util2d::fillRegisteredDepthHoles (cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false) |
float RTABMAP_EXP | rtabmap::util2d::getDepth (const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::interpolate (const cv::Mat &image, int factor, float depthErrorRatio=0.02f) |
cv::Mat RTABMAP_EXP | rtabmap::util2d::registerDepth (const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform) |
float RTABMAP_EXP | rtabmap::util2d::sad (const cv::Mat &windowLeft, const cv::Mat &windowRight) |
float RTABMAP_EXP | rtabmap::util2d::ssd (const cv::Mat &windowLeft, const cv::Mat &windowRight) |
#define CV_DESCALE | ( | x, | |
n | |||
) | (((x) + (1 << ((n)-1))) >> (n)) |
Definition at line 354 of file util2d.cpp.