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 | CIELUV 140 |
#define | CUSTOM 3 |
ID for custom mapping. | |
#define | DEFAULT_LOWER_VISIBLE_FUSION_LIMIT 0.2 |
#define | DEFAULT_UPPER_VISIBLE_FUSION_LIMIT 0.8 |
#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_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 cv::Mat &src, cv::Mat &dst, int code=NORMALIZATION_STANDARD, double factor=0.0) |
void | addBorder (cv::Mat &inputMat, int borderSize) |
void | applyFilter (const cv::Mat &src, cv::Mat &dst, int filter=NO_FILTERING, double param=2.0) |
void | applyIntensityShift (const cv::Mat &src1, cv::Mat &dst1, const cv::Mat &src2, cv::Mat &dst2, double grad, double shift) |
bool | checkIfActuallyGray (const cv::Mat &im) |
void | clusterRectangles (vector< cv::Rect > &rectangles, double minOverlap) |
void | combineImages (const cv::Mat &im1, const cv::Mat &im2, cv::Mat &dst) |
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 | convert16bitTo8bitConfidence (const cv::Mat &src, const cv::Mat &conf, cv::Mat &dst) |
Converts a 16-bit matrix to a 3 channel 8 bit matrix, with the third channel assigned confidence values. | |
void | convertToTemperatureMat (const cv::Mat &src, cv::Mat &dst) |
Converts a 16-bit image encoding temperature into floating point format. | |
void | convertVectorToPoint (vector< cv::Point2f > &input, vector< cv::Point > &output) |
Convert a vector from 'Point2f' format to 'Point' format. | |
void | convertVectorToPoint2f (vector< cv::Point > &input, vector< cv::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 (cv::Mat &gaussianMat, double sigmaFactor=1.0) |
Creates a gaussian intensity distribution in a given matrix. | |
void | cropImage (cv::Mat &image, cv::Point tl, cv::Point br) |
Very basic image cropping. | |
void | down_level (cv::Mat &dst, cv::Mat &src) |
16-bit to 8-bit | |
void | drawGrid (const cv::Mat &src, cv::Mat &dst, int mode=0) |
void | drawLinesBetweenPoints (cv::Mat &image, const vector< cv::Point2f > &src, const vector< cv::Point2f > &dst) |
Draws lines between initial and corrected points. | |
double | findBestAlpha (const cv::Mat &K, const cv::Mat &coeff, const cv::Size &camSize) |
cv::Point | findCentroid (vector< cv::Point > &contour) |
Finds centroid of a contour. | |
cv::Point2f | findCentroid2f (vector< cv::Point > &contour) |
Finds centroid of a contour. | |
void | findIntensityValues (double *vals, cv::Mat &im, cv::Mat &mask) |
void | findPercentiles (const cv::Mat &img, double *vals, double *percentiles, unsigned int num) |
void | fix_bottom_right (cv::Mat &mat) |
void | fixedDownsample (const cv::Mat &src, cv::Mat &dst, double center, double range) |
void | generateHistogram (cv::Mat &src, cv::Mat &dst, double *im_hist, double *im_summ, double *im_stat) |
Obtains histogram and other image statistics. | |
void | histExpand8 (const cv::Mat &src, cv::Mat &dst) |
void | invertMatIntensities (const cv::Mat &src, cv::Mat &dst) |
Inverts the pixel intensities of a matrix. | |
cv::Rect | meanRectangle (vector< cv::Rect > &rectangles) |
void | mixImages (cv::Mat &dst, cv::vector< cv::Mat > &images) |
void | normalize_16 (cv::Mat &dst, const cv::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 (cv::Mat &dst, cv::Mat &src) |
cv::Mat | normForDisplay (cv::Mat origMat) |
void | obtainColorRepresentation (cv::Mat &src, cv::Mat &dst) |
void | obtainEightBitRepresentation (cv::Mat &src, cv::Mat &dst) |
void | process8bitImage (const cv::Mat &src, cv::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 (cv::Rect rectangle1, cv::Rect rectangle2) |
void | reduceToPureImage (cv::Mat &dst, cv::Mat &src) |
double | scoreColorImage (const cv::Mat &src) |
Returns a score which reflects the information content of the image for visualization. | |
double | scoreThermalImage (const cv::Mat &src) |
Returns a score which reflects the information content of the image for visualization. | |
void | shiftIntensities (cv::Mat &im, double scaler, double shifter, double downer) |
void | simpleResize (cv::Mat &src, cv::Mat &dst, cv::Size size) |
Resizes an image without interpolation. | |
void | splitMultimodalImage (const cv::Mat &src, cv::Mat &therm, cv::Mat &vis) |
void | swapElements (vector< cv::Point2f > &corners, int index1, int index2) |
Swaps the position of two elements in a point vector. | |
void | temperatureDownsample (const cv::Mat &src, cv::Mat &dst, double minVal, double maxVal) |
Downsamples a temperature matrix to an 8-bit image. | |
void | temperatureDownsample16 (const cv::Mat &src, cv::Mat &dst) |
Downsamples a temperature matrix to a 16-bit image using Optris-like linear scaling. | |
void | thresholdRawImage (cv::Mat &img, double *vals) |
Sets pixel values in 16-bit image that are above or below limits to the limits themselves. | |
void | transferElement (vector< cv::Point2f > &dst, vector< cv::Point2f > &src, int index) |
Move a point from one vector to another, resize and shift old vector. | |
void | trimToDimensions (cv::Mat &image, int width, int height) |
Trims the top/bottom or sides of the image to get the correct ratio. | |
void | unpackTo8bit3Channel (const cv::Mat &src, cv::Mat &dst) |
Stores a 16-bit monochrome image in the first 2 channels of a CV_8UC3 mat. | |
void | weightedMixture (cv::Mat &dst, const cv::vector< cv::Mat > &srcs, const std::vector< double > &weightings) |
Declarations for image processing.
Definition in file improc.hpp.
#define BILATERAL_FILTERING 2 |
Definition at line 79 of file improc.hpp.
#define BLACKBODY 150 |
Definition at line 26 of file improc.hpp.
#define BLUERED 400 |
Definition at line 41 of file improc.hpp.
#define BLUERED_ALT_1 410 |
Definition at line 42 of file improc.hpp.
#define BLUERED_ALT_2 420 |
Definition at line 43 of file improc.hpp.
#define CIECOMP 100 |
Definition at line 19 of file improc.hpp.
#define CIECOMP_ALT_1 110 |
Definition at line 20 of file improc.hpp.
#define CIECOMP_ALT_2 120 |
Definition at line 21 of file improc.hpp.
#define CIECOMP_ALT_3 130 |
Definition at line 22 of file improc.hpp.
#define CIELUV 140 |
Definition at line 24 of file improc.hpp.
#define CUSTOM 3 |
ID for custom mapping.
Definition at line 14 of file improc.hpp.
#define DEFAULT_LOWER_VISIBLE_FUSION_LIMIT 0.2 |
Definition at line 83 of file improc.hpp.
#define DEFAULT_UPPER_VISIBLE_FUSION_LIMIT 0.8 |
Definition at line 84 of file improc.hpp.
#define GAUSSIAN_FILTERING 1 |
Definition at line 78 of file improc.hpp.
#define GRAYSCALE 0 |
Definition at line 17 of file improc.hpp.
#define HIGHLIGHTED 180 |
Definition at line 28 of file improc.hpp.
#define ICE 600 |
Definition at line 48 of file improc.hpp.
#define ICE_ALT_1 610 |
Definition at line 49 of file improc.hpp.
#define ICE_ALT_2 620 |
Definition at line 50 of file improc.hpp.
#define ICE_ALT_3 630 |
Definition at line 51 of file improc.hpp.
#define ICEFIRE 800 |
Definition at line 57 of file improc.hpp.
#define ICEFIRE_ALT_1 810 |
Definition at line 58 of file improc.hpp.
#define ICEFIRE_ALT_2 820 |
Definition at line 59 of file improc.hpp.
#define ICEFIRE_ALT_3 830 |
Definition at line 60 of file improc.hpp.
#define ICEIRON 700 |
Definition at line 53 of file improc.hpp.
#define ICEIRON_ALT_1 710 |
Definition at line 54 of file improc.hpp.
#define ICEIRON_ALT_2 720 |
Definition at line 55 of file improc.hpp.
#define IRON 300 |
Definition at line 36 of file improc.hpp.
#define IRON_ALT_1 310 |
Definition at line 37 of file improc.hpp.
#define IRON_ALT_2 320 |
Definition at line 38 of file improc.hpp.
#define IRON_ALT_3 330 |
Definition at line 39 of file improc.hpp.
#define JET 500 |
Definition at line 45 of file improc.hpp.
#define JET_ALT_1 510 |
Definition at line 46 of file improc.hpp.
#define MAP_LENGTH 1024 |
Definition at line 15 of file improc.hpp.
#define MIN_PROP_THRESHOLD 0.002 |
Definition at line 81 of file improc.hpp.
#define NO_FILTERING 0 |
Definition at line 77 of file improc.hpp.
#define NORMALIZATION_ADAPTIVE 3 |
Definition at line 73 of file improc.hpp.
#define NORMALIZATION_CENTRALIZED 4 |
Definition at line 74 of file improc.hpp.
#define NORMALIZATION_EQUALIZE 1 |
Definition at line 71 of file improc.hpp.
#define NORMALIZATION_EXPANDED 5 |
Definition at line 75 of file improc.hpp.
#define NORMALIZATION_STANDARD 0 |
Definition at line 70 of file improc.hpp.
#define RAINBOW 200 |
Definition at line 30 of file improc.hpp.
#define RAINBOW_ALT_1 210 |
Definition at line 31 of file improc.hpp.
#define RAINBOW_ALT_2 220 |
Definition at line 32 of file improc.hpp.
#define RAINBOW_ALT_3 230 |
Definition at line 33 of file improc.hpp.
#define RAINBOW_ALT_4 240 |
Definition at line 34 of file improc.hpp.
#define REPEATED 900 |
Definition at line 62 of file improc.hpp.
#define REPEATED_ALT_1 910 |
Definition at line 63 of file improc.hpp.
#define REPEATED_ALT_2 920 |
Definition at line 64 of file improc.hpp.
#define REPEATED_ALT_3 930 |
Definition at line 65 of file improc.hpp.
#define REPEATED_ALT_4 940 |
Definition at line 66 of file improc.hpp.
#define REPEATED_ALT_5 950 |
Definition at line 67 of file improc.hpp.
#define REPEATED_ALT_6 960 |
Definition at line 68 of file improc.hpp.
void adaptiveDownsample | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
int | code = NORMALIZATION_STANDARD , |
||
double | factor = 0.0 |
||
) |
Definition at line 754 of file improc.cpp.
void addBorder | ( | cv::Mat & | inputMat, |
int | borderSize | ||
) |
Definition at line 1645 of file improc.cpp.
void applyFilter | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
int | filter = NO_FILTERING , |
||
double | param = 2.0 |
||
) |
Definition at line 163 of file improc.cpp.
void applyIntensityShift | ( | const cv::Mat & | src1, |
cv::Mat & | dst1, | ||
const cv::Mat & | src2, | ||
cv::Mat & | dst2, | ||
double | grad, | ||
double | shift | ||
) |
Definition at line 371 of file improc.cpp.
bool checkIfActuallyGray | ( | const cv::Mat & | im | ) |
Definition at line 1303 of file improc.cpp.
void clusterRectangles | ( | vector< cv::Rect > & | rectangles, |
double | minOverlap | ||
) |
Definition at line 464 of file improc.cpp.
void combineImages | ( | const cv::Mat & | im1, |
const cv::Mat & | im2, | ||
cv::Mat & | dst | ||
) |
Definition at line 54 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)
Definition at line 1203 of file improc.cpp.
void convert16bitTo8bitConfidence | ( | const cv::Mat & | src, |
const cv::Mat & | conf, | ||
cv::Mat & | dst | ||
) |
Converts a 16-bit matrix to a 3 channel 8 bit matrix, with the third channel assigned confidence values.
Definition at line 326 of file improc.cpp.
void convertToTemperatureMat | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Converts a 16-bit image encoding temperature into floating point format.
Definition at line 291 of file improc.cpp.
void convertVectorToPoint | ( | vector< cv::Point2f > & | input, |
vector< cv::Point > & | output | ||
) |
Convert a vector from 'Point2f' format to 'Point' format.
Definition at line 1080 of file improc.cpp.
void convertVectorToPoint2f | ( | vector< cv::Point > & | input, |
vector< cv::Point2f > & | output | ||
) |
Convert a vector from 'Point' format to 'Point2f' format.
Definition at line 1090 of file improc.cpp.
void copyContour | ( | vector< cv::Point > & | src, |
vector< cv::Point > & | dst | ||
) |
Makes a copy of a contour.
Definition at line 1129 of file improc.cpp.
void createGaussianMatrix | ( | cv::Mat & | gaussianMat, |
double | sigmaFactor = 1.0 |
||
) |
Creates a gaussian intensity distribution in a given matrix.
Definition at line 909 of file improc.cpp.
Very basic image cropping.
Definition at line 1001 of file improc.cpp.
void down_level | ( | cv::Mat & | dst, |
cv::Mat & | src | ||
) |
16-bit to 8-bit
Definition at line 1597 of file improc.cpp.
void drawGrid | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
int | mode = 0 |
||
) |
Definition at line 404 of file improc.cpp.
void drawLinesBetweenPoints | ( | cv::Mat & | image, |
const vector< cv::Point2f > & | src, | ||
const vector< cv::Point2f > & | dst | ||
) |
Draws lines between initial and corrected points.
Definition at line 867 of file improc.cpp.
double findBestAlpha | ( | const cv::Mat & | K, |
const cv::Mat & | coeff, | ||
const cv::Size & | camSize | ||
) |
Definition at line 95 of file improc.cpp.
cv::Point findCentroid | ( | vector< cv::Point > & | contour | ) |
Finds centroid of a contour.
Definition at line 883 of file improc.cpp.
cv::Point2f findCentroid2f | ( | vector< cv::Point > & | contour | ) |
Finds centroid of a contour.
Definition at line 896 of file improc.cpp.
void findIntensityValues | ( | double * | vals, |
cv::Mat & | im, | ||
cv::Mat & | mask | ||
) |
Definition at line 1439 of file improc.cpp.
void findPercentiles | ( | const cv::Mat & | img, |
double * | vals, | ||
double * | percentiles, | ||
unsigned int | num | ||
) |
Definition at line 1344 of file improc.cpp.
void fix_bottom_right | ( | cv::Mat & | mat | ) |
Definition at line 1570 of file improc.cpp.
void fixedDownsample | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
double | center, | ||
double | range | ||
) |
Definition at line 356 of file improc.cpp.
void generateHistogram | ( | cv::Mat & | src, |
cv::Mat & | dst, | ||
double * | im_hist, | ||
double * | im_summ, | ||
double * | im_stat | ||
) |
Obtains histogram and other image statistics.
Definition at line 3030 of file improc.cpp.
void histExpand8 | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Definition at line 445 of file improc.cpp.
void invertMatIntensities | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Inverts the pixel intensities of a matrix.
Definition at line 1154 of file improc.cpp.
cv::Rect meanRectangle | ( | vector< cv::Rect > & | rectangles | ) |
Definition at line 521 of file improc.cpp.
void mixImages | ( | cv::Mat & | dst, |
cv::vector< cv::Mat > & | images | ||
) |
Definition at line 583 of file improc.cpp.
void normalize_16 | ( | cv::Mat & | dst, |
const cv::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 1693 of file improc.cpp.
void normalize_64_vec | ( | cv::Mat & | dst, |
cv::Mat & | src | ||
) |
Definition at line 1658 of file improc.cpp.
cv::Mat normForDisplay | ( | cv::Mat | origMat | ) |
Definition at line 3177 of file improc.cpp.
void obtainColorRepresentation | ( | cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Definition at line 1547 of file improc.cpp.
void obtainEightBitRepresentation | ( | cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Definition at line 1526 of file improc.cpp.
void process8bitImage | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
int | code = NORMALIZATION_STANDARD , |
||
double | factor = 0.0 |
||
) |
Definition at line 735 of file improc.cpp.
cv::Point rectangle_center | ( | cv::Rect | input | ) |
Definition at line 628 of file improc.cpp.
bool rectangle_contains_centroid | ( | cv::Rect | mainRectangle, |
cv::Rect | innerRectangle | ||
) |
Definition at line 617 of file improc.cpp.
double rectangleOverlap | ( | cv::Rect | rectangle1, |
cv::Rect | rectangle2 | ||
) |
Definition at line 638 of file improc.cpp.
void reduceToPureImage | ( | cv::Mat & | dst, |
cv::Mat & | src | ||
) |
Definition at line 1611 of file improc.cpp.
double scoreColorImage | ( | const cv::Mat & | src | ) |
Returns a score which reflects the information content of the image for visualization.
Definition at line 7 of file improc.cpp.
double scoreThermalImage | ( | const cv::Mat & | src | ) |
Returns a score which reflects the information content of the image for visualization.
Definition at line 26 of file improc.cpp.
void shiftIntensities | ( | cv::Mat & | im, |
double | scaler, | ||
double | shifter, | ||
double | downer | ||
) |
Definition at line 1418 of file improc.cpp.
void simpleResize | ( | cv::Mat & | src, |
cv::Mat & | dst, | ||
cv::Size | size | ||
) |
Resizes an image without interpolation.
Definition at line 1103 of file improc.cpp.
void splitMultimodalImage | ( | const cv::Mat & | src, |
cv::Mat & | therm, | ||
cv::Mat & | vis | ||
) |
Definition at line 148 of file improc.cpp.
void swapElements | ( | vector< cv::Point2f > & | corners, |
int | index1, | ||
int | index2 | ||
) |
Swaps the position of two elements in a point vector.
Definition at line 1142 of file improc.cpp.
void temperatureDownsample | ( | const cv::Mat & | src, |
cv::Mat & | dst, | ||
double | minVal, | ||
double | maxVal | ||
) |
Downsamples a temperature matrix to an 8-bit image.
Definition at line 268 of file improc.cpp.
void temperatureDownsample16 | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Downsamples a temperature matrix to a 16-bit image using Optris-like linear scaling.
Definition at line 308 of file improc.cpp.
void thresholdRawImage | ( | cv::Mat & | img, |
double * | vals | ||
) |
Sets pixel values in 16-bit image that are above or below limits to the limits themselves.
Definition at line 1327 of file improc.cpp.
void transferElement | ( | vector< cv::Point2f > & | dst, |
vector< cv::Point2f > & | src, | ||
int | index | ||
) |
Move a point from one vector to another, resize and shift old vector.
Definition at line 1283 of file improc.cpp.
void trimToDimensions | ( | cv::Mat & | image, |
int | width, | ||
int | height | ||
) |
Trims the top/bottom or sides of the image to get the correct ratio.
Definition at line 662 of file improc.cpp.
void unpackTo8bit3Channel | ( | const cv::Mat & | src, |
cv::Mat & | dst | ||
) |
Stores a 16-bit monochrome image in the first 2 channels of a CV_8UC3 mat.
Definition at line 71 of file improc.cpp.
void weightedMixture | ( | cv::Mat & | dst, |
const cv::vector< cv::Mat > & | srcs, | ||
const std::vector< double > & | weightings | ||
) |
Definition at line 543 of file improc.cpp.