00001
00005 #ifndef _THERMALVIS_IMPROC_H_
00006 #define _THERMALVIS_IMPROC_H_
00007
00008
00009
00010
00011 #include "tools.hpp"
00012
00014 #define CUSTOM 3
00015 #define MAP_LENGTH 1024
00016
00017 #define GRAYSCALE 0
00018
00019 #define CIECOMP 100
00020 #define CIECOMP_ALT_1 110
00021 #define CIECOMP_ALT_2 120
00022 #define CIECOMP_ALT_3 130
00023
00024 #define CIELUV 140
00025
00026 #define BLACKBODY 150
00027
00028 #define HIGHLIGHTED 180
00029
00030 #define RAINBOW 200
00031 #define RAINBOW_ALT_1 210
00032 #define RAINBOW_ALT_2 220
00033 #define RAINBOW_ALT_3 230
00034 #define RAINBOW_ALT_4 240
00035
00036 #define IRON 300
00037 #define IRON_ALT_1 310
00038 #define IRON_ALT_2 320
00039 #define IRON_ALT_3 330
00040
00041 #define BLUERED 400
00042 #define BLUERED_ALT_1 410
00043 #define BLUERED_ALT_2 420
00044
00045 #define JET 500
00046 #define JET_ALT_1 510
00047
00048 #define ICE 600
00049 #define ICE_ALT_1 610
00050 #define ICE_ALT_2 620
00051 #define ICE_ALT_3 630
00052
00053 #define ICEIRON 700
00054 #define ICEIRON_ALT_1 710
00055 #define ICEIRON_ALT_2 720
00056
00057 #define ICEFIRE 800
00058 #define ICEFIRE_ALT_1 810
00059 #define ICEFIRE_ALT_2 820
00060 #define ICEFIRE_ALT_3 830
00061
00062 #define REPEATED 900
00063 #define REPEATED_ALT_1 910
00064 #define REPEATED_ALT_2 920
00065 #define REPEATED_ALT_3 930
00066 #define REPEATED_ALT_4 940
00067 #define REPEATED_ALT_5 950
00068 #define REPEATED_ALT_6 960
00069
00070 #define NORMALIZATION_STANDARD 0
00071 #define NORMALIZATION_EQUALIZE 1
00072
00073 #define NORMALIZATION_ADAPTIVE 3
00074 #define NORMALIZATION_CENTRALIZED 4
00075 #define NORMALIZATION_EXPANDED 5
00076
00077 #define NO_FILTERING 0
00078 #define GAUSSIAN_FILTERING 1
00079 #define BILATERAL_FILTERING 2
00080
00081 #define MIN_PROP_THRESHOLD 0.002
00082
00083 #define DEFAULT_LOWER_VISIBLE_FUSION_LIMIT 0.2
00084 #define DEFAULT_UPPER_VISIBLE_FUSION_LIMIT 0.8
00085
00086 void applyFilter(const cv::Mat& src, cv::Mat& dst, int filter = NO_FILTERING, double param = 2.0);
00087
00088
00089
00090 double findBestAlpha(const cv::Mat& K, const cv::Mat& coeff, const cv::Size& camSize);
00091
00092 void weightedMixture(cv::Mat& dst, const cv::vector<cv::Mat>& srcs, const std::vector<double>& weightings);
00093
00094 void addBorder(cv::Mat& inputMat, int borderSize);
00095
00096 void normalize_64_vec(cv::Mat& dst, cv::Mat& src);
00097
00098 void mixImages(cv::Mat& dst, cv::vector<cv::Mat>& images);
00099
00100 bool rectangle_contains_centroid(cv::Rect mainRectangle, cv::Rect innerRectangle);
00101 cv::Rect meanRectangle(vector<cv::Rect>& rectangles);
00102 void clusterRectangles(vector<cv::Rect>& rectangles, double minOverlap);
00103
00104 cv::Point rectangle_center(cv::Rect input);
00105
00106 void combineImages(const cv::Mat& im1, const cv::Mat& im2, cv::Mat& dst);
00107
00109 void unpackTo8bit3Channel(const cv::Mat& src, cv::Mat& dst);
00110
00111 double rectangleOverlap(cv::Rect rectangle1, cv::Rect rectangle2);
00112
00113 void obtainEightBitRepresentation(cv::Mat& src, cv::Mat& dst);
00114 void obtainColorRepresentation(cv::Mat& src, cv::Mat& dst);
00115
00117 void trimToDimensions(cv::Mat& image, int width, int height);
00118
00120 void cropImage(cv::Mat& image, cv::Point tl, cv::Point br);
00121
00122 void drawGrid(const cv::Mat& src, cv::Mat& dst, int mode = 0);
00123
00125 void convertVectorToPoint2f(vector<cv::Point>& input, vector<cv::Point2f>& output);
00126
00128 void convertVectorToPoint(vector<cv::Point2f>& input, vector<cv::Point>& output);
00129
00130 void splitMultimodalImage(const cv::Mat& src, cv::Mat& therm, cv::Mat& vis);
00131
00133 cv::Point findCentroid(vector<cv::Point>& contour);
00134
00136 cv::Point2f findCentroid2f(vector<cv::Point>& contour);
00137
00139 void simpleResize(cv::Mat& src, cv::Mat& dst, cv::Size size);
00140
00142 void thresholdRawImage(cv::Mat& img, double *vals);
00143
00145 void createGaussianMatrix(cv::Mat& gaussianMat, double sigmaFactor = 1.0);
00146
00148 void copyContour(vector<cv::Point>& src, vector<cv::Point>& dst);
00149
00151 void invertMatIntensities(const cv::Mat& src, cv::Mat& dst);
00152
00154 void swapElements(vector<cv::Point2f>& corners, int index1, int index2);
00155
00157 void contourDimensions(vector<cv::Point> contour, double& width, double& height);
00158
00159
00160
00162 void drawLinesBetweenPoints(cv::Mat& image, const vector<cv::Point2f>& src, const vector<cv::Point2f>& dst);
00163
00164
00165
00166
00167
00169 double scoreColorImage(const cv::Mat& src);
00170
00172 double scoreThermalImage(const cv::Mat& src);
00173
00175 void transferElement(vector<cv::Point2f>& dst, vector<cv::Point2f>& src, int index);
00176
00178 void normalize_16(cv::Mat& dst, const cv::Mat& src, double dblmin = -1.0, double dblmax = -1.0);
00179 void histExpand8(const cv::Mat& src, cv::Mat& dst);
00180 void reduceToPureImage(cv::Mat& dst, cv::Mat& src);
00181 void fix_bottom_right(cv::Mat& mat);
00182
00184 void convert16bitTo8bitConfidence(const cv::Mat& src, const cv::Mat& conf, cv::Mat& dst);
00185
00186 void fixedDownsample(const cv::Mat& src, cv::Mat& dst, double center, double range);
00187
00188
00190 void temperatureDownsample(const cv::Mat& src, cv::Mat& dst, double minVal, double maxVal);
00191
00193 void convertToTemperatureMat(const cv::Mat& src, cv::Mat& dst);
00194
00196 void temperatureDownsample16(const cv::Mat& src, cv::Mat& dst);
00197
00198
00199 void adaptiveDownsample(const cv::Mat& src, cv::Mat& dst, int code = NORMALIZATION_STANDARD, double factor = 0.0);
00200
00201 void process8bitImage(const cv::Mat& src, cv::Mat& dst, int code = NORMALIZATION_STANDARD, double factor = 0.0);
00202
00203 bool checkIfActuallyGray(const cv::Mat& im);
00204
00205 void findIntensityValues(double *vals, cv::Mat& im, cv::Mat& mask);
00206 void shiftIntensities(cv::Mat& im, double scaler, double shifter, double downer);
00207 void findPercentiles(const cv::Mat& img, double *vals, double *percentiles, unsigned int num);
00208
00210 void generateHistogram(cv::Mat& src, cv::Mat& dst, double* im_hist, double* im_summ, double* im_stat);
00211
00213 void down_level(cv::Mat& dst, cv::Mat& src);
00214
00215 void applyIntensityShift(const cv::Mat& src1, cv::Mat& dst1, const cv::Mat& src2, cv::Mat& dst2, double grad, double shift);
00216
00217 cv::Mat normForDisplay(cv::Mat origMat);
00218
00220 class cScheme {
00221 protected:
00222
00224 double* dx;
00225
00227 double* rx;
00229 double red[MAP_LENGTH];
00231 double* gx;
00233 double green[MAP_LENGTH];
00235 double* bx;
00237 double blue[MAP_LENGTH];
00239 int length;
00241 int code;
00242
00244 unsigned char lookupTable_1[256][3];
00245 unsigned short lookupTable_2[65536][3];
00246
00247 public:
00249 cScheme();
00250
00251
00252
00258 cScheme(double *d, double *r, double *g, double *b, int len);
00259
00261 ~cScheme();
00262
00265 void load_standard(int mapCode, int mapParam = 0);
00266
00268 void create_long_map();
00269
00271 void setupLookupTable(unsigned int depth = 65536);
00272
00278 void customize(double* d, double* r, double* g, double* b, int len);
00279
00286 void falsify_image(const cv::Mat& thermIm, cv::Mat& outputIm, int param = 1);
00287
00295 void fuse_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double *params = NULL);
00296
00298 void forge_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double* params = NULL, double thresh = 0.05);
00299
00302 int current_scheme();
00303
00308 void image_resize(cv::Mat& inputIm, int dim_i, int dim_j);
00309
00310
00311 };
00312
00313 #endif