#include "cob_common/cob_vision_utils/common/include/cob_vision_utils/GlobalDefines.h"
#include <cv.h>
#include "opencv2/core/core_c.h"
#include "opencv2/core/core.hpp"
#include "opencv2/imgproc/imgproc_c.h"
#include "opencv2/imgproc/imgproc.hpp"
#include "opencv2/video/tracking.hpp"
#include "opencv2/features2d/features2d.hpp"
#include "opencv2/flann/flann.hpp"
#include "opencv2/calib3d/calib3d.hpp"
#include "opencv2/objdetect/objdetect.hpp"
#include "opencv2/imgproc/types_c.h"
#include <math.h>
#include <string.h>
#include <iostream>
Go to the source code of this file.
Namespaces | |
namespace | ipa_Utils |
Functions | |
unsigned long | ipa_Utils::ConvertToShowImage (const cv::Mat &source, cv::Mat &dest, int channel=1, double min=-1, double max=-1) |
unsigned long | ipa_Utils::EvaluatePolynomial (double x, int degree, double *coefficients, double *y) |
unsigned long | ipa_Utils::FilterByAmplitude (cv::Mat &xyzImage, const cv::Mat &greyImage, cv::Mat *mask, cv::Mat *maskColor, float minMaskThresh, float maxMaskThresh) |
unsigned long | ipa_Utils::FilterSpeckles (cv::Mat &img, int maxSpeckleSize, double _maxDiff, cv::Mat &_buf) |
Description. | |
unsigned long | ipa_Utils::FilterTearOffEdges (cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6) |
cv::Mat | ipa_Utils::GetColorcoded (const cv::Mat &img_32F, double min, double max) |
cv::Mat | ipa_Utils::GetColorcoded (const cv::Mat &img_32F) |
cv::Vec3f | ipa_Utils::GrayColorMap (double value, double min, double max) |
void | ipa_Utils::InitUndistortMap (const cv::Mat &A, const cv::Mat &dist_coeffs, cv::Mat &mapxarr, cv::Mat &mapyarr) |
Function to replace the buggy OpenCV 1.1 function. | |
unsigned long | ipa_Utils::LoadMat (cv::Mat &mat, std::string filename) |
unsigned long | ipa_Utils::MaskImage (const cv::Mat &source, cv::Mat &dest, const cv::Mat &mask, cv::Mat &destMask, float minMaskThresh=0, float maxMaskTresh=20000, int sourceChannel=1, double sourceMin=-1, double sourceMax=-1) |
unsigned long | ipa_Utils::SaveMat (cv::Mat &mat, std::string filename) |
cv::Mat | ipa_Utils::vstack (const std::vector< cv::Mat > &mats) |
Utility functions for Fraunhofer IPA vision library.
Definition in file VisionUtils.h.