$search
Declarations for image processing. More...
#include "tools.hpp"

Go to the source code of this file.
Classes | |
| class | cScheme |
| For configuring and applying false-colormapping or modality-fusion schemes. More... | |
Defines | |
| #define | BILATERAL_FILTERING 2 |
| #define | BLACKBODY 150 |
| #define | BLUERED 400 |
| #define | BLUERED_ALT_1 410 |
| #define | BLUERED_ALT_2 420 |
| #define | CIECOMP 100 |
| #define | CIECOMP_ALT_1 110 |
| #define | CIECOMP_ALT_2 120 |
| #define | CIECOMP_ALT_3 130 |
| #define | CUSTOM 3 |
| ID for custom mapping. | |
| #define | GAUSSIAN_FILTERING 1 |
| #define | GRAYSCALE 0 |
| #define | HIGHLIGHTED 180 |
| #define | ICE 600 |
| #define | ICE_ALT_1 610 |
| #define | ICE_ALT_2 620 |
| #define | ICE_ALT_3 630 |
| #define | ICEFIRE 800 |
| #define | ICEFIRE_ALT_1 810 |
| #define | ICEFIRE_ALT_2 820 |
| #define | ICEFIRE_ALT_3 830 |
| #define | ICEIRON 700 |
| #define | ICEIRON_ALT_1 710 |
| #define | ICEIRON_ALT_2 720 |
| #define | IRON 300 |
| #define | IRON_ALT_1 310 |
| #define | IRON_ALT_2 320 |
| #define | IRON_ALT_3 330 |
| #define | JET 500 |
| #define | JET_ALT_1 510 |
| #define | MAP_LENGTH 1024 |
| #define | MIN_PROP_THRESHOLD 0.002 |
| #define | NO_FILTERING 0 |
| #define | NORMALIZATION_ADAPTIVE 3 |
| #define | NORMALIZATION_CENTRALIZED 4 |
| #define | NORMALIZATION_CLAHE 2 |
| #define | NORMALIZATION_EQUALIZE 1 |
| #define | NORMALIZATION_EXPANDED 5 |
| #define | NORMALIZATION_STANDARD 0 |
| #define | RAINBOW 200 |
| #define | RAINBOW_ALT_1 210 |
| #define | RAINBOW_ALT_2 220 |
| #define | RAINBOW_ALT_3 230 |
| #define | RAINBOW_ALT_4 240 |
| #define | REPEATED 900 |
| #define | REPEATED_ALT_1 910 |
| #define | REPEATED_ALT_2 920 |
| #define | REPEATED_ALT_3 930 |
| #define | REPEATED_ALT_4 940 |
| #define | REPEATED_ALT_5 950 |
| #define | REPEATED_ALT_6 960 |
Functions | |
| void | adaptiveDownsample (const Mat &src, Mat &dst, int code=NORMALIZATION_STANDARD, double factor=0.0) |
| void | addBorder (Mat &inputMat, int borderSize) |
| void | applyFilter (const Mat &src, Mat &dst, int filter=NO_FILTERING, double param=2.0) |
| 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< cv::Point > contour, double &width, double &height) |
| Determine the width and height of a contour (in x and y directions at this stage). | |
| void | convertVectorToPoint (vector< Point2f > &input, vector< cv::Point > &output) |
| Convert a vector from 'Point2f' format to 'Point' format. | |
| void | convertVectorToPoint2f (vector< cv::Point > &input, vector< Point2f > &output) |
| Convert a vector from 'Point' format to 'Point2f' format. | |
| void | copyContour (vector< cv::Point > &src, vector< cv::Point > &dst) |
| Makes a copy of a contour. | |
| void | createGaussianMatrix (Mat &gaussianMat, double sigmaFactor) |
| Creates a gaussian intensity distribution in a given matrix. | |
| void | cropImage (Mat &image, cv::Point tl, cv::Point br) |
| Very basic image cropping. | |
| double | distBetweenPts (cv::Point &P1, cv::Point &P2) |
| Calculates the distance between two "Point" points. | |
| 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=0) |
| 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) |
| cv::Point | findCentroid (vector< cv::Point > &contour) |
| Finds centroid of a contour. | |
| Point2f | findCentroid2f (vector< cv::Point > &contour) |
| Finds centroid of a 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=-1.0, double dblmax=-1.0) |
| 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=NORMALIZATION_STANDARD, double factor=0.0) |
| cv::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) |
Declarations for image processing.
Definition in file improc.hpp.
| #define BILATERAL_FILTERING 2 |
Definition at line 82 of file improc.hpp.
| #define BLACKBODY 150 |
Definition at line 29 of file improc.hpp.
| #define BLUERED 400 |
Definition at line 44 of file improc.hpp.
| #define BLUERED_ALT_1 410 |
Definition at line 45 of file improc.hpp.
| #define BLUERED_ALT_2 420 |
Definition at line 46 of file improc.hpp.
| #define CIECOMP 100 |
Definition at line 24 of file improc.hpp.
| #define CIECOMP_ALT_1 110 |
Definition at line 25 of file improc.hpp.
| #define CIECOMP_ALT_2 120 |
Definition at line 26 of file improc.hpp.
| #define CIECOMP_ALT_3 130 |
Definition at line 27 of file improc.hpp.
| #define CUSTOM 3 |
ID for custom mapping.
Definition at line 19 of file improc.hpp.
| #define GAUSSIAN_FILTERING 1 |
Definition at line 81 of file improc.hpp.
| #define GRAYSCALE 0 |
Definition at line 22 of file improc.hpp.
| #define HIGHLIGHTED 180 |
Definition at line 31 of file improc.hpp.
| #define ICE 600 |
Definition at line 51 of file improc.hpp.
| #define ICE_ALT_1 610 |
Definition at line 52 of file improc.hpp.
| #define ICE_ALT_2 620 |
Definition at line 53 of file improc.hpp.
| #define ICE_ALT_3 630 |
Definition at line 54 of file improc.hpp.
| #define ICEFIRE 800 |
Definition at line 60 of file improc.hpp.
| #define ICEFIRE_ALT_1 810 |
Definition at line 61 of file improc.hpp.
| #define ICEFIRE_ALT_2 820 |
Definition at line 62 of file improc.hpp.
| #define ICEFIRE_ALT_3 830 |
Definition at line 63 of file improc.hpp.
| #define ICEIRON 700 |
Definition at line 56 of file improc.hpp.
| #define ICEIRON_ALT_1 710 |
Definition at line 57 of file improc.hpp.
| #define ICEIRON_ALT_2 720 |
Definition at line 58 of file improc.hpp.
| #define IRON 300 |
Definition at line 39 of file improc.hpp.
| #define IRON_ALT_1 310 |
Definition at line 40 of file improc.hpp.
| #define IRON_ALT_2 320 |
Definition at line 41 of file improc.hpp.
| #define IRON_ALT_3 330 |
Definition at line 42 of file improc.hpp.
| #define JET 500 |
Definition at line 48 of file improc.hpp.
| #define JET_ALT_1 510 |
Definition at line 49 of file improc.hpp.
| #define MAP_LENGTH 1024 |
Definition at line 20 of file improc.hpp.
| #define MIN_PROP_THRESHOLD 0.002 |
Definition at line 84 of file improc.hpp.
| #define NO_FILTERING 0 |
Definition at line 80 of file improc.hpp.
| #define NORMALIZATION_ADAPTIVE 3 |
Definition at line 76 of file improc.hpp.
| #define NORMALIZATION_CENTRALIZED 4 |
Definition at line 77 of file improc.hpp.
| #define NORMALIZATION_CLAHE 2 |
Definition at line 75 of file improc.hpp.
| #define NORMALIZATION_EQUALIZE 1 |
Definition at line 74 of file improc.hpp.
| #define NORMALIZATION_EXPANDED 5 |
Definition at line 78 of file improc.hpp.
| #define NORMALIZATION_STANDARD 0 |
Definition at line 73 of file improc.hpp.
| #define RAINBOW 200 |
Definition at line 33 of file improc.hpp.
| #define RAINBOW_ALT_1 210 |
Definition at line 34 of file improc.hpp.
| #define RAINBOW_ALT_2 220 |
Definition at line 35 of file improc.hpp.
| #define RAINBOW_ALT_3 230 |
Definition at line 36 of file improc.hpp.
| #define RAINBOW_ALT_4 240 |
Definition at line 37 of file improc.hpp.
| #define REPEATED 900 |
Definition at line 65 of file improc.hpp.
| #define REPEATED_ALT_1 910 |
Definition at line 66 of file improc.hpp.
| #define REPEATED_ALT_2 920 |
Definition at line 67 of file improc.hpp.
| #define REPEATED_ALT_3 930 |
Definition at line 68 of file improc.hpp.
| #define REPEATED_ALT_4 940 |
Definition at line 69 of file improc.hpp.
| #define REPEATED_ALT_5 950 |
Definition at line 70 of file improc.hpp.
| #define REPEATED_ALT_6 960 |
Definition at line 71 of file improc.hpp.
| void adaptiveDownsample | ( | const Mat & | src, | |
| Mat & | dst, | |||
| int | code = NORMALIZATION_STANDARD, |
|||
| double | factor = 0.0 | |||
| ) |
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 = NO_FILTERING, |
|||
| double | param = 2.0 | |||
| ) |
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< cv::Point > | contour, | |
| double & | width, | |||
| double & | height | |||
| ) |
Determine the width and height of a contour (in x and y directions at this stage).
| void convertVectorToPoint | ( | vector< Point2f > & | input, | |
| vector< cv::Point > & | output | |||
| ) |
Convert a vector from 'Point2f' format to 'Point' format.
| void convertVectorToPoint2f | ( | vector< cv::Point > & | input, | |
| vector< Point2f > & | output | |||
| ) |
Convert a vector from 'Point' format to 'Point2f' format.
| void copyContour | ( | vector< cv::Point > & | src, | |
| vector< cv::Point > & | dst | |||
| ) |
Makes a copy of a contour.
| void createGaussianMatrix | ( | Mat & | gaussianMat, | |
| double | sigmaFactor | |||
| ) |
Creates a gaussian intensity distribution in a given matrix.
Definition at line 769 of file improc.cpp.
| void cropImage | ( | Mat & | image, | |
| cv::Point | tl, | |||
| cv::Point | br | |||
| ) |
Very basic image cropping.
| double distBetweenPts | ( | cv::Point & | P1, | |
| cv::Point & | P2 | |||
| ) |
Calculates the distance between two "Point" points.
| 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 = 0 | |||
| ) |
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.
| cv::Point findCentroid | ( | vector< cv::Point > & | contour | ) |
Finds centroid of a contour.
| Point2f findCentroid2f | ( | vector< cv::Point > & | contour | ) |
Finds centroid of a contour.
| 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 = -1.0, |
|||
| double | dblmax = -1.0 | |||
| ) |
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 = NORMALIZATION_STANDARD, |
|||
| double | factor = 0.0 | |||
| ) |
Definition at line 579 of file improc.cpp.
| cv::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.