$search
00001 00005 #ifndef _THERMALVIS_IMPROC_H_ 00006 #define _THERMALVIS_IMPROC_H_ 00007 00008 //#include "general_resources.hpp" 00009 //#include "opencv_resources.hpp" 00010 00011 #include "tools.hpp" 00012 00013 #ifdef USE_CLAHE 00014 #include "clahe.h" 00015 #endif 00016 00017 00019 #define CUSTOM 3 00020 #define MAP_LENGTH 1024 00021 00022 #define GRAYSCALE 0 00023 00024 #define CIECOMP 100 00025 #define CIECOMP_ALT_1 110 00026 #define CIECOMP_ALT_2 120 00027 #define CIECOMP_ALT_3 130 00028 00029 #define BLACKBODY 150 00030 00031 #define HIGHLIGHTED 180 00032 00033 #define RAINBOW 200 00034 #define RAINBOW_ALT_1 210 00035 #define RAINBOW_ALT_2 220 00036 #define RAINBOW_ALT_3 230 00037 #define RAINBOW_ALT_4 240 00038 00039 #define IRON 300 00040 #define IRON_ALT_1 310 00041 #define IRON_ALT_2 320 00042 #define IRON_ALT_3 330 00043 00044 #define BLUERED 400 00045 #define BLUERED_ALT_1 410 00046 #define BLUERED_ALT_2 420 00047 00048 #define JET 500 00049 #define JET_ALT_1 510 00050 00051 #define ICE 600 00052 #define ICE_ALT_1 610 00053 #define ICE_ALT_2 620 00054 #define ICE_ALT_3 630 00055 00056 #define ICEIRON 700 00057 #define ICEIRON_ALT_1 710 00058 #define ICEIRON_ALT_2 720 00059 00060 #define ICEFIRE 800 00061 #define ICEFIRE_ALT_1 810 00062 #define ICEFIRE_ALT_2 820 00063 #define ICEFIRE_ALT_3 830 00064 00065 #define REPEATED 900 00066 #define REPEATED_ALT_1 910 00067 #define REPEATED_ALT_2 920 00068 #define REPEATED_ALT_3 930 00069 #define REPEATED_ALT_4 940 00070 #define REPEATED_ALT_5 950 00071 #define REPEATED_ALT_6 960 00072 00073 #define NORMALIZATION_STANDARD 0 00074 #define NORMALIZATION_EQUALIZE 1 00075 #define NORMALIZATION_CLAHE 2 00076 #define NORMALIZATION_ADAPTIVE 3 00077 #define NORMALIZATION_CENTRALIZED 4 00078 #define NORMALIZATION_EXPANDED 5 00079 00080 #define NO_FILTERING 0 00081 #define GAUSSIAN_FILTERING 1 00082 #define BILATERAL_FILTERING 2 00083 00084 #define MIN_PROP_THRESHOLD 0.002 00085 00086 void applyFilter(const Mat& src, Mat& dst, int filter = NO_FILTERING, double param = 2.0); 00087 00088 void straightCLAHE(const Mat& src, Mat& dst, double factor); 00089 00090 double findBestAlpha(const Mat& K, const Mat& coeff, const Size& camSize); 00091 00092 void weightedMixture(Mat& dst, const cv::vector<Mat>& srcs, const std::vector<double>& weightings); 00093 00094 void addBorder(Mat& inputMat, int borderSize); 00095 00096 void normalize_64_vec(Mat& dst, Mat& src); 00097 00098 void mixImages(Mat& dst, cv::vector<Mat>& images); 00099 00100 bool rectangle_contains_centroid(cv::Rect mainRectangle, cv::Rect innerRectangle); 00101 Rect meanRectangle(vector<Rect>& rectangles); 00102 void clusterRectangles(vector<Rect>& rectangles, double minOverlap); 00103 00104 cv::Point rectangle_center(cv::Rect input); 00105 00107 void unpackTo8bit3Channel(const Mat& src, Mat& dst); 00108 00109 double rectangleOverlap(Rect rectangle1, Rect rectangle2); 00110 00111 void obtainEightBitRepresentation(Mat& src, Mat& dst); 00112 void obtainColorRepresentation(Mat& src, Mat& dst); 00113 00115 void trimToDimensions(Mat& image, int width, int height); 00116 00118 void cropImage(Mat& image, cv::Point tl, cv::Point br); 00119 00120 void drawGrid(const Mat& src, Mat& dst, int mode = 0); 00121 00123 void convertVectorToPoint2f(vector<cv::Point>& input, vector<Point2f>& output); 00124 00126 void convertVectorToPoint(vector<Point2f>& input, vector<cv::Point>& output); 00127 00128 void splitMultimodalImage(const Mat& src, Mat& therm, Mat& vis); 00129 00131 cv::Point findCentroid(vector<cv::Point>& contour); 00132 00134 Point2f findCentroid2f(vector<cv::Point>& contour); 00135 00137 void simpleResize(Mat& src, Mat& dst, Size size); 00138 00140 void createGaussianMatrix(Mat& gaussianMat, double sigmaFactor); 00141 00143 void copyContour(vector<cv::Point>& src, vector<cv::Point>& dst); 00144 00146 void invertMatIntensities(const Mat& src, Mat& dst); 00147 00149 void swapElements(vector<Point2f>& corners, int index1, int index2); 00150 00152 void contourDimensions(vector<cv::Point> contour, double& width, double& height); 00153 00155 Point2f meanPoint(Point2f& P1, Point2f& P2); 00156 00158 double findMinimumSeparation(vector<Point2f>& pts); 00159 00161 void drawLinesBetweenPoints(Mat& image, const vector<Point2f>& src, const vector<Point2f>& dst); 00162 00164 double perpDist(Point2f& P1, Point2f& P2, Point2f& P3); 00165 00167 double distBetweenPts(cv::Point& P1, cv::Point& P2); 00169 double distBetweenPts2f(Point2f& P1, Point2f& P2); 00170 00172 void transferElement(vector<Point2f>& dst, vector<Point2f>& src, int index); 00173 00175 void normalize_16(Mat& dst, const Mat& src, double dblmin = -1.0, double dblmax = -1.0); 00176 void histExpand8(const Mat& src, Mat& dst); 00177 void reduceToPureImage(cv::Mat& dst, cv::Mat& src); 00178 void fix_bottom_right(Mat& mat); 00179 00180 void fixedDownsample(const Mat& src, Mat& dst, double center, double range); 00181 00182 void downsampleCLAHE(const Mat& src, Mat& dst, double factor); 00183 void adaptiveDownsample(const Mat& src, Mat& dst, int code = NORMALIZATION_STANDARD, double factor = 0.0); 00184 00185 void process8bitImage(const Mat& src, Mat& dst, int code = NORMALIZATION_STANDARD, double factor = 0.0); 00186 00187 bool checkIfActuallyGray(const Mat& im); 00188 00189 void findIntensityValues(double *vals, Mat& im, Mat& mask); 00190 void shiftIntensities(Mat& im, double scaler, double shifter, double downer); 00191 void findPercentiles(const Mat& img, double *vals, double *percentiles, unsigned int num); 00192 00194 void generateHistogram(Mat& src, Mat& dst, double* im_hist, double* im_summ, double* im_stat); 00195 00197 void down_level(Mat& dst, Mat& src); 00198 00199 void applyIntensityShift(const Mat& src1, Mat& dst1, const Mat& src2, Mat& dst2, double grad, double shift); 00200 00201 Mat normForDisplay(Mat origMat); 00202 00204 class cScheme { 00205 protected: 00206 00208 double* dx; 00209 00211 double* rx; 00213 double red[MAP_LENGTH]; 00215 double* gx; 00217 double green[MAP_LENGTH]; 00219 double* bx; 00221 double blue[MAP_LENGTH]; 00223 int length; 00225 int code; 00226 00228 unsigned char lookupTable_1[256][3]; 00229 unsigned short lookupTable_2[65536][3]; 00230 00231 public: 00233 cScheme(); 00234 00235 00236 00242 cScheme(double *d, double *r, double *g, double *b, int len); 00243 00245 ~cScheme(); 00246 00249 void load_standard(int mapCode, int mapParam = 0); 00250 00252 void create_long_map(); 00253 00255 void setupLookupTable(unsigned int depth = 65536); 00256 00262 void customize(double* d, double* r, double* g, double* b, int len); 00263 00270 void falsify_image(const cv::Mat& thermIm, cv::Mat& outputIm, int param = 1); 00271 00279 void fuse_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double *params = NULL); 00280 00282 void forge_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double* params = NULL, double thresh = 0.05); 00283 00286 int current_scheme(); 00287 00292 void image_resize(cv::Mat& inputIm, int dim_i, int dim_j); 00293 00294 00295 }; 00296 00297 #endif