$search
Definitions for image processing. More...
#include "flags.hpp"
#include "improc.hpp"
Go to the source code of this file.
Functions | |
void | adaptiveDownsample (const Mat &src, Mat &dst, int code, double factor) |
void | addBorder (Mat &inputMat, int borderSize) |
void | applyFilter (const Mat &src, Mat &dst, int filter, double param) |
void | applyIntensityShift (const Mat &src1, Mat &dst1, const Mat &src2, Mat &dst2, double grad, double shift) |
bool | checkIfActuallyGray (const Mat &im) |
void | clusterRectangles (vector< Rect > &rectangles, double minOverlap) |
void | contourDimensions (vector< Point > contour, double &width, double &height) |
void | convertVectorToPoint (vector< Point2f > &input, vector< Point > &output) |
void | convertVectorToPoint2f (vector< Point > &input, vector< Point2f > &output) |
void | copyContour (vector< Point > &src, vector< Point > &dst) |
void | createGaussianMatrix (Mat &gaussianMat, double sigmaFactor) |
Creates a gaussian intensity distribution in a given matrix. | |
void | cropImage (Mat &image, Point tl, Point br) |
double | distBetweenPts (Point &P1, Point &P2) |
double | distBetweenPts2f (Point2f &P1, Point2f &P2) |
Calculates the distance between two "Point2f" points. | |
void | down_level (Mat &dst, Mat &src) |
16-bit to 8-bit | |
void | downsampleCLAHE (const Mat &src, Mat &dst, double factor) |
void | drawGrid (const Mat &src, Mat &dst, int mode) |
void | drawLinesBetweenPoints (Mat &image, const vector< Point2f > &src, const vector< Point2f > &dst) |
Draws lines between initial and corrected points. | |
double | findBestAlpha (const Mat &K, const Mat &coeff, const Size &camSize) |
Point | findCentroid (vector< Point > &contour) |
Point2f | findCentroid2f (vector< Point > &contour) |
void | findIntensityValues (double *vals, Mat &im, Mat &mask) |
double | findMinimumSeparation (vector< Point2f > &pts) |
Finds the minimum separation between any two points in a set. | |
void | findPercentiles (const Mat &img, double *vals, double *percentiles, unsigned int num) |
void | fix_bottom_right (Mat &mat) |
void | fixedDownsample (const Mat &src, Mat &dst, double center, double range) |
void | generateHistogram (Mat &src, Mat &dst, double *im_hist, double *im_summ, double *im_stat) |
Obtains histogram and other image statistics. | |
void | histExpand8 (const Mat &src, Mat &dst) |
void | invertMatIntensities (const Mat &src, Mat &dst) |
Inverts the pixel intensities of a matrix. | |
Point2f | meanPoint (Point2f &P1, Point2f &P2) |
Generates a point that's half way in between the two input points. | |
Rect | meanRectangle (vector< Rect > &rectangles) |
void | mixImages (Mat &dst, cv::vector< Mat > &images) |
void | normalize_16 (Mat &dst, const Mat &src, double dblmin, double dblmax) |
Stretches the histogram to span the whole 16-bit scale (16-bit to 16-bit). | |
void | normalize_64_vec (Mat &dst, Mat &src) |
Mat | normForDisplay (Mat origMat) |
void | obtainColorRepresentation (Mat &src, Mat &dst) |
void | obtainEightBitRepresentation (Mat &src, Mat &dst) |
double | perpDist (Point2f &P1, Point2f &P2, Point2f &P3) |
Calculates the perpindicular distance between a line (P1 to P2) and a point (P3). | |
void | process8bitImage (const Mat &src, Mat &dst, int code, double factor) |
Point | rectangle_center (cv::Rect input) |
bool | rectangle_contains_centroid (cv::Rect mainRectangle, cv::Rect innerRectangle) |
double | rectangleOverlap (Rect rectangle1, Rect rectangle2) |
void | reduceToPureImage (cv::Mat &dst, cv::Mat &src) |
void | shiftIntensities (Mat &im, double scaler, double shifter, double downer) |
void | simpleResize (Mat &src, Mat &dst, Size size) |
Resizes an image without interpolation. | |
void | splitMultimodalImage (const Mat &src, Mat &therm, Mat &vis) |
void | straightCLAHE (const Mat &src, Mat &dst, double factor) |
void | swapElements (vector< Point2f > &corners, int index1, int index2) |
Swaps the position of two elements in a point vector. | |
void | transferElement (vector< Point2f > &dst, vector< Point2f > &src, int index) |
Move a point from one vector to another, resize and shift old vector. | |
void | trimToDimensions (Mat &image, int width, int height) |
Trims the top/bottom or sides of the image to get the correct ratio. | |
void | unpackTo8bit3Channel (const Mat &src, Mat &dst) |
Stores a 16-bit monochrome image in the first 2 channels of a CV_8UC3 mat. | |
void | weightedMixture (Mat &dst, const cv::vector< Mat > &srcs, const std::vector< double > &weightings) |
Definitions for image processing.
Definition in file improc.cpp.
void adaptiveDownsample | ( | const Mat & | src, | |
Mat & | dst, | |||
int | code, | |||
double | factor | |||
) |
Definition at line 595 of file improc.cpp.
void addBorder | ( | Mat & | inputMat, | |
int | borderSize | |||
) |
Definition at line 1489 of file improc.cpp.
void applyFilter | ( | const Mat & | src, | |
Mat & | dst, | |||
int | filter, | |||
double | param | |||
) |
Definition at line 100 of file improc.cpp.
void applyIntensityShift | ( | const Mat & | src1, | |
Mat & | dst1, | |||
const Mat & | src2, | |||
Mat & | dst2, | |||
double | grad, | |||
double | shift | |||
) |
Definition at line 215 of file improc.cpp.
bool checkIfActuallyGray | ( | const Mat & | im | ) |
Definition at line 1197 of file improc.cpp.
void clusterRectangles | ( | vector< Rect > & | rectangles, | |
double | minOverlap | |||
) |
Definition at line 308 of file improc.cpp.
void contourDimensions | ( | vector< Point > | contour, | |
double & | width, | |||
double & | height | |||
) |
Definition at line 1052 of file improc.cpp.
void convertVectorToPoint | ( | vector< Point2f > & | input, | |
vector< Point > & | output | |||
) |
Definition at line 932 of file improc.cpp.
void convertVectorToPoint2f | ( | vector< Point > & | input, | |
vector< Point2f > & | output | |||
) |
Definition at line 942 of file improc.cpp.
Definition at line 981 of file improc.cpp.
void createGaussianMatrix | ( | Mat & | gaussianMat, | |
double | sigmaFactor | |||
) |
Creates a gaussian intensity distribution in a given matrix.
Definition at line 769 of file improc.cpp.
Definition at line 853 of file improc.cpp.
Definition at line 717 of file improc.cpp.
double distBetweenPts2f | ( | Point2f & | P1, | |
Point2f & | P2 | |||
) |
Calculates the distance between two "Point2f" points.
Definition at line 706 of file improc.cpp.
void down_level | ( | Mat & | dst, | |
Mat & | src | |||
) |
16-bit to 8-bit
Definition at line 1441 of file improc.cpp.
void downsampleCLAHE | ( | const Mat & | src, | |
Mat & | dst, | |||
double | factor | |||
) |
Definition at line 152 of file improc.cpp.
void drawGrid | ( | const Mat & | src, | |
Mat & | dst, | |||
int | mode | |||
) |
Definition at line 248 of file improc.cpp.
void drawLinesBetweenPoints | ( | Mat & | image, | |
const vector< Point2f > & | src, | |||
const vector< Point2f > & | dst | |||
) |
Draws lines between initial and corrected points.
Definition at line 727 of file improc.cpp.
double findBestAlpha | ( | const Mat & | K, | |
const Mat & | coeff, | |||
const Size & | camSize | |||
) |
Definition at line 32 of file improc.cpp.
Definition at line 743 of file improc.cpp.
Point2f findCentroid2f | ( | vector< Point > & | contour | ) |
Definition at line 756 of file improc.cpp.
void findIntensityValues | ( | double * | vals, | |
Mat & | im, | |||
Mat & | mask | |||
) |
Definition at line 1303 of file improc.cpp.
double findMinimumSeparation | ( | vector< Point2f > & | pts | ) |
Finds the minimum separation between any two points in a set.
Definition at line 1152 of file improc.cpp.
void findPercentiles | ( | const Mat & | img, | |
double * | vals, | |||
double * | percentiles, | |||
unsigned int | num | |||
) |
Definition at line 1219 of file improc.cpp.
void fix_bottom_right | ( | Mat & | mat | ) |
Definition at line 1434 of file improc.cpp.
void fixedDownsample | ( | const Mat & | src, | |
Mat & | dst, | |||
double | center, | |||
double | range | |||
) |
Definition at line 200 of file improc.cpp.
void generateHistogram | ( | Mat & | src, | |
Mat & | dst, | |||
double * | im_hist, | |||
double * | im_summ, | |||
double * | im_stat | |||
) |
Obtains histogram and other image statistics.
Definition at line 2835 of file improc.cpp.
void histExpand8 | ( | const Mat & | src, | |
Mat & | dst | |||
) |
Definition at line 289 of file improc.cpp.
void invertMatIntensities | ( | const Mat & | src, | |
Mat & | dst | |||
) |
Inverts the pixel intensities of a matrix.
Definition at line 1006 of file improc.cpp.
Point2f meanPoint | ( | Point2f & | P1, | |
Point2f & | P2 | |||
) |
Generates a point that's half way in between the two input points.
Definition at line 1172 of file improc.cpp.
Rect meanRectangle | ( | vector< Rect > & | rectangles | ) |
Definition at line 365 of file improc.cpp.
void mixImages | ( | Mat & | dst, | |
cv::vector< Mat > & | images | |||
) |
Definition at line 427 of file improc.cpp.
void normalize_16 | ( | Mat & | dst, | |
const Mat & | src, | |||
double | dblmin, | |||
double | dblmax | |||
) |
Stretches the histogram to span the whole 16-bit scale (16-bit to 16-bit).
Definition at line 1537 of file improc.cpp.
void normalize_64_vec | ( | Mat & | dst, | |
Mat & | src | |||
) |
Definition at line 1502 of file improc.cpp.
Mat normForDisplay | ( | Mat | origMat | ) |
Definition at line 2982 of file improc.cpp.
void obtainColorRepresentation | ( | Mat & | src, | |
Mat & | dst | |||
) |
Definition at line 1411 of file improc.cpp.
void obtainEightBitRepresentation | ( | Mat & | src, | |
Mat & | dst | |||
) |
Definition at line 1390 of file improc.cpp.
double perpDist | ( | Point2f & | P1, | |
Point2f & | P2, | |||
Point2f & | P3 | |||
) |
Calculates the perpindicular distance between a line (P1 to P2) and a point (P3).
Definition at line 1126 of file improc.cpp.
void process8bitImage | ( | const Mat & | src, | |
Mat & | dst, | |||
int | code, | |||
double | factor | |||
) |
Definition at line 579 of file improc.cpp.
Point rectangle_center | ( | cv::Rect | input | ) |
Definition at line 472 of file improc.cpp.
bool rectangle_contains_centroid | ( | cv::Rect | mainRectangle, | |
cv::Rect | innerRectangle | |||
) |
Definition at line 461 of file improc.cpp.
double rectangleOverlap | ( | Rect | rectangle1, | |
Rect | rectangle2 | |||
) |
Definition at line 482 of file improc.cpp.
void reduceToPureImage | ( | cv::Mat & | dst, | |
cv::Mat & | src | |||
) |
Definition at line 1455 of file improc.cpp.
void shiftIntensities | ( | Mat & | im, | |
double | scaler, | |||
double | shifter, | |||
double | downer | |||
) |
Definition at line 1282 of file improc.cpp.
void simpleResize | ( | Mat & | src, | |
Mat & | dst, | |||
Size | size | |||
) |
Resizes an image without interpolation.
Definition at line 955 of file improc.cpp.
void splitMultimodalImage | ( | const Mat & | src, | |
Mat & | therm, | |||
Mat & | vis | |||
) |
Definition at line 85 of file improc.cpp.
void straightCLAHE | ( | const Mat & | src, | |
Mat & | dst, | |||
double | factor | |||
) |
Definition at line 126 of file improc.cpp.
void swapElements | ( | vector< Point2f > & | corners, | |
int | index1, | |||
int | index2 | |||
) |
Swaps the position of two elements in a point vector.
Definition at line 994 of file improc.cpp.
void transferElement | ( | vector< Point2f > & | dst, | |
vector< Point2f > & | src, | |||
int | index | |||
) |
Move a point from one vector to another, resize and shift old vector.
Definition at line 1177 of file improc.cpp.
void trimToDimensions | ( | Mat & | image, | |
int | width, | |||
int | height | |||
) |
Trims the top/bottom or sides of the image to get the correct ratio.
Definition at line 506 of file improc.cpp.
void unpackTo8bit3Channel | ( | const Mat & | src, | |
Mat & | dst | |||
) |
Stores a 16-bit monochrome image in the first 2 channels of a CV_8UC3 mat.
Definition at line 8 of file improc.cpp.
void weightedMixture | ( | Mat & | dst, | |
const cv::vector< Mat > & | srcs, | |||
const std::vector< double > & | weightings | |||
) |
Definition at line 387 of file improc.cpp.