$search
00001 00005 #include "flags.hpp" 00006 #include "improc.hpp" 00007 00008 void unpackTo8bit3Channel(const Mat& src, Mat& dst) { 00009 00010 dst = Mat(src.size(), CV_8UC3); 00011 00012 for (unsigned int iii = 0; iii < src.rows; iii++) { 00013 for (unsigned int jjj = 0; jjj < src.cols; jjj++) { 00014 00015 // First byte should be the major component 00016 dst.at<Vec3b>(iii,jjj)[0] = src.at<unsigned short>(iii,jjj) >> 8; 00017 00018 // Second byte should be the minor component 00019 dst.at<Vec3b>(iii,jjj)[1] = src.at<unsigned short>(iii,jjj) & 0x00FF; 00020 dst.at<Vec3b>(iii,jjj)[2] = 0; 00021 00022 if (src.at<unsigned short>(iii,jjj) != (256 * dst.at<Vec3b>(iii,jjj)[0]) + dst.at<Vec3b>(iii,jjj)[1]) { 00023 printf("%s << ERROR! (%d) != (%d, %d)\n", __FUNCTION__, src.at<unsigned short>(iii,jjj), dst.at<Vec3b>(iii,jjj)[0], dst.at<Vec3b>(iii,jjj)[1]); 00024 cin.get(); 00025 } 00026 00027 } 00028 } 00029 00030 } 00031 00032 double findBestAlpha(const Mat& K, const Mat& coeff, const Size& camSize) { 00033 00034 Mat newCamMat; 00035 00036 Rect roi; 00037 00038 double alpha = 0.00; 00039 bool centerPrincipalPoint = true; 00040 00041 Mat map1, map2; 00042 00043 unsigned int protectionCounter = 0; 00044 00045 Mat R_default = Mat::eye(3, 3, CV_64FC1); 00046 00047 while (1) { 00048 00049 Mat white = Mat::ones(camSize, CV_16UC1); 00050 Mat mapped; 00051 00052 newCamMat = getOptimalNewCameraMatrix(K, coeff, camSize, alpha, camSize, &roi, centerPrincipalPoint); 00053 00054 initUndistortRectifyMap(K, coeff, R_default, newCamMat, camSize, CV_32FC1, map1, map2); 00055 00056 double minVal, maxVal; 00057 00058 Mat scaled_white; 00059 white.convertTo(scaled_white, CV_16UC1, 65535, 0); 00060 00061 remap(scaled_white, mapped, map1, map2, INTER_LINEAR, BORDER_CONSTANT, 0); 00062 00063 //imshow("scaled_white", mapped); 00064 //waitKey(); 00065 00066 minMaxLoc(mapped, &minVal, &maxVal); 00067 00068 if (minVal == 65535.0) { 00069 break; 00070 } 00071 00072 if (protectionCounter == 100) { 00073 alpha = 0.0; 00074 break; 00075 } 00076 00077 alpha -= 0.01; 00078 protectionCounter++; 00079 } 00080 00081 return alpha; 00082 00083 } 00084 00085 void splitMultimodalImage(const Mat& src, Mat& therm, Mat& vis) { 00086 00087 therm = Mat::zeros(src.size(), CV_8UC1); 00088 vis = Mat::zeros(src.size(), CV_8UC1); 00089 00090 #pragma omp parallel for 00091 for (int iii = 0; iii < src.rows; iii++) { 00092 for (int jjj = 0; jjj < src.cols; jjj++) { 00093 therm.at<unsigned char>(iii,jjj) = src.at<Vec3b>(iii,jjj)[2]; 00094 vis.at<unsigned char>(iii,jjj) = src.at<Vec3b>(iii,jjj)[1]; 00095 } 00096 } 00097 00098 } 00099 00100 void applyFilter(const Mat& src, Mat& dst, int filter, double param) { 00101 00102 int ksize; 00103 00104 if (filter == GAUSSIAN_FILTERING) { 00105 ksize = int(param * 2); 00106 } else if (filter == BILATERAL_FILTERING) { 00107 ksize = int(param); 00108 } 00109 00110 if ((int(ksize) % 2) == 0) { 00111 ksize++; 00112 } 00113 00114 double bilateralVal = param; 00115 00116 if (filter == GAUSSIAN_FILTERING) { 00117 GaussianBlur(src, dst, Size(ksize, ksize), sqrt(param)); 00118 } else if (filter == BILATERAL_FILTERING) { 00119 bilateralFilter(src, dst, ksize, param * 2.0, param * 2.0); //, double sigmaColor, double sigmaSpace, int borderType=BORDER_DEFAULT ); 00120 } else { 00121 src.copyTo(dst); 00122 } 00123 00124 } 00125 00126 void straightCLAHE(const Mat& src, Mat& dst, double factor) { 00127 00128 int xdivs = 2; 00129 int ydivs = 2; 00130 int bins = 256; 00131 //int limit_counter = 255.0 * factor; 00132 00133 IplImage tmp_ipl(src); 00134 00135 00136 IplImage* dst_ipl = cvCreateImage(cvSize(tmp_ipl.width,tmp_ipl.height), tmp_ipl.depth, 1); 00137 dst_ipl->origin = tmp_ipl.origin; 00138 00139 //IplImage dst_ipl; 00140 00141 #ifdef USE_CLAHE 00142 cvCLAdaptEqualize(&tmp_ipl, dst_ipl, (unsigned int) xdivs, (unsigned int) ydivs, 00143 (unsigned int) bins, (1.0 + factor * 14.0), CV_CLAHE_RANGE_FULL); 00144 // (float) limit_counter * 0.1 00145 #endif 00146 00147 00148 dst = Mat(dst_ipl); 00149 00150 } 00151 00152 void downsampleCLAHE(const Mat& src, Mat& dst, double factor) { 00153 00154 Mat tmp; 00155 00156 if (factor == 0.0) { 00157 00158 adaptiveDownsample(src, dst, NORMALIZATION_STANDARD, 0.001); 00159 00160 return; 00161 } 00162 00163 // from: https://github.com/joshdoe/opencv-clahe 00164 00165 // ... 00166 00167 //printf("%s << entered...\n", __FUNCTION__); 00168 00169 Mat tmp_2; 00170 00171 adaptiveDownsample(src, tmp_2, NORMALIZATION_STANDARD, 0.001); 00172 00173 straightCLAHE(tmp_2, dst, factor); 00174 00175 00176 //int xdivs = 2; 00177 //int ydivs = 2; 00178 //int bins = 256; 00180 00181 //IplImage tmp_ipl(tmp_2); 00182 00183 00184 //IplImage* dst_ipl = cvCreateImage(cvSize(tmp_ipl.width,tmp_ipl.height), tmp_ipl.depth, 1); 00185 //dst_ipl->origin = tmp_ipl.origin; 00186 00188 00189 //cvCLAdaptEqualize(&tmp_ipl, dst_ipl, (unsigned int) xdivs, (unsigned int) ydivs, 00190 //(unsigned int) bins, (1.0 + factor * 14.0), CV_CLAHE_RANGE_FULL); 00192 00193 00194 //dst = Mat(dst_ipl); 00195 00197 00198 } 00199 00200 void fixedDownsample(const Mat& src, Mat& dst, double center, double range) { 00201 00202 dst = Mat::zeros(src.rows, src.cols, CV_8UC1); 00203 00204 #pragma omp parallel for 00205 for (int iii = 0; iii < src.rows; iii++) { 00206 for (int jjj = 0; jjj < src.cols; jjj++) { 00207 00208 dst.at<unsigned char>(iii,jjj) = std::min(255.0, std::max(0.0, 127.5 + 127.5*(double(src.at<unsigned short>(iii,jjj)) - center)/(0.5 * range))); 00209 00210 } 00211 } 00212 00213 } 00214 00215 void applyIntensityShift(const Mat& src1, Mat& dst1, const Mat& src2, Mat& dst2, double grad, double shift) { 00216 00217 double center = 8000.0, range = 1.0; 00218 00219 double percentileVals[3] = { 0.001, 0.500, 0.999 }; 00220 double intensityVals[3]; 00221 findPercentiles(src1, intensityVals, percentileVals, 3); 00222 00223 center = intensityVals[1]; 00224 range = std::max(abs(intensityVals[2] - intensityVals[1]), abs(intensityVals[0] - intensityVals[1])); 00225 00226 //printf("%s << normalizing with center = (%f) and range = (%f)\n", __FUNCTION__, center, range); 00227 00228 //adaptiveDownsample(src1, dst1); 00229 fixedDownsample(src1, dst1, center, 2.0*range); 00230 00231 Mat src2_shifted(src2.rows, src2.cols, src2.type()); 00232 // src2.copyTo(src2_shifted); 00233 00234 #pragma omp parallel for 00235 for (int iii = 0; iii < src2_shifted.rows; iii++) { 00236 for (int jjj = 0; jjj < src2_shifted.cols; jjj++) { 00237 00238 src2_shifted.at<unsigned short>(iii,jjj) = grad * double(src2.at<unsigned short>(iii,jjj)) + shift; 00239 00240 } 00241 } 00242 00243 //adaptiveDownsample(src2_shifted, dst2); 00244 fixedDownsample(src2_shifted, dst2, center, range); 00245 00246 } 00247 00248 void drawGrid(const Mat& src, Mat& dst, int mode) { 00249 00250 src.copyTo(dst); 00251 00252 Scalar col; 00253 00254 int shift; 00255 00256 if (mode == 0) { 00257 shift = 0; 00258 col = CV_RGB(255, 0, 0); 00259 } else { 00260 shift = 1; 00261 col = CV_RGB(0, 0, 255); 00262 } 00263 00264 Point2f startPt, endPt; 00265 00266 double amt = double(src.cols) / 8.0; 00267 00268 // Vertical lines 00269 for (int iii = shift; iii <= 8-shift; iii++) { 00270 startPt = Point2f(16.0 * double(iii)*amt, 16.0 * double(shift)*amt); 00271 endPt = Point2f(16.0 * double(iii)*amt, 16.0 * (double(src.rows) - double(shift)*amt)); 00272 00273 line(dst, startPt, endPt, col, 1, CV_AA, 4); 00274 } 00275 00276 // Horizontal lines 00277 for (int iii = shift; iii <= 6-shift; iii++) { 00278 00279 startPt = Point2f(16.0 * double(shift)*amt, 16.0 * double(iii)*amt); 00280 endPt = Point2f(16.0 * (double(src.cols) - double(shift)*amt), 16.0 * double(iii)*amt); 00281 00282 line(dst, startPt, endPt, col, 1, CV_AA, 4); 00283 00284 } 00285 00286 00287 } 00288 00289 void histExpand8(const Mat& src, Mat& dst) { 00290 00291 double minVal, maxVal; 00292 minMaxLoc(src, &minVal, &maxVal); 00293 00294 dst = Mat::zeros(src.size(), src.type()); 00295 00296 #pragma omp parallel for 00297 for (int iii = 0; iii < src.rows; iii++) { 00298 for (int jjj = 0; jjj < src.cols; jjj++) { 00299 00300 unsigned char val = (unsigned char) (((double)src.at<unsigned char>(iii,jjj)) - minVal) * 255.0 / (maxVal - minVal); 00301 00302 dst.at<unsigned char>(iii,jjj) = val; 00303 } 00304 } 00305 00306 } 00307 00308 void clusterRectangles(vector<Rect>& rectangles, double minOverlap) { 00309 00310 if (rectangles.size() == 0) { 00311 return; 00312 } 00313 00314 unsigned int j,k; 00315 00316 bool hasBeenClustered; 00317 00318 vector<Rect> falseVector; 00319 00320 Rect tempRect; 00321 00322 vector<vector<Rect> > clusteredRectangles; 00323 00324 clusteredRectangles.push_back(falseVector); 00325 00326 clusteredRectangles.at(0).push_back(rectangles.at(0)); 00327 00328 // For each remaining rectangle 00329 for (unsigned int i = 1; i < rectangles.size(); i++) { 00330 00331 hasBeenClustered = false; 00332 00333 j = 0; 00334 k = 0; 00335 00336 while (!hasBeenClustered) { 00337 if (rectangleOverlap(rectangles.at(i), clusteredRectangles.at(j).at(k)) > minOverlap) { 00338 clusteredRectangles.at(j).push_back(rectangles.at(i)); 00339 hasBeenClustered = true; 00340 } else if (k < clusteredRectangles.at(j).size()-1) { 00341 k++; 00342 } else if (j < clusteredRectangles.size()-1) { 00343 j++; 00344 k = 0; 00345 } else { 00346 clusteredRectangles.push_back(falseVector); 00347 clusteredRectangles.at(j+1).push_back(rectangles.at(i)); 00348 hasBeenClustered = true; 00349 } 00350 } 00351 00352 //printf("%s << overlapProp = %f\n", __FUNCTION__, overlapProp); 00353 00354 } 00355 00356 rectangles.clear(); 00357 00358 for (unsigned int i = 0; i < clusteredRectangles.size(); i++) { 00359 tempRect = meanRectangle(clusteredRectangles.at(i)); 00360 rectangles.push_back(tempRect); 00361 } 00362 00363 } 00364 00365 Rect meanRectangle(vector<Rect>& rectangles) { 00366 00367 Rect retVal; 00368 double xSum = 0.0, ySum = 0.0, wSum = 0.0, hSum = 0.0; 00369 00370 for (unsigned int i = 0; i < rectangles.size(); i++) { 00371 xSum += rectangles.at(i).x; 00372 ySum += rectangles.at(i).y; 00373 wSum += rectangles.at(i).width; 00374 hSum += rectangles.at(i).height; 00375 } 00376 00377 xSum /= rectangles.size(); 00378 ySum /= rectangles.size(); 00379 wSum /= rectangles.size(); 00380 hSum /= rectangles.size(); 00381 00382 retVal = Rect(int(xSum), int(ySum), int(wSum), int(hSum)); 00383 00384 return retVal; 00385 } 00386 00387 void weightedMixture(Mat& dst, const cv::vector<Mat>& srcs, const std::vector<double>& weightings) { 00388 00389 double totalWeighting = 0.0; 00390 vector<double> newWeightings; 00391 newWeightings.insert(newWeightings.end(), weightings.begin(), weightings.end()); 00392 00393 for (unsigned int iii = 0; iii < weightings.size(); iii++) { 00394 totalWeighting += weightings.at(iii); 00395 } 00396 00397 for (unsigned int iii = 0; iii < weightings.size(); iii++) { 00398 newWeightings.at(iii) /= totalWeighting; 00399 } 00400 00401 Mat tmpDst = Mat::zeros(srcs.at(0).size(), CV_64FC3); 00402 00403 for (unsigned int i = 0; i < srcs.size(); i++) { 00404 00405 for (int m = 0; m < srcs.at(i).rows; m++) { 00406 00407 for (int n = 0; n < srcs.at(i).cols; n++) { 00408 00409 for (int k = 0; k < 3; k++) { 00410 tmpDst.at<Vec3d>(m,n)[k] += double((srcs.at(i)).at<Vec3b>(m,n)[k]) * newWeightings.at(i); 00411 } 00412 00413 } 00414 00415 } 00416 00417 } 00418 00419 Mat normMat; 00420 normalize_64_vec(normMat, tmpDst); 00421 00422 dst = Mat(normMat.size(), CV_8UC3); 00423 convertScaleAbs(normMat, dst, 255); 00424 00425 } 00426 00427 void mixImages(Mat& dst, cv::vector<Mat>& images) { 00428 // No checks at present... 00429 00430 dst = Mat::zeros(images.at(0).size(), CV_64FC3); 00431 Mat tmp; 00432 dst.copyTo(tmp); 00433 00434 00435 for (unsigned int i = 0; i < images.size(); i++) { 00436 00437 for (int m = 0; m < images.at(i).rows; m++) { 00438 00439 for (int n = 0; n < images.at(i).cols; n++) { 00440 00441 for (int k = 0; k < 3; k++) { 00442 dst.at<Vec3d>(m,n)[k] += double((images.at(i)).at<Vec3b>(m,n)[k]) / images.size(); 00443 } 00444 00445 00446 00447 } 00448 00449 00450 } 00451 00452 normalize_64_vec(tmp, dst); 00453 00454 //imshow("tmp", tmp); 00455 //waitKey(0); 00456 00457 } 00458 00459 } 00460 00461 bool rectangle_contains_centroid(cv::Rect mainRectangle, cv::Rect innerRectangle) { 00462 bool retVal = false; 00463 00464 //printf("%s << Main Rectangle: [%d, %d] : [%d, %d]\n", __FUNCTION__, mainRectangle.x, mainRectangle.y, mainRectangle.x+mainRectangle.width, mainRectangle.y+mainRectangle.height); 00465 //printf("%s << Centroid: [%d, %d]\n", __FUNCTION__, innerRectangle.x + innerRectangle.width/2, innerRectangle.y + innerRectangle.height/2); 00466 00467 retVal = mainRectangle.contains(Point(innerRectangle.x + innerRectangle.width/2, innerRectangle.y + innerRectangle.height/2)); 00468 00469 return retVal; 00470 } 00471 00472 Point rectangle_center(cv::Rect input) { 00473 Point center; 00474 00475 center.x = input.x + input.width/2; 00476 center.y = input.y + input.height/2; 00477 00478 00479 return center; 00480 } 00481 00482 double rectangleOverlap(Rect rectangle1, Rect rectangle2) { 00483 00484 double area1, area2, exLeft, exRight, exTop, exBot, overlapArea, overlapProp; 00485 00486 area1 = rectangle1.width*rectangle1.height; 00487 area2 = rectangle2.width*rectangle2.height; 00488 00489 exLeft = max(rectangle1.x, rectangle2.x); 00490 exRight = min(rectangle1.x+rectangle1.width, rectangle2.x+rectangle2.width); 00491 exTop = max(rectangle1.y, rectangle2.y); 00492 exBot = min(rectangle1.y+rectangle1.height, rectangle2.y+rectangle2.height); 00493 00494 if ((exLeft > exRight) || (exTop > exBot)) { 00495 return 0.0; 00496 } 00497 00498 overlapArea = (exRight-exLeft)*(exBot-exTop); 00499 00500 overlapProp = overlapArea / (max(area1, area2)); 00501 00502 return overlapProp; 00503 00504 } 00505 00506 void trimToDimensions(Mat& image, int width, int height) { 00507 00508 Mat dst; 00509 00510 int imWidth = image.cols; 00511 int imHeight = image.rows; 00512 00513 double actualRatio = double(imWidth)/double(imHeight); 00514 double wantedRatio = double(width)/double(height); 00515 00516 int initialWidth, initialHeight; 00517 00518 //imshow("cropping", image); 00519 //waitKey(0); 00520 00521 printf("%s << image dimensions = %d x %d.\n", __FUNCTION__, imWidth, imHeight); 00522 printf("%s << desired dimensions = %d x %d.\n", __FUNCTION__, width, height); 00523 00524 printf("%s << actualRatio = %f; wantedRatio = %f\n", __FUNCTION__, actualRatio, wantedRatio); 00525 00526 if (actualRatio < wantedRatio) { 00527 printf("%s << taller than we want.\n", __FUNCTION__); 00528 00529 initialWidth = width; 00530 initialHeight = int(double(width)/actualRatio); 00531 00532 // resize to get width to exactly desired width 00533 resize(image, dst, Size(initialWidth, initialHeight)); 00534 00535 //imshow("cropping", dst); 00536 //waitKey(0); 00537 00538 // cut down height to desired height 00539 int topY = (dst.rows - height)/2; 00540 int botY = topY + height; 00541 00542 printf("%s << topY = %d; botY = %d\n", __FUNCTION__, topY, botY); 00543 00544 cropImage(dst, Point(0, topY), Point(width, botY)); 00545 00546 //imshow("cropping", dst); 00547 //waitKey(0); 00548 00549 } else if (actualRatio >= wantedRatio) { 00550 printf("%s << wider than we want.\n", __FUNCTION__); 00551 00552 initialWidth = int(double(height)*actualRatio); 00553 initialHeight = height; 00554 00555 // resize to get width to exactly desired width 00556 resize(image, dst, Size(initialWidth, initialHeight)); 00557 00558 //imshow("cropping", dst); 00559 //waitKey(0); 00560 00561 // cut down height to desired height 00562 int leftX = (dst.cols - width)/2; 00563 int rightX = leftX + width; 00564 00565 printf("%s << leftX = %d; rightX = %d\n", __FUNCTION__, leftX , rightX); 00566 00567 cropImage(dst, Point(leftX, 0), Point(rightX, height)); 00568 00569 //imshow("cropping", dst); 00570 //waitKey(0); 00571 00572 } 00573 00574 dst.copyTo(image); 00575 00576 00577 } 00578 00579 void process8bitImage(const Mat& src, Mat& dst, int code, double factor) { 00580 00581 if (code == NORMALIZATION_EQUALIZE) { 00582 00583 equalizeHist(src, dst); 00584 00585 } else if (code == NORMALIZATION_CLAHE) { 00586 00587 //downsampleCLAHE(src, dst, factor); 00588 straightCLAHE(src, dst, factor); 00589 00590 } else { 00591 src.copyTo(dst); 00592 } 00593 } 00594 00595 void adaptiveDownsample(const Mat& src, Mat& dst, int code, double factor) { 00596 00597 Mat dwn, _16; 00598 00599 double minVal, maxVal; 00600 minMaxLoc(src, &minVal, &maxVal); 00601 00602 //printf("%s << min/max = (%f / %f)\n", __FUNCTION__, minVal, maxVal); 00603 00604 00605 00606 //double percentileVals[3] = { MIN_PROP_THRESHOLD, 0.500, 1 - MIN_PROP_THRESHOLD }; 00607 double percentileVals[5] = { 0.001, (factor / 2.0), 0.500, 1.0 - (factor / 2.0), 0.999 }; 00608 double intensityVals[5]; 00609 00610 findPercentiles(src, intensityVals, percentileVals, 5); 00611 00612 intensityVals[1] = max(intensityVals[1], minVal); 00613 intensityVals[3] = min(intensityVals[3], maxVal); 00614 00615 //printf("%s << factor = (%f); vals = (%f, %f)\n", __FUNCTION__, factor, intensityVals[0], intensityVals[2]); 00616 00617 double midVal = (intensityVals[0] + intensityVals[4]) / 2.0; // (intensityVals[0] + intensityVals[2]) / 2.0; 00618 double centralVal = intensityVals[1]; // (maxVal + minVal) / 2.0; // 00619 double halfRange = max(abs(intensityVals[3] - midVal), abs(intensityVals[1] - midVal)); 00620 double fullRange = abs(intensityVals[3] - intensityVals[1]); 00621 double compressionFactor = 1.0; 00622 00623 if (code == NORMALIZATION_STANDARD) { 00624 00625 if (fullRange > 255.0) { 00626 compressionFactor = fullRange / 255.0; 00627 } 00628 00629 minVal = intensityVals[1]; 00630 maxVal = intensityVals[3]; 00631 00632 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl; 00633 00634 normalize_16(_16, src, minVal, maxVal); 00635 down_level(dst, _16); 00636 00637 } else if (code == NORMALIZATION_CENTRALIZED) { 00638 00639 compressionFactor = 255.0 / (4.0 * max(factor, 0.01)); 00640 00641 //printf("%s << centralVal = (%f); compressionFactor = (%f)\n", __FUNCTION__, centralVal, compressionFactor); 00642 minVal = centralVal - compressionFactor; 00643 maxVal = centralVal + compressionFactor; 00644 00645 minVal = max(minVal, 0.0); 00646 maxVal = min(maxVal, 65535.0); 00647 00648 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl; 00649 00650 //minVal = ((intensityVals[0] + intensityVals[2]) / 2.0) - 127.5 * compressionFactor; 00651 //maxVal = ((intensityVals[0] + intensityVals[2]) / 2.0) + 127.5 * compressionFactor; 00652 00653 normalize_16(_16, src, minVal, maxVal); 00654 00655 //imshow("test", _16); 00656 //waitKey(1); 00657 down_level(dst, _16); 00658 00659 } else if (code == NORMALIZATION_EXPANDED) { 00660 00661 compressionFactor = 255.0 / (4.0 * max(factor, 0.01)); 00662 00663 //printf("%s << centralVal = (%f); compressionFactor = (%f)\n", __FUNCTION__, centralVal, compressionFactor); 00664 minVal = midVal - compressionFactor; 00665 maxVal = midVal + compressionFactor; 00666 00667 minVal = max(minVal, 0.0); 00668 maxVal = min(maxVal, 65535.0); 00669 00670 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl; 00671 00672 //minVal = ((intensityVals[0] + intensityVals[2]) / 2.0) - 127.5 * compressionFactor; 00673 //maxVal = ((intensityVals[0] + intensityVals[2]) / 2.0) + 127.5 * compressionFactor; 00674 00675 normalize_16(_16, src, minVal, maxVal); 00676 00677 //imshow("test", _16); 00678 //waitKey(1); 00679 down_level(dst, _16); 00680 00681 } else if (code == NORMALIZATION_EQUALIZE) { 00682 00683 normalize_16(_16, src, intensityVals[1], intensityVals[3]); 00684 down_level(dwn, _16); 00685 equalizeHist(dwn, dst); 00686 00687 } else if (code == NORMALIZATION_CLAHE) { 00688 Mat dst_inter; 00689 adaptiveDownsample(src, dst_inter, NORMALIZATION_STANDARD, 0.001); 00690 straightCLAHE(dst_inter, dst, factor); 00691 00692 } else if (code == NORMALIZATION_ADAPTIVE) { 00693 Mat dst_inter; 00694 double adaptive_factor = min(1.0, (255.0 / (maxVal - minVal)) * factor); 00695 adaptiveDownsample(src, dst_inter, NORMALIZATION_STANDARD, 0.001); 00696 straightCLAHE(dst_inter, dst, adaptive_factor); 00697 00698 } else { 00699 00700 src.convertTo(dst, CV_8UC1); 00701 00702 } 00703 00704 } 00705 00706 double distBetweenPts2f(Point2f& P1, Point2f& P2) 00707 { 00708 /* 00709 double retVal; 00710 retVal = pow((pow(double(P1.x - P2.x), 2.0) + pow(double(P1.y - P2.y),2)), 0.5); 00711 return retVal; 00712 */ 00713 00714 return pow((pow(double(P1.x - P2.x), 2.0) + pow(double(P1.y - P2.y),2)), 0.5); 00715 } 00716 00717 double distBetweenPts(Point& P1, Point& P2) 00718 { 00719 // TODO: 00720 // Possible issue.. see above ^ 00721 00722 double retVal; 00723 retVal = pow(double(pow(double(P1.x - P2.x), 2.0) + pow(double(P1.y - P2.y), 2.0)), 0.5); 00724 return retVal; 00725 } 00726 00727 void drawLinesBetweenPoints(Mat& image, const vector<Point2f>& src, const vector<Point2f>& dst) 00728 { 00729 00730 Point p1, p2; 00731 00732 for (unsigned int i = 0; i < src.size(); i++) 00733 { 00734 p1 = Point(src.at(i).x*16, src.at(i).y*16); 00735 p2 = Point(dst.at(i).x*16, dst.at(i).y*16); 00736 00737 //line(image, p1, p2, CV_RGB(0,0,255), 1, CV_AA, 4); 00738 circle(image, p2, 4*16, CV_RGB(0,0,255), 1, CV_AA, 4); 00739 } 00740 00741 } 00742 00743 Point findCentroid(vector<Point>& contour) 00744 { 00745 Moments momentSet; 00746 00747 double x,y; 00748 00749 momentSet = moments(Mat(contour)); 00750 x = momentSet.m10/momentSet.m00; 00751 y = momentSet.m01/momentSet.m00; 00752 00753 return Point((int)x,(int)y); 00754 } 00755 00756 Point2f findCentroid2f(vector<Point>& contour) 00757 { 00758 Moments momentSet; 00759 00760 double x,y; 00761 00762 momentSet = moments(Mat(contour)); 00763 x = momentSet.m10/momentSet.m00; 00764 y = momentSet.m01/momentSet.m00; 00765 00766 return Point2f(x,y); 00767 } 00768 00769 void createGaussianMatrix(Mat& gaussianMat, double sigmaFactor) 00770 { 00771 00772 Mat distributionDisplay(Size(640, 480), CV_8UC1); 00773 Mat binTemp(gaussianMat.size(), CV_8UC1); 00774 00775 // sigmaFactor says how many standard deviations should span from the center to the nearest edge 00776 // (i.e. along the shortest axis) 00777 00778 00779 // What about an elliptical gaussian function? 00780 00781 Point2f center((float)((double(gaussianMat.size().height-1))/2), (float)((double(gaussianMat.size().width-1))/2)); 00782 Point2f tmpPt; 00783 double dist = 0.0, average = 0.0, maxVal = 0.0; 00784 // double sigma = min(gaussianMat.size().width, gaussianMat.size().height)/(2*sigmaFactor); 00785 00786 // double A = (gaussianMat.size().width*gaussianMat.size().height) / (sigma * pow(2*3.142, 0.5)); 00787 00788 00789 for (int i = 0; i < gaussianMat.size().width; i++) 00790 { 00791 for (int j = 0; j < gaussianMat.size().height; j++) 00792 { 00793 tmpPt = Point2f(float(j), float(i)); 00794 dist = distBetweenPts2f(center, tmpPt); 00795 00796 00797 //gaussianMat.at<double>(j,i) = A*exp(-(pow(dist,2)/(2*pow(sigma,2)))); 00798 //gaussianMat.at<double>(j,i) = dist; 00799 if (dist < max(double(gaussianMat.size().width)/2, double(gaussianMat.size().height)/2)) 00800 { 00801 gaussianMat.at<double>(j,i) = 1.0; 00802 } 00803 else 00804 { 00805 gaussianMat.at<double>(j,i) = 0.0; 00806 } 00807 00808 average += gaussianMat.at<double>(j,i); 00809 00810 if (gaussianMat.at<double>(j,i) > maxVal) 00811 { 00812 maxVal = gaussianMat.at<double>(j,i); 00813 } 00814 00815 //printf("val = %f\n", gaussianMat.at<double>(j,i)); 00816 00817 //gaussianMat.at<double>(j,i) = double(rand()) / RAND_MAX; 00818 } 00819 } 00820 00821 average /= gaussianMat.size().width*gaussianMat.size().height; 00822 00823 gaussianMat /= average; 00824 average = 0.0; 00825 maxVal = 0.0; 00826 00827 for (int i = 0; i < gaussianMat.size().width; i++) 00828 { 00829 for (int j = 0; j < gaussianMat.size().height; j++) 00830 { 00831 average += gaussianMat.at<double>(j,i); 00832 if (gaussianMat.at<double>(j,i) > maxVal) 00833 { 00834 maxVal = gaussianMat.at<double>(j,i); 00835 } 00836 } 00837 } 00838 00839 average /= gaussianMat.size().width*gaussianMat.size().height; 00840 00841 //printf("%s << average val = %f\n", __FUNCTION__, average); 00842 //cin.get(); 00843 00844 /* 00845 convertScaleAbs(gaussianMat, binTemp, (255.0/maxVal), 0); 00846 svLib::simpleResize(binTemp, distributionDisplay, Size(480, 640)); 00847 //equalizeHist(distributionDisplay, distributionDisplay); 00848 imshow("gaussianMat", distributionDisplay); 00849 waitKey(40); 00850 */ 00851 } 00852 00853 void cropImage(Mat& image, Point tl, Point br) 00854 { 00855 // not compatible with all image types yet... 00856 00857 int width, height, xOff, yOff; 00858 00859 //printf("%s << Starting function.\n", __FUNCTION__); 00860 00861 //printf("%s << TL = (%d, %d); BR = (%d, %d)\n", __FUNCTION__, tl.x, tl.y, br.x, br.y); 00862 00863 width = abs(br.x-tl.x); 00864 height = abs(br.y-tl.y); 00865 00866 xOff = min(tl.x, br.x); 00867 yOff = min(tl.y, br.y); 00868 00869 //printf("%s << width = %d, height = %d, xOff = %d, yOff = %d\n", __FUNCTION__, width, height, xOff, yOff); 00870 00871 //cin.get(); 00872 00873 Mat tmpMat; 00874 00875 if (image.channels() == 3) 00876 { 00877 tmpMat = Mat(height, width, CV_8UC3); 00878 } 00879 else if (image.channels() == 1) 00880 { 00881 tmpMat = Mat(height, width, CV_8UC1); 00882 } 00883 00884 00885 00886 for (int i = 0; i < width; i++) 00887 { 00888 for (int j = 0; j < height; j++) 00889 { 00890 //printf("%s << %d / %d\n", __FUNCTION__, i, j); 00891 00892 if (image.channels() == 3) 00893 { 00894 if ((j+yOff < 0) || (j+yOff > image.rows-1) || (i+xOff < 0) || (i+xOff > image.cols-1)) 00895 { 00896 tmpMat.at<Vec3b>(j,i)[0] = 0; 00897 tmpMat.at<Vec3b>(j,i)[1] = 0; 00898 tmpMat.at<Vec3b>(j,i)[2] = 0; 00899 } 00900 else 00901 { 00902 tmpMat.at<Vec3b>(j,i) = image.at<Vec3b>(j+yOff,i+xOff); 00903 } 00904 } 00905 else if (image.channels() == 1) 00906 { 00907 if ((j+yOff < 0) || (j+yOff > image.rows-1) || (i+xOff < 0) || (i+xOff > image.cols-1)) 00908 { 00909 tmpMat.at<unsigned char>(j,i) = 0; 00910 } 00911 else 00912 { 00913 tmpMat.at<unsigned char>(j,i) = image.at<unsigned char>(j+yOff,i+xOff); 00914 } 00915 00916 00917 } 00918 00919 00920 00921 00922 } 00923 } 00924 00925 //tmpMat.copyTo(image); 00926 resize(tmpMat, image, Size(width, height)); // working 00927 00928 //printf("%s << Completing function.\n", __FUNCTION__); 00929 00930 } 00931 00932 void convertVectorToPoint(vector<Point2f>& input, vector<Point>& output) 00933 { 00934 output.clear(); 00935 00936 for (unsigned int i = 0; i < input.size(); i++) 00937 { 00938 output.push_back(Point((int)input.at(i).x, (int)input.at(i).y)); 00939 } 00940 } 00941 00942 void convertVectorToPoint2f(vector<Point>& input, vector<Point2f>& output) 00943 { 00944 // TODO: 00945 // Nothing much. 00946 00947 output.clear(); 00948 00949 for (unsigned int i = 0; i < input.size(); i++) 00950 { 00951 output.push_back(Point2f((float)input.at(i).x, (float)input.at(i).y)); 00952 } 00953 } 00954 00955 void simpleResize(Mat& src, Mat& dst, Size size) 00956 { 00957 00958 dst = Mat::zeros(size, src.type()); 00959 00960 for (int i = 0; i < dst.size().width; i++) 00961 { 00962 for (int j = 0; j < dst.size().height; j++) 00963 { 00964 if (src.depth() == 1) 00965 { 00966 dst.at<unsigned char>(j,i) = src.at<unsigned char>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width); 00967 } 00968 else if (src.depth() == 8) 00969 { 00970 dst.at<double>(j,i) = src.at<double>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width); 00971 } 00972 else if (src.depth() == CV_16U) 00973 { 00974 dst.at<unsigned short>(j,i) = src.at<unsigned short>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width); 00975 } 00976 00977 } 00978 } 00979 } 00980 00981 void copyContour(vector<Point>& src, vector<Point>& dst) 00982 { 00983 // TODO: 00984 // Make safer. 00985 00986 dst.clear(); 00987 00988 for (unsigned int i = 0; i < src.size(); i++) 00989 { 00990 dst.push_back(src.at(i)); 00991 } 00992 } 00993 00994 void swapElements(vector<Point2f>& corners, int index1, int index2) 00995 { 00996 // TODO: 00997 // Nothing much. 00998 00999 Point2f tempPt; 01000 01001 tempPt = corners.at(index1); // copy first element to temp 01002 corners.at(index1) = corners.at(index2); // put best element in first 01003 corners.at(index2) = tempPt; // copy temp to where best element was 01004 } 01005 01006 void invertMatIntensities(const Mat& src, Mat& dst) 01007 { 01008 dst.release(); 01009 dst = Mat(src.size(), src.type()); 01010 01011 if (src.type() == CV_8UC1) 01012 { 01013 01014 01015 #pragma omp parallel for 01016 for (int iii = 0; iii < src.rows; iii++) 01017 { 01018 for (int jjj = 0; jjj < src.cols; jjj++) 01019 { 01020 dst.at<unsigned char>(iii,jjj) = 255 - src.at<unsigned char>(iii, jjj); 01021 } 01022 } 01023 01024 } 01025 else if (src.type() == CV_8UC3) 01026 { 01027 01028 // printf("%s << here.\n", __FUNCTION__); 01029 #pragma omp parallel for 01030 for (int iii = 0; iii < src.rows; iii++) 01031 { 01032 for (int jjj = 0; jjj < src.cols; jjj++) 01033 { 01034 //a = src.at<Vec3b>(iii, jjj)[0]; 01035 //z = std::max(std::min(255, int(255 - (1.5*(a - 128)+128))),0); 01036 //dst.at<Vec3b>(iii, jjj)[0] = z; 01037 //dst.at<Vec3b>(iii, jjj)[1] = z; 01038 //dst.at<Vec3b>(iii, jjj)[2] = z; 01039 01040 dst.at<Vec3b>(iii, jjj)[0] = 255 - src.at<Vec3b>(iii, jjj)[0]; 01041 dst.at<Vec3b>(iii, jjj)[1] = 255 - src.at<Vec3b>(iii, jjj)[1]; 01042 dst.at<Vec3b>(iii, jjj)[2] = 255 - src.at<Vec3b>(iii, jjj)[2]; 01043 } 01044 } 01045 } 01046 01047 //imshow("dst", dst); 01048 //waitKey(); 01049 01050 } 01051 01052 void contourDimensions(vector<Point> contour, double& width, double& height) 01053 { 01054 // TODO: 01055 // May want to replace this with something that finds the longest and shortest distances across 01056 // Because the idea of this is to help determine if it's a square or not. 01057 01058 // new methodology 01059 RotatedRect wrapperRectangle; 01060 Size size; 01061 vector<Point> contourCpy; 01062 Point meanPoint; 01063 01064 // Interpolate contour to get it to an adequate size for "fitEllipse" function 01065 if (contour.size() < 6) 01066 { 01067 for (unsigned int i = 0; i < contour.size()-1; i++) 01068 { 01069 contourCpy.push_back(contour.at(i)); 01070 meanPoint.x = (2*contour.at(i).x + 1*contour.at(i+1).x) / 3; 01071 meanPoint.y = (2*contour.at(i).y + 1*contour.at(i+1).y) / 3; 01072 contourCpy.push_back(meanPoint); 01073 meanPoint.x = (1*contour.at(i).x + 2*contour.at(i+1).x) / 3; 01074 meanPoint.y = (1*contour.at(i).y + 2*contour.at(i+1).y) / 3; 01075 contourCpy.push_back(meanPoint); 01076 } 01077 01078 contourCpy.push_back(contour.at(contour.size()-1)); 01079 meanPoint.x = (2*contour.at(contour.size()-1).x + 1*contour.at(0).x) / 3; 01080 meanPoint.y = (2*contour.at(contour.size()-1).y + 1*contour.at(0).y) / 3; 01081 contourCpy.push_back(meanPoint); 01082 meanPoint.x = (1*contour.at(contour.size()-1).x + 2*contour.at(0).x) / 3; 01083 meanPoint.y = (1*contour.at(contour.size()-1).y + 2*contour.at(0).y) / 3; 01084 contourCpy.push_back(meanPoint); 01085 01086 } 01087 else 01088 { 01089 contourCpy.assign(contour.begin(), contour.end()); 01090 } 01091 01092 wrapperRectangle = fitEllipse(Mat(contourCpy)); 01093 size = wrapperRectangle.size; 01094 width = size.width; 01095 height = size.height; 01096 01097 // old methodology... (simply using highest and lowest X and Y values..) 01098 /* 01099 double xMax = 0.0, yMax = 0.0, xMin = 99999.0, yMin = 99999.0; 01100 01101 for (unsigned int i = 0; i < contour.size(); i++) { 01102 01103 if (contour.at(i).x > xMax) { 01104 xMax = contour.at(i).x; 01105 } 01106 01107 if (contour.at(i).y > yMax) { 01108 yMax = contour.at(i).y; 01109 } 01110 01111 if (contour.at(i).x < xMin) { 01112 xMin = contour.at(i).x; 01113 } 01114 01115 if (contour.at(i).y < yMin) { 01116 yMin = contour.at(i).y; 01117 } 01118 01119 } 01120 01121 width = xMax - xMin; 01122 height = yMax - yMin; 01123 */ 01124 } 01125 01126 double perpDist(Point2f& P1, Point2f& P2, Point2f& P3) 01127 { 01128 // TODO: 01129 // There may be some kind of issue occuring here... check the bug list at the top of this file 01130 01131 // P3 is the test point 01132 double u, x, y, d; 01133 01134 u = ((P3.x - P1.x)*(P2.x - P1.x) + (P3.y - P1.y)*(P2.y - P1.y)) / (pow(double(P2.x - P1.x), 2.0) + pow(double(P2.y - P1.y), 2.0)); 01135 01136 /* 01137 printf("denominator = %f\n", pow(double(P2.x - P1.x), 2.0) - pow(double(P2.y - P1.y), 2.0)); 01138 printf("P1 = %f,%f\n", P1.x, P1.y); 01139 printf("P2 = %f,%f\n", P2.x, P2.y); 01140 printf("P3 = %f,%f\n", P3.x, P3.y); 01141 printf("u = %f\n", u); 01142 */ 01143 01144 x = P1.x + u*(P2.x - P1.x); 01145 y = P1.y + u*(P2.y - P1.y); 01146 01147 d = pow(pow(P3.x - x, 2.0) + pow(P3.y - y, 2.0),0.5); 01148 01149 return d; 01150 } 01151 01152 double findMinimumSeparation(vector<Point2f>& pts) 01153 { 01154 double minSep = 9e50; 01155 double val = 0.0; 01156 01157 for (unsigned int i = 0; i < pts.size(); i++) 01158 { 01159 for (unsigned int j = i+1; j < pts.size(); j++) 01160 { 01161 val = norm(pts.at(i)-pts.at(j)); 01162 if (val < minSep) 01163 { 01164 minSep = val; 01165 } 01166 } 01167 } 01168 01169 return minSep; 01170 } 01171 01172 Point2f meanPoint(Point2f& P1, Point2f& P2) 01173 { 01174 return Point2f((P1.x+P2.x)/2, (P1.y+P2.y)/2); 01175 } 01176 01177 void transferElement(vector<Point2f>& dst, vector<Point2f>& src, int index) 01178 { 01179 Point2f pointCpy; 01180 01181 pointCpy = src.at(index); 01182 01183 // Move from old one to new one 01184 dst.push_back(pointCpy); 01185 01186 // Replace and shift points in old one 01187 for (unsigned int i = index; i < src.size()-1; i++) 01188 { 01189 src.at(i) = src.at(i+1); 01190 } 01191 01192 // Truncate the original vector (effectively discarding old point) 01193 src.pop_back(); 01194 } 01195 01196 01197 bool checkIfActuallyGray(const Mat& im) { 01198 01199 bool retVal = true; 01200 01201 for (int iii = 0; iii < im.rows; iii++) { 01202 for (int jjj = 0; jjj < im.cols; jjj++) { 01203 01204 if (im.at<Vec3b>(iii,jjj)[0] != im.at<Vec3b>(iii,jjj)[1]) { 01205 return false; 01206 } 01207 01208 if (im.at<Vec3b>(iii,jjj)[2] != im.at<Vec3b>(iii,jjj)[1]) { 01209 return false; 01210 } 01211 01212 } 01213 } 01214 01215 return retVal; 01216 01217 } 01218 01219 void findPercentiles(const Mat& img, double *vals, double *percentiles, unsigned int num) { 01220 01221 //double median = 0.0; 01222 01223 Mat mx; 01224 01225 unsigned int *aimedPixelCounts; 01226 aimedPixelCounts = new unsigned int[num]; 01227 01228 for (unsigned int iii = 0; iii < num; iii++) { 01229 aimedPixelCounts[iii] = (unsigned int) (((double) img.rows) * ((double) img.cols) * percentiles[iii]); 01230 //printf("%s << aimedPixelCounts[%d] = %d (%f)\n", __FUNCTION__, iii, aimedPixelCounts[iii], percentiles[iii]); 01231 } 01232 01233 //cin.get(); 01234 01235 //if (img.type() == CV_16UC1) { 01236 img.convertTo(mx, CV_32FC1); 01237 //} 01238 01239 MatND hist; 01240 int channels[] = {0}; 01241 int ibins = 65536; 01242 int histSize[] = {ibins}; 01243 float iranges[] = { 0, 65535 }; 01244 const float* ranges[] = { iranges }; 01245 01246 calcHist(&mx, 1, channels, Mat(), hist, 1, histSize, ranges); 01247 01248 unsigned int pointsTally = 0; 01249 01250 bool allCountsReached = false; 01251 01252 for (int i = 0; i < ibins; i++) { 01253 01254 pointsTally += (unsigned int)(hist.at<float>(i)); 01255 01256 if (pointsTally > 0) { 01257 //printf("%s << hist(%d) = %f\n", __FUNCTION__, i, hist.at<float>(i)); 01258 } 01259 01260 allCountsReached = true; 01261 01262 for (unsigned int iii = 0; iii < num; iii++) { 01263 if (pointsTally <= aimedPixelCounts[iii]) { 01264 vals[iii] = i; 01265 //printf("%s << vals[%d] = %f\n", __FUNCTION__, iii, vals[iii]); 01266 allCountsReached = false; 01267 } 01268 } 01269 01270 if (allCountsReached) { 01271 return; 01272 } 01273 01274 01275 //printf("%s << histval(%d) = %f\n", __FUNCTION__, i, hist.at<float>(i)); 01276 } 01277 01278 //cin.get(); 01279 01280 } 01281 01282 void shiftIntensities(Mat& im, double scaler, double shifter, double downer) { 01283 01284 double val; 01285 for (int iii = 0; iii < im.rows; iii++) { 01286 for (int jjj = 0; jjj < im.cols; jjj++) { 01287 01288 val = ((double) im.at<unsigned char>(iii,jjj)); 01289 01290 val -= downer; 01291 01292 val *= scaler; 01293 01294 val += (downer + shifter); 01295 01296 im.at<unsigned char>(iii,jjj) = ((unsigned char) val); 01297 01298 } 01299 } 01300 01301 } 01302 01303 void findIntensityValues(double *vals, Mat& im, Mat& mask) { 01304 01305 vals[0] = 9e99; 01306 vals[1] = -9e99; 01307 vals[2] = 0.0; 01308 01309 unsigned int activeCount = countNonZero(mask); 01310 01311 if (activeCount == 0) { 01312 return; 01313 } 01314 01315 unsigned int hist[256]; 01316 01317 for (unsigned int iii = 0; iii < 256; iii++) { 01318 hist[iii] = 0; 01319 } 01320 01321 for (int iii = 0; iii < im.rows; iii++) { 01322 for (int jjj = 0; jjj < im.cols; jjj++) { 01323 01324 if (mask.at<unsigned char>(iii,jjj) != 0) { 01325 vals[2] += ((double) im.at<unsigned char>(iii,jjj)) / ((double) activeCount); 01326 01327 if (((double) im.at<unsigned char>(iii,jjj)) < vals[0]) { 01328 vals[0] = ((double) im.at<unsigned char>(iii,jjj)); 01329 } 01330 01331 if (((double) im.at<unsigned char>(iii,jjj)) > vals[1]) { 01332 vals[1] = ((double) im.at<unsigned char>(iii,jjj)); 01333 } 01334 01335 hist[im.at<unsigned char>(iii,jjj)]++; 01336 01337 } 01338 01339 } 01340 } 01341 01342 unsigned int intensityCount = 0; 01343 int intensityPtr = -1; 01344 unsigned int medianCount = countNonZero(mask); 01345 01346 while (intensityCount < (medianCount/2)) { 01347 intensityPtr++; 01348 intensityCount += hist[intensityPtr]; 01349 } 01350 01351 vals[3] = intensityPtr; 01352 01353 01354 } 01355 01356 void cScheme::setupLookupTable(unsigned int depth) { 01357 01358 unsigned int maxIndex, level; 01359 01360 if (depth == 2) { 01361 maxIndex = 65536; 01362 } else if (depth == 1) { 01363 maxIndex = 256; 01364 } else { 01365 maxIndex = 256; 01366 } 01367 01368 for (unsigned int iii = 0; iii < maxIndex; iii++) { 01369 01370 level = (int) floor(double((iii*(MAP_LENGTH-1))/((double) (maxIndex-1)))); // for 16 bits/pixel 01371 01372 if (depth == 2) { 01373 lookupTable_2[iii][2] = (unsigned short) (255.0 * red[level]); 01374 lookupTable_2[iii][1] = (unsigned short) (255.0 * green[level]); 01375 lookupTable_2[iii][0] = (unsigned short) (255.0 * blue[level]); 01376 01377 //printf("%s << LT(%d) = (%d, %d, %d)\n", __FUNCTION__, iii, lookupTable_2[iii][2], lookupTable_2[iii][1], lookupTable_2[iii][0]); 01378 } else if (depth == 1) { 01379 lookupTable_1[iii][2] = (unsigned char) (255.0 * red[level]); 01380 lookupTable_1[iii][1] = (unsigned char) (255.0 * green[level]); 01381 lookupTable_1[iii][0] = (unsigned char) (255.0 * blue[level]); 01382 //printf("%s << LT(%d) = (%d, %d, %d)\n", __FUNCTION__, iii, lookupTable_1[iii][2], lookupTable_1[iii][1], lookupTable_1[iii][0]); 01383 } 01384 01385 01386 } 01387 01388 } 01389 01390 void obtainEightBitRepresentation(Mat& src, Mat& dst) { 01391 if (src.type() == CV_8UC1) { 01392 dst = src; 01393 } else if (src.type() == CV_8UC3) { 01394 cvtColor(src, dst, CV_RGB2GRAY); 01395 } else if (src.type() == CV_16UC1) { 01396 Mat nMat; 01397 double currMin, currMax; 01398 minMaxLoc(src, &currMin, &currMax); 01399 normalize_16(nMat, src, currMin, currMax); 01400 down_level(dst, nMat); 01401 } else if (src.type() == CV_16UC3) { 01402 Mat nMat, tMat; 01403 cvtColor(src, tMat, CV_RGB2GRAY); 01404 double currMin, currMax; 01405 minMaxLoc(tMat, &currMin, &currMax); 01406 normalize_16(nMat, tMat, currMin, currMax); 01407 down_level(dst, nMat); 01408 } 01409 } 01410 01411 void obtainColorRepresentation(Mat& src, Mat& dst) { 01412 if (src.type() == CV_8UC1) { 01413 cvtColor(src, dst, CV_GRAY2RGB); 01414 } else if (src.type() == CV_8UC3) { 01415 dst = src; 01416 } else if (src.type() == CV_16UC1) { 01417 Mat nMat, tMat; 01418 double currMin, currMax; 01419 minMaxLoc(src, &currMin, &currMax); 01420 normalize_16(nMat, src, currMin, currMax); 01421 down_level(tMat, nMat); 01422 cvtColor(tMat, dst, CV_GRAY2RGB); 01423 } else if (src.type() == CV_16UC3) { 01424 Mat nMat, tMat, tMat2; 01425 double currMin, currMax; 01426 cvtColor(src, tMat, CV_RGB2GRAY); 01427 minMaxLoc(tMat, &currMin, &currMax); 01428 normalize_16(nMat, tMat, currMin, currMax); 01429 down_level(tMat2, nMat); 01430 cvtColor(tMat2, dst, CV_GRAY2RGB); 01431 } 01432 } 01433 01434 void fix_bottom_right(Mat& mat) { 01435 01436 for (int iii = (mat.cols-6); iii < mat.cols; iii++) { 01437 mat.at<unsigned short>(mat.rows-1, iii) = std::max( std::min(( (unsigned int) ((mat.at<unsigned short>(mat.rows-2, iii) + mat.at<unsigned short>(mat.rows-1, iii-1)) / 2.0) ), (unsigned int) 65535) , (unsigned int) 0); 01438 } 01439 } 01440 01441 void down_level(Mat& dst, Mat& src) { 01442 01443 // Currently only works for a single channel image i.e. CV_16UC1 01444 dst = Mat(src.rows, src.cols, CV_8UC1); 01445 01446 //unsigned int val; 01447 for (int i = 0; i < dst.size().height; i++) { 01448 for (int j = 0; j < dst.size().width; j++) { 01449 dst.at<unsigned char>(i,j) = (src.at<unsigned short>(i,j)) / 256; 01450 } 01451 01452 } 01453 } 01454 01455 void reduceToPureImage(cv::Mat& dst, cv::Mat& src) { 01456 01457 01458 if (dst.cols == 0) { 01459 if (src.type() == CV_16UC3) { 01460 dst = Mat(src.size(), CV_16UC1); 01461 } else if (src.type() == CV_8UC3) { 01462 dst = Mat(src.size(), CV_8UC1); 01463 } 01464 01465 } 01466 01467 for (int iii = 0; iii < src.cols; iii++) { 01468 for (int jjj = 0; jjj < src.rows; jjj++) { 01469 if (src.type() == CV_16UC3) { 01470 if (((src.at<Vec3s>(jjj,iii)[0]) == (src.at<Vec3s>(jjj,iii)[1])) && ((src.at<Vec3s>(jjj,iii)[2]) == (src.at<Vec3s>(jjj,iii)[1]))) { 01471 dst.at<unsigned short>(jjj,iii) = src.at<Vec3s>(jjj,iii)[0]; 01472 } else { 01473 dst.at<unsigned short>(jjj,iii) = (unsigned short) (0.299 * (double) src.at<Vec3s>(jjj,iii)[0] + 0.587 * (double) src.at<Vec3s>(jjj,iii)[1] + 0.114 * (double) src.at<Vec3s>(jjj,iii)[2]); 01474 } 01475 01476 } else if (src.type() == CV_8UC3) { 01477 if (((src.at<Vec3b>(jjj,iii)[0]) == (src.at<Vec3b>(jjj,iii)[1])) && ((src.at<Vec3b>(jjj,iii)[2]) == (src.at<Vec3b>(jjj,iii)[1]))) { 01478 dst.at<unsigned char>(jjj,iii) = src.at<Vec3b>(jjj,iii)[0]; 01479 } else { 01480 dst.at<unsigned char>(jjj,iii) = (unsigned char) (0.299 * (double) src.at<Vec3b>(jjj,iii)[0] + 0.587 * (double) src.at<Vec3b>(jjj,iii)[1] + 0.114 * (double) src.at<Vec3b>(jjj,iii)[2]); 01481 } 01482 01483 } 01484 01485 } 01486 } 01487 } 01488 01489 void addBorder(Mat& inputMat, int borderSize) { 01490 Mat newMat = Mat::zeros(inputMat.rows + 2*borderSize, inputMat.cols + 2*borderSize, CV_8UC3); 01491 01492 for (int i = borderSize; i < newMat.rows-borderSize; i++) { 01493 for (int j = borderSize; j < newMat.cols-borderSize; j++) { 01494 newMat.at<Vec3b>(i,j) = inputMat.at<Vec3b>(i-borderSize, j-borderSize); 01495 } 01496 } 01497 01498 newMat.copyTo(inputMat); 01499 01500 } 01501 01502 void normalize_64_vec(Mat& dst, Mat& src) { 01503 01504 //printf("%s << Entered...\n", __FUNCTION__); 01505 01506 dst = Mat(src.size(), src.type()); 01507 01508 double minVal = 9e50, maxVal = -9e50; 01509 01510 for (int i = 0; i < src.rows; i++) { 01511 for (int j = 0; j < src.cols; j++) { 01512 for (int k = 0; k < src.channels(); k++) { 01513 if (src.at<Vec3d>(i,j)[k] > maxVal) { 01514 maxVal = src.at<Vec3d>(i,j)[k]; 01515 } 01516 01517 if (src.at<Vec3d>(i,j)[k] < minVal) { 01518 minVal = src.at<Vec3d>(i,j)[k]; 01519 } 01520 } 01521 01522 01523 } 01524 } 01525 01526 for (int i = 0; i < src.rows; i++) { 01527 for (int j = 0; j < src.cols; j++) { 01528 for (int k = 0; k < src.channels(); k++) { 01529 dst.at<Vec3d>(i,j)[k] = max(min(((src.at<Vec3d>(i,j)[k] - minVal) / (maxVal - minVal)), 1.0),0.0); 01530 } 01531 01532 01533 } 01534 } 01535 } 01536 01537 void normalize_16(Mat& dst, const Mat& src, double dblmin, double dblmax) { 01538 01539 unsigned short minv, maxv; 01540 bool presetLimits; 01541 01542 double lower_bound = 0.0, upper_bound = 65535.0; 01543 01544 if ((dblmin > -1.0) && (dblmax > -1.0)) { 01545 presetLimits = true; 01546 //cout << "preset == true" << endl; 01547 } else { 01548 presetLimits = false; 01549 } 01550 01551 minv = 65535; 01552 maxv = 0; 01553 01554 //printf("%s << min = %d; max = %d\n", __FUNCTION__, min, max); 01555 01556 unsigned short val; //, new_val; 01557 //double limitTester; 01558 01559 Size matSize = src.size(); 01560 src.copyTo(dst); 01561 01562 // Safety checks 01563 if ((src.size().height != dst.size().height) || (src.size().width != dst.size().width)) { 01564 printf("svLib::normalize_16() << Image dimensions don't match.\n"); 01565 return; 01566 } 01567 01568 01569 01570 if (1) { // (!presetLimits) { 01571 01572 for (int i = 0; i < matSize.height; i++) { 01573 for (int j = 0; j < matSize.width; j++) { 01574 val = src.at<unsigned short>(i,j); // how do I incorporate channels? 01575 01576 if (val < minv) { 01577 minv = val; 01578 } 01579 01580 if (val > maxv) { 01581 maxv = val; 01582 } 01583 } 01584 } 01585 01586 } else { 01587 minv = (unsigned short) dblmin; 01588 maxv = (unsigned short) dblmax; 01589 01590 } 01591 01592 if (!presetLimits) { 01593 dblmin = double(minv); 01594 dblmax = double(maxv); 01595 } 01596 01597 // dblmin, dblmax are the limits you want to use for normalization 01598 // minv, maxv are the actual limits of the image 01599 01600 //cout << "minv = " << minv << ", maxv = " << maxv << endl; 01601 01602 //unsigned short abs_min = std::max(minv, (unsigned short) dblmin); 01603 //unsigned short abs_max = std::min(maxv, (unsigned short) dblmax); 01604 01605 #pragma omp parallel for 01606 for (int i = 0; i < matSize.height; i++) { 01607 for (int j = 0; j < matSize.width; j++) { 01608 dst.at<unsigned short>(i,j) = std::max((unsigned short) dblmin, std::min((unsigned short) dblmax, src.at<unsigned short>(i,j))); 01609 } 01610 } 01611 01612 // Compare actual min with the desired min in order to determine lower bound... 01613 01614 //double total_range = abs(std::min(dblmin, double(minv)) - std::max(dblmax, double(maxv))); 01615 01616 double total_range = dblmax - dblmin; 01617 01618 //printf("%s << (minv / dblmin) = (%f, %f); (maxv / dblmax) = (%f, %f)\n", __FUNCTION__, double(minv), dblmin, double(maxv), dblmax); 01619 01620 //cout << "total_range = " << total_range << endl; 01621 01622 if (double(minv) > dblmin) { 01623 lower_bound = 65535.0 * (abs(double(minv) - dblmin) / total_range); 01624 } 01625 01626 if (double(maxv) < dblmax) { 01627 upper_bound = 65535.0 - 65535.0 * (abs(double(maxv) - dblmax) / total_range); 01628 } 01629 01630 //printf("%s << lower_bound = (%f); upper_bound = (%f)\n", __FUNCTION__, lower_bound, upper_bound); 01631 01632 01633 normalize(dst, dst, lower_bound, upper_bound, NORM_MINMAX); 01634 01635 return; 01636 01637 /* 01638 //printf("PURPLE MONKEY!\n"); 01639 01640 //printf("%s << Debug %d.\n", __FUNCTION__, -1); 01641 01642 // Perform image processing 01643 for (int i = 0; i < matSize.height; i++) { 01644 for (int j = 0; j < matSize.width; j++) { 01645 for (int k = 0; k < src.channels(); k++) { 01646 val = src.at<unsigned short>(i,j); // how do I incorporate channels? 01647 01648 if (val < min) { 01649 val = min; 01650 } else if (val > max) { 01651 val = max; 01652 } 01653 // attempt at normalization 01654 01655 limitTester = std::max(double(val - min), 0.0); 01656 limitTester *= 65535.0/(max-min); 01657 01658 if (limitTester < 0) { 01659 //printf("%s << limitTester too low: %f\n", __FUNCTION__, limitTester); 01660 //cin.get(); 01661 limitTester = 0; 01662 } else if (limitTester > 65535) { 01663 //printf("%s << limitTester too high: %f\n", __FUNCTION__, limitTester); 01664 //cin.get(); 01665 limitTester = 65535; 01666 } 01667 01668 new_val = (unsigned short) limitTester; 01669 01670 //new_val = (unsigned short) (65535*((double(val - min))/(double(max - min)))); // 255 for VXL.. 01671 01672 //printf("%s << val = %d; new_val = %d\n", __FUNCTION__, val, new_val); 01673 01674 if (new_val == 0) { 01675 if (1) { 01676 //printf("%s << val = %d; new_val = %d\n", __FUNCTION__, val, new_val); 01677 //cin.get(); 01678 } 01679 } 01680 01681 dst.at<unsigned short>(i,j) = new_val; 01682 } 01683 } 01684 } 01685 01686 //printf("%s << min = %d; max = %d\n", __FUNCTION__, min, max); 01687 //cin.get(); 01688 */ 01689 } 01690 01691 cScheme::cScheme() { 01692 load_standard(100); 01693 } 01694 01695 cScheme::cScheme(double *d, double *r, double *g, double *b, int len) { 01696 code = CUSTOM; 01697 dx = d; 01698 rx = r; 01699 gx = g; 01700 bx = b; 01701 length = len; 01702 } 01703 01704 cScheme::~cScheme() { } 01705 01706 void cScheme::create_long_map() { 01707 01708 int element, i; 01709 01710 double e, segs, iy, M, fact; 01711 01712 segs = (double) (length-1); 01713 M = (double) MAP_LENGTH; 01714 01715 // Fill in initial elements 01716 red[0] = rx[0]; 01717 green[0] = gx[0]; 01718 blue[0] = bx[0]; 01719 01720 int start_el = 0, finish_el; 01721 01722 //cout << "Starting interpolation..." << endl; 01723 01724 // Interpolate 01725 for (int iii = 0; iii < segs; iii++) { 01726 01727 //cout << "start_el = " << start_el << endl; 01728 01729 //cout << "dx[iii] = " << dx[iii] << endl; 01730 //cout << "dx[iii+1] = " << dx[iii+1] << endl; 01731 //cout << "MAP_LENGTH = " << MAP_LENGTH << endl; 01732 01733 finish_el = int(dx[iii+1] * double(MAP_LENGTH-1)); 01734 01735 //cout << "finish_el = " << finish_el << endl; 01736 01737 for (int jjj = start_el; jjj < finish_el; jjj++) { 01738 01739 element = iii; 01740 01741 e = (double) element; 01742 iy = (double) jjj; 01743 fact = (double(jjj) - double(start_el)) / (double(finish_el) - double(start_el)); 01744 01745 //cout << "jjj = " << jjj << endl; 01746 //cout << "fact = " << fact << endl; 01747 01748 01749 //cout << "start_el = " << start_el << endl; 01750 01751 //cout << "rx[element] = " << rx[element] << endl; 01752 //cout << "gx[element] = " << gx[element] << endl; 01753 //cout << "bx[element] = " << bx[element] << endl; 01754 01755 red[jjj] = rx[element] + fact*(rx[element+1] - rx[element]); 01756 green[jjj] = gx[element] + fact*(gx[element+1] - gx[element]); 01757 blue[jjj] = bx[element] + fact*(bx[element+1] - bx[element]); 01758 01759 //cout << "red[jjj] = " << red[jjj] << endl; 01760 //cout << "green[jjj] = " << green[jjj] << endl; 01761 //cout << "blue[jjj] = " << blue[jjj] << endl; 01762 01763 } 01764 01765 start_el = finish_el; 01766 } 01767 01768 //cout << "Finishing interpolation..." << endl; 01769 01770 01771 // Fill in final elements 01772 red[MAP_LENGTH-1] = rx[length-1]; 01773 green[MAP_LENGTH-1] = gx[length-1]; 01774 blue[MAP_LENGTH-1] = bx[length-1]; 01775 01776 } 01777 01778 // Should be: 01779 // Every ten units from 100 - 990 corresponds to a new colour scheme 01780 // 100*N + 2*v + a: v corresponds to a different 'variation'; a can equal 1 or 0 - if 1, can include black 01781 // and/or white (a = 0 is basically a safe version [if needed] for image fusion) 01782 01783 void cScheme::load_standard(int mapCode, int mapParam) { 01784 01785 code = mapCode + mapParam; 01786 01787 double *dd; 01788 double da[256]; 01789 01790 bool flexibleMarkers = false; 01791 01792 if (code == GRAYSCALE) { 01793 length = 2; 01794 double rr [] = { 0, 1 }; 01795 double gg [] = { 0, 1 }; 01796 double bb [] = { 0, 1 }; 01797 rx = rr; 01798 gx = gg; 01799 bx = bb; 01800 } else if (code == (GRAYSCALE + 1)) { 01801 length = 2; 01802 double rr [] = { 0.2, 0.8 }; 01803 double gg [] = { 0.2, 0.8 }; 01804 double bb [] = { 0.2, 0.8 }; 01805 rx = rr; 01806 gx = gg; 01807 01808 bx = bb; 01809 } else if (code == HIGHLIGHTED) { 01810 length = 4; 01811 flexibleMarkers = true; 01812 double da [] = { 0.0, 0.5, 0.5, 1.0 }; 01813 double rr [] = { 0, 1.0, 1.0, 1.0 }; 01814 double gg [] = { 0, 1.0, 0.0, 0.0 }; 01815 double bb [] = { 0, 1.0, 0.0, 0.0 }; 01816 dd = da; 01817 rx = rr; 01818 gx = gg; 01819 bx = bb; 01820 } else if (code == (HIGHLIGHTED + 1)) { 01821 length = 4; 01822 flexibleMarkers = true; 01823 double da [] = { 0.25, 0.5, 0.5, 1.0 }; 01824 double rr [] = { 0.25, 0.75, 1.0, 1.0 }; 01825 double gg [] = { 0.25, 0.75, 0.0, 0.0 }; 01826 double bb [] = { 0.25, 0.75, 0.0, 0.0 }; 01827 dd = da; 01828 rx = rr; 01829 gx = gg; 01830 bx = bb; 01831 } else if (code == CIECOMP) { 01832 length = 33; 01833 double rr [] = { 1.000000, 0.765154, 0.514649, 0.264229, 0.082532, 0.004867, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000541, 0.062517, 0.246214, 0.493080, 0.743824, 0.931596, 0.996408, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000 }; 01834 double gg [] = { 1.000000, 1.000000, 1.000000, 1.000000, 0.964432, 0.859914, 0.717154, 0.572201, 0.435801, 0.319831, 0.214279, 0.109202, 0.031115, 0.002438, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000889, 0.020277, 0.077613, 0.155367, 0.234768, 0.334034, 0.475222, 0.637346, 0.798860, 0.922554, 0.971514, 0.982362, 0.991155, 0.999981 }; 01835 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.938789, 0.756126, 0.508812, 0.258234, 0.070001, 0.004301, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.001793, 0.069474, 0.251770, 0.498992, 0.749491, 1.000000 }; 01836 rx = rr; 01837 gx = gg; 01838 bx = bb; 01839 } else if (code == (CIECOMP + 1)) { 01840 length = 27; 01841 double rr [] = { 0.264229, 0.082532, 0.004867, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000541, 0.062517, 0.246214, 0.493080, 0.743824, 0.931596, 0.996408, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000 }; 01842 double gg [] = { 1.000000, 0.964432, 0.859914, 0.717154, 0.572201, 0.435801, 0.319831, 0.214279, 0.109202, 0.031115, 0.002438, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000889, 0.020277, 0.077613, 0.155367, 0.234768, 0.334034, 0.475222, 0.637346, 0.798860, 0.922554, 0.971514 }; 01843 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.938789, 0.756126, 0.508812, 0.258234, 0.070001, 0.004301, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.001793, 0.069474, 0.251770 }; 01844 rx = rr; 01845 gx = gg; 01846 bx = bb; 01847 } else if (code == CIECOMP_ALT_1) { 01848 length = 33; 01849 double rr [] = { 0.999951, 0.764763, 0.513833, 0.262280, 0.070539, 0.004449, 0.000982, 0.000000, 0.014764, 0.079511, 0.164042, 0.247835, 0.342405, 0.474597, 0.620949, 0.766563, 0.888141, 0.936537, 0.955818, 0.977795, 0.996042, 1.000000, 0.999773, 0.999860, 1.000000, 0.999750, 0.999432, 0.999660, 0.999868, 0.999382, 0.999179, 0.999381, 0.999959 }; 01850 double gg [] = { 1.000000, 1.000000, 1.000000, 0.997055, 0.970402, 0.863627, 0.716516, 0.570543, 0.432488, 0.318623, 0.214564, 0.108254, 0.027442, 0.002708, 0.000136, 0.000000, 0.000011, 0.000033, 0.000094, 0.000746, 0.017982, 0.076261, 0.155089, 0.233998, 0.330934, 0.473361, 0.636642, 0.802257, 0.931872, 0.974355, 0.982178, 0.991650, 1.000000 }; 01851 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 0.999997, 0.999995, 0.999977, 0.999922, 0.999902, 0.999551, 0.999534, 0.998992, 0.999522, 0.999971, 0.999664, 0.999221, 0.950204, 0.758209, 0.505805, 0.252367, 0.056835, 0.003052, 0.000875, 0.000378, 0.000067, 0.000073, 0.000477, 0.004040, 0.061700, 0.249519, 0.498347, 0.748001, 0.997975 }; 01852 rx = rr; 01853 gx = gg; 01854 bx = bb; 01855 } else if (code == (CIECOMP_ALT_1 + 1)) { 01856 length = 33; 01857 double rr [] = { 0.000021, 0.000002, 0.000016, 0.000234, 0.000162, 0.003354, 0.038452, 0.102054, 0.165385, 0.228699, 0.291374, 0.369664, 0.475506, 0.586630, 0.695216, 0.803475, 0.893515, 0.930827, 0.944857, 0.961729, 0.978009, 0.993506, 0.999136, 0.998879, 0.999137, 0.999905, 0.999888, 0.999957, 0.999987, 1.000000, 1.000000, 1.000000, 1.000000 }; 01858 double gg [] = { 1.000000, 0.898136, 0.788027, 0.679369, 0.570642, 0.461780, 0.370245, 0.292206, 0.213912, 0.134749, 0.055599, 0.007772, 0.000272, 0.000008, 0.000004, 0.000009, 0.000007, 0.000014, 0.000011, 0.000027, 0.000088, 0.004334, 0.037984, 0.096488, 0.155866, 0.214581, 0.274564, 0.358132, 0.474443, 0.596959, 0.719264, 0.841713, 0.964617 }; 01859 double bb [] = { 0.999914, 1.000000, 1.000000, 0.999790, 0.998744, 0.998603, 0.999497, 0.999707, 0.999911, 0.999704, 0.999322, 0.999702, 1.000000, 0.999979, 0.999586, 0.998111, 0.956023, 0.819800, 0.630929, 0.440522, 0.253413, 0.086470, 0.011451, 0.000127, 0.000003, 0.000001, 0.000015, 0.000453, 0.001038, 0.000450, 0.000225, 0.000199, 0.000161 }; 01860 rx = rr; 01861 gx = gg; 01862 bx = bb; 01863 } else if (code == CIECOMP_ALT_2) { 01864 length = 33; 01865 double rr [] = { 0.999911, 0.764767, 0.513903, 0.262540, 0.070481, 0.004493, 0.000952, 0.000000, 0.014727, 0.079215, 0.164105, 0.250787, 0.300361, 0.256821, 0.171949, 0.088134, 0.087815, 0.263848, 0.518803, 0.760556, 0.943220, 0.993926, 0.999249, 0.999896, 1.000000, 0.999897, 0.999731, 0.999881, 0.999938, 0.999386, 0.999076, 0.999067, 0.999460 }; 01866 double gg [] = { 1.000000, 0.999999, 0.999994, 0.997249, 0.969474, 0.863789, 0.716632, 0.570567, 0.432580, 0.318934, 0.214508, 0.108219, 0.027005, 0.001377, 0.000081, 0.000009, 0.000000, 0.000031, 0.000254, 0.000000, 0.018056, 0.077171, 0.155264, 0.234004, 0.331232, 0.473361, 0.636852, 0.802178, 0.931685, 0.974284, 0.982440, 0.991755, 1.000000 }; 01867 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.999990, 0.999945, 0.999878, 0.999520, 0.999207, 0.994201, 0.946503, 0.762066, 0.509103, 0.254220, 0.060146, 0.006524, 0.000870, 0.000094, 0.000032, 0.000035, 0.000022, 0.000005, 0.000019, 0.000073, 0.000473, 0.005081, 0.060686, 0.248644, 0.498482, 0.748191, 0.998655 }; 01868 rx = rr; 01869 gx = gg; 01870 bx = bb; 01871 } else if (code == (CIECOMP_ALT_2 + 1)) { 01872 length = 26; 01873 double rr [] = { 0.513903, 0.262540, 0.070481, 0.004493, 0.000952, 0.000000, 0.014727, 0.079215, 0.164105, 0.250787, 0.300361, 0.256821, 0.171949, 0.518803, 0.760556, 0.943220, 0.993926, 0.999249, 0.999896, 1.000000, 0.999897, 0.999731, 0.999881, 0.999938, 0.999386, 0.999076 }; 01874 double gg [] = { 0.999994, 0.997249, 0.969474, 0.863789, 0.716632, 0.570567, 0.432580, 0.318934, 0.214508, 0.108219, 0.027005, 0.001377, 0.000081, 0.000254, 0.000000, 0.018056, 0.077171, 0.155264, 0.234004, 0.331232, 0.473361, 0.636852, 0.802178, 0.931685, 0.974284, 0.982440 }; 01875 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 0.999990, 0.999945, 0.999878, 0.999520, 0.999207, 0.994201, 0.946503, 0.762066, 0.509103, 0.000870, 0.000094, 0.000032, 0.000035, 0.000022, 0.000005, 0.000019, 0.000073, 0.000473, 0.005081, 0.060686, 0.248644, 0.498482 }; 01876 rx = rr; 01877 gx = gg; 01878 bx = bb; 01879 } else if (code == CIECOMP_ALT_3) { 01880 length = 33; 01881 double rr [] = { 0.000021, 0.000002, 0.000016, 0.000234, 0.000162, 0.003354, 0.038452, 0.102054, 0.165385, 0.228699, 0.291374, 0.369664, 0.475506, 0.586630, 0.695216, 0.803475, 0.893515, 0.930827, 0.944857, 0.961729, 0.978009, 0.993506, 0.999136, 0.998879, 0.999137, 0.999905, 0.999888, 0.999957, 0.999987, 1.000000, 1.000000, 1.000000, 1.000000 }; 01882 double gg [] = { 1.000000, 0.898136, 0.788027, 0.679369, 0.570642, 0.461780, 0.370245, 0.292206, 0.213912, 0.134749, 0.055599, 0.007772, 0.000272, 0.000008, 0.000004, 0.000009, 0.000007, 0.000014, 0.000011, 0.000027, 0.000088, 0.004334, 0.037984, 0.096488, 0.155866, 0.214581, 0.274564, 0.358132, 0.474443, 0.596959, 0.719264, 0.841713, 0.964617 }; 01883 double bb [] = { 0.999914, 1.000000, 1.000000, 0.999790, 0.998744, 0.998603, 0.999497, 0.999707, 0.999911, 0.999704, 0.999322, 0.999702, 1.000000, 0.999979, 0.999586, 0.998111, 0.956023, 0.819800, 0.630929, 0.440522, 0.253413, 0.086470, 0.011451, 0.000127, 0.000003, 0.000001, 0.000015, 0.000453, 0.001038, 0.000450, 0.000225, 0.000199, 0.000161 }; 01884 rx = rr; 01885 gx = gg; 01886 bx = bb; 01887 } else if (code == (CIECOMP_ALT_3 + 1)) { 01888 length = 27; 01889 double rr [] = { 0.000234, 0.000162, 0.003354, 0.038452, 0.102054, 0.165385, 0.228699, 0.291374, 0.369664, 0.475506, 0.586630, 0.695216, 0.803475, 0.893515, 0.930827, 0.944857, 0.961729, 0.978009, 0.993506, 0.999136, 0.998879, 0.999137, 0.999905, 0.999888, 0.999957, 0.999987, 1.000000 }; 01890 double gg [] = { 0.679369, 0.570642, 0.461780, 0.370245, 0.292206, 0.213912, 0.134749, 0.055599, 0.007772, 0.000272, 0.000008, 0.000004, 0.000009, 0.000007, 0.000014, 0.000011, 0.000027, 0.000088, 0.004334, 0.037984, 0.096488, 0.155866, 0.214581, 0.274564, 0.358132, 0.474443, 0.596959 }; 01891 double bb [] = { 0.999790, 0.998744, 0.998603, 0.999497, 0.999707, 0.999911, 0.999704, 0.999322, 0.999702, 1.000000, 0.999979, 0.999586, 0.998111, 0.956023, 0.819800, 0.630929, 0.440522, 0.253413, 0.086470, 0.011451, 0.000127, 0.000003, 0.000001, 0.000015, 0.000453, 0.001038, 0.000450 }; 01892 rx = rr; 01893 gx = gg; 01894 bx = bb; 01895 } else if (code == BLACKBODY) { 01896 length = 33; 01897 double rr [] = { 1.000000, 1.000000, 1.000000, 0.999999, 0.999996, 0.999675, 0.999319, 0.999516, 0.999489, 0.999604, 0.999995, 1.000000, 1.000000, 0.999997, 0.999865, 1.000000, 0.983105, 0.909532, 0.813694, 0.720501, 0.626450, 0.532048, 0.438575, 0.343988, 0.250932, 0.157250, 0.062752, 0.007126, 0.000412, 0.000324, 0.000000, 0.000046, 0.000258 }; 01898 double gg [] = { 0.000000, 0.086618, 0.180586, 0.274778, 0.368677, 0.462417, 0.555966, 0.649320, 0.743804, 0.838791, 0.930766, 0.984766, 1.000000, 0.999999, 0.999942, 0.996948, 0.982010, 0.911528, 0.815235, 0.720867, 0.626425, 0.531084, 0.437229, 0.344078, 0.250634, 0.156937, 0.066379, 0.010972, 0.000155, 0.000066, 0.000106, 0.000057, 0.000028 }; 01899 double bb [] = { 0.000000, 0.000028, 0.000047, 0.000017, 0.000006, 0.000011, 0.000034, 0.000020, 0.000028, 0.000211, 0.011424, 0.076038, 0.239387, 0.427148, 0.616124, 0.803833, 0.950133, 0.997841, 0.997676, 0.997875, 0.997774, 0.997078, 0.997007, 0.996407, 0.996357, 0.997493, 0.996829, 0.944413, 0.813917, 0.672345, 0.531919, 0.390918, 0.251743 }; 01900 rx = rr; 01901 gx = gg; 01902 bx = bb; 01903 } else if (code == (BLACKBODY + 1)) { 01904 length = 33; 01905 double rr [] = { 1.000000, 0.999906, 0.999708, 0.999539, 0.999552, 0.999235, 0.999463, 0.999773, 0.999862, 0.999950, 0.999895, 0.999494, 0.999077, 0.999141, 0.998829, 1.000000, 0.986819, 0.938395, 0.875514, 0.812872, 0.750901, 0.688290, 0.625432, 0.562228, 0.499214, 0.436045, 0.374025, 0.311043, 0.250516, 0.188187, 0.125189, 0.062544, 0.000095 }; 01906 double gg [] = { 0.000000, 0.058804, 0.121131, 0.183065, 0.245874, 0.308954, 0.371402, 0.433194, 0.494831, 0.557439, 0.619737, 0.682929, 0.746057, 0.808921, 0.872426, 0.935061, 0.969323, 0.940452, 0.876631, 0.813228, 0.749850, 0.687075, 0.624668, 0.561989, 0.498919, 0.436440, 0.374136, 0.311701, 0.249296, 0.187608, 0.125145, 0.062669, 0.000080 }; 01907 double bb [] = { 0.000012, 0.000028, 0.000042, 0.000152, 0.000239, 0.000069, 0.000387, 0.001237, 0.001583, 0.001240, 0.000291, 0.000238, 0.000232, 0.000184, 0.000516, 0.002223, 0.027364, 0.120060, 0.246693, 0.371988, 0.497032, 0.622486, 0.747998, 0.875008, 0.971356, 0.998454, 0.997949, 0.997694, 0.997953, 0.998069, 0.998122, 0.998256, 0.998504 }; 01908 rx = rr; 01909 gx = gg; 01910 bx = bb; 01911 } else if (code == RAINBOW) { 01912 length = 33; 01913 double rr [] = { 0.000000, 0.086173, 0.179998, 0.275159, 0.369505, 0.431644, 0.351353, 0.118157, 0.019516, 0.000785, 0.000248, 0.000176, 0.000039, 0.000017, 0.000213, 0.000960, 0.058315, 0.229594, 0.461803, 0.696663, 0.901663, 0.985886, 0.999456, 0.999834, 0.999881, 0.999986, 0.999991, 0.998931, 0.999086, 0.999625, 0.999794, 0.999880, 1.000000 }; 01914 double gg [] = { 0.000129, 0.000054, 0.000053, 0.000064, 0.000062, 0.000257, 0.000501, 0.024325, 0.133515, 0.350071, 0.583836, 0.813183, 0.960441, 0.999336, 0.999975, 1.000000, 0.999995, 0.999990, 0.999973, 0.999093, 0.970101, 0.819314, 0.598721, 0.365028, 0.137422, 0.001499, 0.000000, 0.072536, 0.247121, 0.436213, 0.623769, 0.811851, 1.000000 }; 01915 double bb [] = { 0.000000, 0.173973, 0.362471, 0.550963, 0.739751, 0.909659, 0.991103, 0.999353, 0.999848, 0.999933, 0.998977, 0.991456, 0.909874, 0.713164, 0.478570, 0.243157, 0.060479, 0.004108, 0.000011, 0.000015, 0.000009, 0.000124, 0.000658, 0.001394, 0.016480, 0.119105, 0.342446, 0.521194, 0.625726, 0.717459, 0.810571, 0.904202, 0.998013 }; 01916 rx = rr; 01917 gx = gg; 01918 bx = bb; 01919 } else if (code == (RAINBOW + 1)) { 01920 length = 25; 01921 double rr [] = { 0.369505, 0.431644, 0.351353, 0.118157, 0.019516, 0.000785, 0.000248, 0.000176, 0.000039, 0.000017, 0.000213, 0.000960, 0.058315, 0.229594, 0.461803, 0.696663, 0.901663, 0.985886, 0.999456, 0.999834, 0.999881, 0.999986, 0.999991, 0.998931, 0.999086 }; 01922 double gg [] = { 0.000062, 0.000257, 0.000501, 0.024325, 0.133515, 0.350071, 0.583836, 0.813183, 0.960441, 0.999336, 0.999975, 1.000000, 0.999995, 0.999990, 0.999973, 0.999093, 0.970101, 0.819314, 0.598721, 0.365028, 0.137422, 0.001499, 0.000000, 0.072536, 0.247121 }; 01923 double bb [] = { 0.739751, 0.909659, 0.991103, 0.999353, 0.999848, 0.999933, 0.998977, 0.991456, 0.909874, 0.713164, 0.478570, 0.243157, 0.060479, 0.004108, 0.000011, 0.000015, 0.000009, 0.000124, 0.000658, 0.001394, 0.016480, 0.119105, 0.342446, 0.521194, 0.625726 }; 01924 rx = rr; 01925 gx = gg; 01926 bx = bb; 01927 } else if (code == RAINBOW_ALT_1) { 01928 length = 11; 01929 double rr [] = { 0.00, 0.50, 0.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 1.00, 1.00 }; 01930 double gg [] = { 0.00, 0.00, 0.00, 0.50, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 1.00 }; 01931 double bb [] = { 0.00, 1.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 }; 01932 rx = rr; 01933 gx = gg; 01934 bx = bb; 01935 } else if (code == (RAINBOW_ALT_1 + 1)) { 01936 length = 9; 01937 double rr [] = { 0.50, 0.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 1.00 }; 01938 double gg [] = { 0.00, 0.00, 0.50, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00 }; 01939 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 0.00, 0.50 }; 01940 rx = rr; 01941 gx = gg; 01942 bx = bb; 01943 } else if (code == RAINBOW_ALT_2) { 01944 length = 13; 01945 double rr [] = { 0.00, 0.50, 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00, 1.00, 1.00 }; 01946 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00, 0.50, 1.00 }; 01947 double bb [] = { 0.00, 0.50, 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 }; 01948 rx = rr; 01949 gx = gg; 01950 bx = bb; 01951 } else if (code == (RAINBOW_ALT_2 + 1)) { 01952 length = 9; 01953 double rr [] = { 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00 }; 01954 double gg [] = { 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00 }; 01955 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00 }; 01956 rx = rr; 01957 gx = gg; 01958 bx = bb; 01959 } else if (code == RAINBOW_ALT_3) { 01960 length = 13; 01961 double rr [] = { 0.00, 0.50, 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00, 1.00, 1.00 }; 01962 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00, 0.50, 1.00 }; 01963 double bb [] = { 0.00, 0.50, 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 }; 01964 rx = rr; 01965 gx = gg; 01966 bx = bb; 01967 } else if (code == (RAINBOW_ALT_3 + 1)) { 01968 length = 9; 01969 double rr [] = { 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00 }; 01970 double gg [] = { 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00 }; 01971 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00 }; 01972 rx = rr; 01973 gx = gg; 01974 bx = bb; 01975 } else if (code == RAINBOW_ALT_4) { 01976 length = 33; 01977 double rr [] = { 0.000000, 0.086173, 0.179998, 0.275159, 0.369505, 0.431644, 0.351353, 0.118157, 0.019516, 0.000785, 0.000248, 0.000176, 0.000039, 0.000017, 0.000213, 0.000960, 0.058315, 0.229594, 0.461803, 0.696663, 0.901663, 0.985886, 0.999456, 0.999834, 0.999881, 0.999986, 0.999991, 0.998931, 0.999086, 0.999625, 0.999794, 0.999880, 1.000000 }; 01978 double gg [] = { 0.000129, 0.000054, 0.000053, 0.000064, 0.000062, 0.000257, 0.000501, 0.024325, 0.133515, 0.350071, 0.583836, 0.813183, 0.960441, 0.999336, 0.999975, 1.000000, 0.999995, 0.999990, 0.999973, 0.999093, 0.970101, 0.819314, 0.598721, 0.365028, 0.137422, 0.001499, 0.000000, 0.072536, 0.247121, 0.436213, 0.623769, 0.811851, 1.000000 }; 01979 double bb [] = { 0.000000, 0.173973, 0.362471, 0.550963, 0.739751, 0.909659, 0.991103, 0.999353, 0.999848, 0.999933, 0.998977, 0.991456, 0.909874, 0.713164, 0.478570, 0.243157, 0.060479, 0.004108, 0.000011, 0.000015, 0.000009, 0.000124, 0.000658, 0.001394, 0.016480, 0.119105, 0.342446, 0.521194, 0.625726, 0.717459, 0.810571, 0.904202, 0.998013 }; 01980 rx = rr; 01981 gx = gg; 01982 bx = bb; 01983 } else if (code == (RAINBOW_ALT_4 + 1)) { 01984 length = 22; 01985 double rr [] = { 0.275159, 0.369505, 0.431644, 0.351353, 0.118157, 0.019516, 0.000785, 0.000248, 0.000176, 0.000039, 0.000017, 0.461803, 0.696663, 0.901663, 0.999456, 0.999834, 0.999881, 0.999986, 0.999991, 0.998931, 0.999086, 0.999625 }; 01986 double gg [] = { 0.000064, 0.000062, 0.000257, 0.000501, 0.024325, 0.133515, 0.350071, 0.583836, 0.813183, 0.960441, 0.999336, 0.999973, 0.999093, 0.970101, 0.598721, 0.365028, 0.137422, 0.001499, 0.000000, 0.072536, 0.247121, 0.436213 }; 01987 double bb [] = { 0.550963, 0.739751, 0.909659, 0.991103, 0.999353, 0.999848, 0.999933, 0.998977, 0.991456, 0.909874, 0.713164, 0.000011, 0.000015, 0.000009, 0.000658, 0.001394, 0.016480, 0.119105, 0.342446, 0.521194, 0.625726, 0.717459 }; 01988 rx = rr; 01989 gx = gg; 01990 bx = bb; 01991 } else if (code == IRON) { 01992 length = 33; 01993 double rr [] = { 0.000137, 0.044733, 0.091636, 0.138374, 0.185449, 0.235309, 0.310152, 0.409810, 0.509259, 0.608080, 0.707532, 0.784229, 0.832226, 0.874605, 0.914548, 0.957131, 0.990374, 0.999789, 0.999559, 0.999753, 0.999893, 0.999713, 0.999243, 0.999138, 0.998799, 0.998982, 0.999794, 0.999992, 0.999997, 0.999947, 0.998754, 0.998419, 0.998206 }; 01994 double gg [] = { 0.000218, 0.000655, 0.001318, 0.002240, 0.002696, 0.004508, 0.015631, 0.033312, 0.051963, 0.070414, 0.088750, 0.129074, 0.197559, 0.271724, 0.346554, 0.421253, 0.486973, 0.528391, 0.559335, 0.591508, 0.623114, 0.657761, 0.707739, 0.770047, 0.832696, 0.895595, 0.958334, 0.994681, 0.999982, 1.000000, 1.000000, 1.000000, 1.000000 }; 01995 double bb [] = { 0.000000, 0.087421, 0.182004, 0.276794, 0.372322, 0.463058, 0.506880, 0.513951, 0.520935, 0.528776, 0.535606, 0.503864, 0.411574, 0.308960, 0.206618, 0.103307, 0.024739, 0.001474, 0.003034, 0.003601, 0.005707, 0.007447, 0.006697, 0.005752, 0.004690, 0.002699, 0.007463, 0.077716, 0.244948, 0.434054, 0.622376, 0.810788, 0.998917 }; 01996 rx = rr; 01997 gx = gg; 01998 bx = bb; 01999 } else if (code == (IRON + 1)) { 02000 length = 25; 02001 double rr [] = { 0.185449, 0.235309, 0.310152, 0.409810, 0.509259, 0.608080, 0.707532, 0.784229, 0.832226, 0.874605, 0.914548, 0.957131, 0.990374, 0.999789, 0.999559, 0.999753, 0.999893, 0.999713, 0.999243, 0.999138, 0.998799, 0.998982, 0.999794, 0.999992, 0.999997 }; 02002 double gg [] = { 0.002696, 0.004508, 0.015631, 0.033312, 0.051963, 0.070414, 0.088750, 0.129074, 0.197559, 0.271724, 0.346554, 0.421253, 0.486973, 0.528391, 0.559335, 0.591508, 0.623114, 0.657761, 0.707739, 0.770047, 0.832696, 0.895595, 0.958334, 0.994681, 0.999982 }; 02003 double bb [] = { 0.372322, 0.463058, 0.506880, 0.513951, 0.520935, 0.528776, 0.535606, 0.503864, 0.411574, 0.308960, 0.206618, 0.103307, 0.024739, 0.001474, 0.003034, 0.003601, 0.005707, 0.007447, 0.006697, 0.005752, 0.004690, 0.002699, 0.007463, 0.077716, 0.244948 }; 02004 rx = rr; 02005 gx = gg; 02006 bx = bb; 02007 } else if (code == IRON_ALT_1) { 02008 length = 12; 02009 double rr [] = { 0.00, 0.05, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02010 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95, 1.00 }; 02011 double bb [] = { 0.00, 0.25, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45, 1.00 }; 02012 rx = rr; 02013 gx = gg; 02014 bx = bb; 02015 } else if (code == (IRON_ALT_1 + 1)) { 02016 length = 10; 02017 double rr [] = { 0.05, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 }; 02018 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 }; 02019 double bb [] = { 0.25, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 }; 02020 rx = rr; 02021 gx = gg; 02022 bx = bb; 02023 } else if (code == IRON_ALT_2) { 02024 length = 11; 02025 double rr [] = { 0.00, 0.05, 0.10, 0.40, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02026 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.80, 0.95, 1.00, 1.00 }; 02027 double bb [] = { 0.00, 0.25, 0.50, 0.60, 0.50, 0.05, 0.00, 0.05, 0.45, 0.70, 1.00 }; 02028 rx = rr; 02029 gx = gg; 02030 bx = bb; 02031 } else if (code == (IRON_ALT_2 + 1)) { 02032 length = 5; 02033 double rr [] = { 0.40, 0.80, 0.90, 0.95, 1.00 }; 02034 double gg [] = { 0.60, 0.50, 0.05, 0.00, 0.05 }; 02035 double bb [] = { 0.00, 0.10, 0.25, 0.45, 0.80 }; 02036 rx = rr; 02037 gx = gg; 02038 bx = bb; 02039 } else if (code == (IRON_ALT_3)) { 02040 length = 11; 02041 double rr [] = { 0.00, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02042 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95, 1.00 }; 02043 double bb [] = { 0.00, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45, 1.00 }; 02044 rx = rr; 02045 gx = gg; 02046 bx = bb; 02047 } else if (code == (IRON_ALT_3 + 1)) { 02048 length = 9; 02049 double rr [] = { 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 }; 02050 double gg [] = { 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 }; 02051 double bb [] = { 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 }; 02052 rx = rr; 02053 gx = gg; 02054 bx = bb; 02055 } else if (code == BLUERED) { 02056 length = 3; 02057 double rr [] = { 0.00, 1.00, 1.00 }; 02058 double gg [] = { 0.00, 1.00, 0.00 }; 02059 double bb [] = { 1.00, 1.00, 0.00 }; 02060 rx = rr; 02061 gx = gg; 02062 bx = bb; 02063 } else if (code == (BLUERED + 1)) { 02064 length = 2; 02065 double rr [] = { 0.00, 1.00 }; 02066 double gg [] = { 0.00, 0.00 }; 02067 double bb [] = { 1.00, 0.00 }; 02068 rx = rr; 02069 gx = gg; 02070 bx = bb; 02071 } else if (code == BLUERED_ALT_1) { 02072 length = 4; 02073 double rr [] = { 0.00, 0.00, 1.00, 1.00 }; 02074 double gg [] = { 0.00, 0.00, 0.00, 1.00 }; 02075 double bb [] = { 0.00, 1.00, 0.00, 1.00 }; 02076 rx = rr; 02077 gx = gg; 02078 bx = bb; 02079 } else if (code == (BLUERED_ALT_1 + 1)) { 02080 length = 2; 02081 double rr [] = { 0.00, 1.00 }; 02082 double gg [] = { 0.00, 0.00 }; 02083 double bb [] = { 1.00, 0.00 }; 02084 rx = rr; 02085 gx = gg; 02086 bx = bb; 02087 } else if (code == BLUERED_ALT_2) { 02088 length = 7; 02089 double rr [] = { 0.00, 0.50, 0.80, 1.00, 1.00, 1.00, 1.00 }; 02090 double gg [] = { 0.00, 0.50, 0.80, 1.00, 0.80, 0.50, 0.00 }; 02091 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.80, 0.50, 0.00 }; 02092 rx = rr; 02093 gx = gg; 02094 bx = bb; 02095 } else if (code == (BLUERED_ALT_2 + 1)) { 02096 length = 4; 02097 double rr [] = { 0.00, 0.50, 1.00, 1.00 }; 02098 double gg [] = { 0.00, 0.50, 0.50, 0.00 }; 02099 double bb [] = { 1.00, 1.00, 0.50, 0.00 }; 02100 rx = rr; 02101 gx = gg; 02102 bx = bb; 02103 } else if (code == JET) { 02104 length = 13; 02105 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02106 double gg [] = { 0.00, 0.00, 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00, 0.50, 1.00 }; 02107 double bb [] = { 0.00, 0.50, 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 }; 02108 rx = rr; 02109 gx = gg; 02110 bx = bb; 02111 } else if (code == (JET + 1)) { 02112 length = 11; 02113 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00, 1.00 }; 02114 double gg [] = { 0.00, 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00, 0.50 }; 02115 double bb [] = { 0.50, 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50 }; 02116 rx = rr; 02117 gx = gg; 02118 bx = bb; 02119 } else if (code == JET_ALT_1) { 02120 length = 11; 02121 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00, 1.00 }; 02122 double gg [] = { 0.00, 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00, 1.00 }; 02123 double bb [] = { 0.00, 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00, 1.00 }; 02124 rx = rr; 02125 gx = gg; 02126 bx = bb; 02127 } else if (code == (JET_ALT_1 + 1)) { 02128 length = 9; 02129 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00 }; 02130 double gg [] = { 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00 }; 02131 double bb [] = { 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02132 rx = rr; 02133 gx = gg; 02134 bx = bb; 02135 } else if (code == ICE) { 02136 length = 9; 02137 double rr [] = { 1.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02138 double gg [] = { 1.00, 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.13, 0.00 }; 02139 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00 }; 02140 rx = rr; 02141 gx = gg; 02142 bx = bb; 02143 } else if (code == (ICE + 1)) { 02144 length = 7; 02145 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02146 double gg [] = { 0.88, 0.75, 0.68, 0.50, 0.38, 0.25 }; 02147 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50 }; 02148 rx = rr; 02149 gx = gg; 02150 bx = bb; 02151 } else if (code == ICE_ALT_1) { 02152 length = 11; 02153 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02154 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00 }; 02155 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00 }; 02156 rx = rr; 02157 gx = gg; 02158 bx = bb; 02159 } else if (code == (ICE_ALT_1 + 1)) { 02160 length = 7; 02161 double rr [] = { 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02162 double gg [] = { 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.00 }; 02163 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67 }; 02164 rx = rr; 02165 gx = gg; 02166 bx = bb; 02167 } else if (code == ICE_ALT_2) { 02168 length = 11; 02169 double rr [] = { 1.00, 0.64, 0.36, 0.16, 0.04, 0.01, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02170 double gg [] = { 1.00, 0.90, 0.80, 0.70, 0.60, 0.50, 0.40, 0.30, 0.20, 0.10, 0.00 }; 02171 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.99, 0.89, 0.78, 0.63, 0.48, 0.00 }; 02172 rx = rr; 02173 gx = gg; 02174 bx = bb; 02175 } else if (code == (ICE_ALT_2 + 1)) { 02176 length = 7; 02177 double rr [] = { 0.36, 0.16, 0.04, 0.01, 0.00, 0.00, 0.00 }; 02178 double gg [] = { 0.80, 0.70, 0.60, 0.50, 0.40, 0.30, 0.20 }; 02179 double bb [] = { 1.00, 1.00, 1.00, 0.99, 0.89, 0.78, 0.63 }; 02180 rx = rr; 02181 gx = gg; 02182 bx = bb; 02183 } else if (code == ICE_ALT_3) { 02184 length = 9; 02185 double rr [] = { 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02186 double gg [] = { 1.00, 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.50, 0.00 }; 02187 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00 }; 02188 rx = rr; 02189 gx = gg; 02190 bx = bb; 02191 } else if (code == (ICE_ALT_3 + 1)) { 02192 length = 7; 02193 double rr [] = { 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02194 double gg [] = { 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.50 }; 02195 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00 }; 02196 rx = rr; 02197 gx = gg; 02198 bx = bb; 02199 } else if (code == ICEIRON) { 02200 length = 19; 02201 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 0.67, 0.86, 0.93, 1.00, 1.00, 1.00, 1.00 }; 02202 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.15, 0.40, 0.80, 0.95, 1.00, 1.00 }; 02203 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.33, 0.40, 0.10, 0.05, 0.45, 0.70, 1.00 }; 02204 rx = rr; 02205 gx = gg; 02206 bx = bb; 02207 } else if (code == (ICEIRON + 1)) { 02208 length = 12; 02209 double rr [] = { 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.67, 0.67, 0.86, 0.93, 1.00, 1.00 }; 02210 double gg [] = { 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.15, 0.40, 0.80, 0.95 }; 02211 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.00, 0.33, 0.40, 0.10, 0.05, 0.45 }; 02212 rx = rr; 02213 gx = gg; 02214 bx = bb; 02215 } else if (code == ICEIRON_ALT_1) { 02216 length = 21; 02217 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.05, 0.10, 0.40, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02218 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.80, 0.95, 1.00, 1.00 }; 02219 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.25, 0.50, 0.60, 0.50, 0.05, 0.00, 0.05, 0.45, 0.70, 1.00 }; 02220 rx = rr; 02221 gx = gg; 02222 bx = bb; 02223 } else if (code == (ICEIRON_ALT_1 + 1)) { 02224 length = 10; 02225 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.40, 0.80, 0.90, 0.95, 1.00 }; 02226 double gg [] = { 1.00, 0.75, 0.50, 0.25, 0.00, 0.00, 0.10, 0.25, 0.45, 0.80 }; 02227 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.60, 0.50, 0.05, 0.00, 0.05 }; 02228 rx = rr; 02229 gx = gg; 02230 bx = bb; 02231 } else if (code == ICEIRON_ALT_2) { 02232 length = 19; 02233 double rr [] = { 1.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02234 double gg [] = { 1.00, 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.13, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95, 1.00 }; 02235 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45, 1.00 }; 02236 rx = rr; 02237 gx = gg; 02238 bx = bb; 02239 } else if (code == (ICEIRON_ALT_2 + 1)) { 02240 length = 17; 02241 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 }; 02242 double gg [] = { 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.13, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 }; 02243 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 }; 02244 rx = rr; 02245 gx = gg; 02246 bx = bb; 02247 } else if (code == ICEFIRE) { 02248 length = 19; 02249 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02250 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00, 1.00, 1.00, 1.00 }; 02251 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00 }; 02252 rx = rr; 02253 gx = gg; 02254 bx = bb; 02255 } else if (code == (ICEFIRE + 1)) { 02256 length = 12; 02257 double rr [] = { 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.67, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02258 double gg [] = { 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00, 1.00 }; 02259 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33 }; 02260 rx = rr; 02261 gx = gg; 02262 bx = bb; 02263 } else if (code == ICEFIRE_ALT_1) { 02264 length = 17; 02265 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02266 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00, 1.00, 1.00, 1.00 }; 02267 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.33, 0.67, 1.00 }; 02268 rx = rr; 02269 gx = gg; 02270 bx = bb; 02271 } else if (code == (ICEFIRE_ALT_1 + 1)) { 02272 length = 10; 02273 double rr [] = { 0.33, 0.00, 0.00, 0.00, 0.00, 0.67, 1.00, 1.00, 1.00, 1.00 }; 02274 double gg [] = { 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00, 1.00 }; 02275 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.67, 0.00, 0.00, 0.00, 0.00, 0.33 }; 02276 rx = rr; 02277 gx = gg; 02278 bx = bb; 02279 } else if (code == ICEFIRE_ALT_2) { 02280 length = 17; 02281 double rr [] = { 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.25, 0.50, 0.75, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02282 double gg [] = { 1.00, 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00, 1.00, 1.00 }; 02283 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 0.00, 0.00, 0.00, 0.50, 1.00 }; 02284 rx = rr; 02285 gx = gg; 02286 bx = bb; 02287 } else if (code == (ICEFIRE_ALT_2 + 1)) { 02288 length = 12; 02289 double rr [] = { 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 0.75, 1.00, 1.00, 1.00, 1.00 }; 02290 double gg [] = { 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.00, 0.00, 0.00, 0.50, 1.00, 1.00 }; 02291 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.50, 0.00, 0.00, 0.00, 0.50 }; 02292 rx = rr; 02293 gx = gg; 02294 bx = bb; 02295 } else if (code == ICEFIRE_ALT_3) { 02296 length = 17; 02297 // WHITE CYAN LBLUE DBLUE PURPLE RED ORANGE YELLOW WHITE 02298 double rr [] = { 1.00, 0.50, 0.00, 0.00, 0.50, 0.25, 0.00, 0.25, 0.50, 0.75, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02299 double gg [] = { 1.00, 1.00, 1.00, 0.50, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.25, 0.50, 0.75, 1.00, 1.00, 1.00 }; 02300 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.50, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 }; 02301 rx = rr; 02302 gx = gg; 02303 bx = bb; 02304 } else if (code == (ICEFIRE_ALT_3 + 1)) { 02305 length = 13; 02306 // CYAN LBLUE DBLUE PURPLE RED ORANGE YELLOW 02307 double rr [] = { 0.00, 0.00, 0.50, 0.25, 0.00, 0.25, 0.50, 0.75, 1.00, 1.00, 1.00, 1.00, 1.00 }; 02308 double gg [] = { 1.00, 0.50, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.25, 0.50, 0.75, 1.00 }; 02309 double bb [] = { 1.00, 1.00, 1.00, 0.75, 0.50, 0.50, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02310 rx = rr; 02311 gx = gg; 02312 bx = bb; 02313 } else if (code == REPEATED) { 02314 length = 16; 02315 double rr [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, 1.00, 1.00 }; 02316 double gg [] = { 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, }; 02317 double bb [] = { 1.00, 1.00, 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, 1.00, 1.00, 0.00, 1.00, }; 02318 rx = rr; 02319 gx = gg; 02320 bx = bb; 02321 } else if (code == (REPEATED + 1)) { 02322 length = 12; 02323 double rr [] = { 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00 }; 02324 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 }; 02325 double bb [] = { 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00 }; 02326 rx = rr; 02327 gx = gg; 02328 bx = bb; 02329 } else if (code == REPEATED_ALT_1) { 02330 length = 6; 02331 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02332 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02333 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02334 rx = rr; 02335 gx = gg; 02336 bx = bb; 02337 } else if (code == (REPEATED_ALT_1 + 1)) { 02338 length = 6; 02339 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02340 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02341 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02342 rx = rr; 02343 gx = gg; 02344 bx = bb; 02345 } else if (code == REPEATED_ALT_2) { 02346 length = 48; 02347 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02348 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02349 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02350 rx = rr; 02351 gx = gg; 02352 bx = bb; 02353 } else if (code == (REPEATED_ALT_2 + 1)) { 02354 length = 48; 02355 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02356 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02357 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02358 rx = rr; 02359 gx = gg; 02360 bx = bb; 02361 } else if (code == REPEATED_ALT_3) { 02362 length = 41; 02363 double rr [] = { 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.05, 0.10, 0.40, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.05, 0.10, 0.40, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 }; 02364 double gg [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.80, 0.95, 1.00, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.80, 0.95, 1.00, 1.00 }; 02365 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.25, 0.50, 0.60, 0.50, 0.05, 0.00, 0.05, 0.45, 0.70, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.67, 0.33, 0.00, 0.25, 0.50, 0.60, 0.50, 0.05, 0.00, 0.05, 0.45, 0.70, 1.00 }; 02366 rx = rr; 02367 gx = gg; 02368 bx = bb; 02369 } else if (code == (REPEATED_ALT_3 + 1)) { 02370 length = 28; 02371 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 }; 02372 double gg [] = { 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95, 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 }; 02373 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 }; 02374 rx = rr; 02375 gx = gg; 02376 bx = bb; 02377 } else if (code == REPEATED_ALT_4) { 02378 length = 12; 02379 double rr [] = { 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00 }; 02380 double gg [] = { 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00 }; 02381 double bb [] = { 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00, 0.00, 1.00 }; 02382 rx = rr; 02383 gx = gg; 02384 bx = bb; 02385 } else if (code == (REPEATED_ALT_4 + 1)) { 02386 length = 12; 02387 double rr [] = { 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75 }; 02388 double gg [] = { 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75 }; 02389 double bb [] = { 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75, 0.25, 0.75 }; 02390 rx = rr; 02391 gx = gg; 02392 bx = bb; 02393 } else if (code == REPEATED_ALT_5) { 02394 length = 6; 02395 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02396 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02397 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02398 rx = rr; 02399 gx = gg; 02400 bx = bb; 02401 } else if (code == (REPEATED_ALT_5 + 1)) { 02402 length = 6; 02403 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02404 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02405 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02406 rx = rr; 02407 gx = gg; 02408 bx = bb; 02409 } else if (code == REPEATED_ALT_6) { 02410 length = 48; 02411 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02412 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02413 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02414 rx = rr; 02415 gx = gg; 02416 bx = bb; 02417 } else if (code == (REPEATED_ALT_6 + 1)) { 02418 length = 48; 02419 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 }; 02420 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 }; 02421 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 }; 02422 rx = rr; 02423 gx = gg; 02424 bx = bb; 02425 } 02426 02427 //cout << "gx[0] = " << gx[0] << endl; 02428 //cout << "gx[1] = " << gx[1] << endl; 02429 02430 if (!flexibleMarkers) { 02431 02432 for (unsigned int iii = 0; iii < length; iii++) { 02433 da[iii] = (double(iii) / double((length-1))); 02434 } 02435 dd = da; 02436 } 02437 02438 dx = dd; 02439 02440 //cout << "gx[0] = " << gx[0] << endl; 02441 //cout << "gx[1] = " << gx[1] << endl; 02442 02443 create_long_map(); 02444 02445 //cout << "gx[0] = " << gx[0] << endl; 02446 //cout << "gx[1] = " << gx[1] << endl; 02447 02448 setupLookupTable(1); 02449 setupLookupTable(2); 02450 02451 } 02452 02453 int cScheme::current_scheme() { 02454 return code; 02455 } 02456 02457 void cScheme::customize(double* d, double* r, double* g, double* b, int len) { 02458 code = CUSTOM; 02459 dx = d; 02460 rx = r; 02461 gx = g; 02462 bx = b; 02463 length = len; 02464 } 02465 02466 void cScheme::falsify_image(const Mat& thermIm, Mat& outputIm, int param) { 02467 02468 if ((outputIm.size() != thermIm.size()) || (outputIm.type() != CV_8UC3)) { 02469 outputIm = Mat::zeros(thermIm.size(), CV_8UC3); 02470 } 02471 02472 //int level; 02473 // inputs can be 8 or 16 bits/pixel 02474 // output is 8 bits/pixel 02475 //int maxVal = 255; 02476 02477 // some kind of check to figure out if input image is actual 16-bits/pixel 02478 if (thermIm.depth() == 2) { 02479 //maxVal = 65535; 02480 } 02481 02482 // store the current standard, and then modify it according to params 02483 //int newCode, oldCode; 02484 02485 if (param == 1) { 02486 //oldCode = code; 02487 //newCode = code + 1; 02488 } 02489 02490 //printf("%s << code = %d; newCode = %d\n", __FUNCTION__, code, newCode); 02491 02492 /* 02493 if (params[0] == 0) { // if a variation hasn't been selected 02494 02495 // start to deconstruct code... 02496 newCode = code; 02497 02498 if (((newCode % 2) == 0) && (params[1] == 1)) { // if it's unsafe but safety has been selected 02499 newCode += 1; 02500 } 02501 02502 02503 } else { // otherwise, ignore last digit 02504 newCode = code - (code % 10); 02505 02506 newCode += (params[0]-1)*2; // add variation code 02507 02508 if (params[1] == 1) { 02509 newCode += 1; // add safety index 02510 } 02511 02512 } 02513 */ 02514 02515 if (param == 1) { 02516 //load_standard(newCode); 02517 } 02518 02519 //setupLookupTable(); 02520 02521 //double sr, sg, sb; 02522 02523 /* 02524 printf("%s << thermIm = %dx%d, %d, %d\n", __FUNCTION__, thermIm.size().width, thermIm.size().height, thermIm.depth(), thermIm.channels()); 02525 printf("%s << outputIm = %dx%d, %d, %d\n", __FUNCTION__, outputIm.size().width, outputIm.size().height, outputIm.depth(), outputIm.channels()); 02526 */ 02527 02528 // Create RGB output image 02529 //if (outputIm.empty()) { 02530 //outputIm = Mat(thermIm.size(), CV_8UC3); 02531 //} 02532 02533 //struct timeval timer; 02534 //double elapsedTime; 02535 //elapsedTime = timeElapsedMS(timer); 02536 02537 02538 //level = 0; 02539 02540 int lookupIndex = 0; 02541 02542 for (int i = 0; i < thermIm.size().height; i++) { 02543 for (int j = 0; j < thermIm.size().width; j++) { 02544 02545 // find closest element... 02546 02547 //if ((*thermIm)(i, j) > 255 02548 02549 //level = (thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/65536; 02550 //level = (int) floor((thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/65535); // or 65536? 02551 //printf("level = %d\n", level); 02552 02553 // removing this halves from 15 - 7 02554 /* 02555 if (thermIm.depth() == 2) { 02556 level = (int) floor(double((thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/maxVal)); // for 16 bits/pixel 02557 } else { 02558 level = (int) floor(double((thermIm.at<unsigned char>(i,j)*(MAP_LENGTH-1))/maxVal)); // for standard 8bits/pixel 02559 } 02560 */ 02561 // removing this takes it down effectively to zero... 02562 /* 02563 outputIm.at<Vec3b>(i,j)[2] = (unsigned char) (255.0 * red[level]); 02564 outputIm.at<Vec3b>(i,j)[1] = (unsigned char) (255.0 * green[level]); 02565 outputIm.at<Vec3b>(i,j)[0] = (unsigned char) (255.0 * blue[level]); 02566 */ 02567 02568 //printf("%s << depth (%d) (%d, %d)\n", __FUNCTION__, thermIm.depth(), thermIm.cols, thermIm.rows); 02569 02570 //imshow("asda", thermIm); 02571 //waitKey(); 02572 02573 if (thermIm.depth() == 2) { 02574 lookupIndex = thermIm.at<unsigned short>(i,j); 02575 outputIm.at<Vec3b>(i,j)[2] = lookupTable_2[lookupIndex][2]; 02576 outputIm.at<Vec3b>(i,j)[1] = lookupTable_2[lookupIndex][1]; 02577 outputIm.at<Vec3b>(i,j)[0] = lookupTable_2[lookupIndex][0]; 02578 } else if (thermIm.depth() == 0) { 02579 02580 lookupIndex = thermIm.at<unsigned char>(i,j); 02581 //printf("%s << here (%d, %d, %d)\n", __FUNCTION__, lookupTable_1[lookupIndex][2], lookupTable_1[lookupIndex][1], lookupTable_1[lookupIndex][0]); 02582 outputIm.at<Vec3b>(i,j)[2] = lookupTable_1[lookupIndex][2]; 02583 outputIm.at<Vec3b>(i,j)[1] = lookupTable_1[lookupIndex][1]; 02584 outputIm.at<Vec3b>(i,j)[0] = lookupTable_1[lookupIndex][0]; 02585 } 02586 02587 02588 /* 02589 sr = 255.0 * red[level]; 02590 sg = 255.0 * green[level]; 02591 sb = 255.0 * blue[level]; 02592 02593 outputIm.at<Vec3b>(i,j)[2] = (unsigned char) sr; 02594 outputIm.at<Vec3b>(i,j)[1] = (unsigned char) sg; 02595 outputIm.at<Vec3b>(i,j)[0] = (unsigned char) sb; 02596 */ 02597 02598 //printf("raw = %f\n", thermIm(i, j)); 02599 //printf("lvl = %d\n", level); 02600 //printf("red = %f\n", red[level]); 02601 //printf("grn = %f\n", green[level]); 02602 //printf("blu = %f\n", blue[level]); 02603 //printf("/n"); 02604 02605 } 02606 //std::cin.get(); 02607 } 02608 02609 //elapsedTime = timeElapsedMS(timer); 02610 //printf("%s << Time elapsed [%d] = %f\n", __FUNCTION__, 0, elapsedTime); 02611 02612 if (param == 1) { 02613 //load_standard(oldCode); 02614 } 02615 02616 } 02617 02618 void cScheme::image_resize(Mat& inputIm, int dim_i, int dim_j) { 02619 Mat newIm; 02620 newIm = Mat(dim_i,dim_j,inputIm.type()); 02621 02622 double val; 02623 02624 int ni, nj; 02625 02626 ni = inputIm.size().height; 02627 nj = inputIm.size().width; 02628 02629 for (int i = 0; i < dim_i; i++) { 02630 for (int j = 0; j < dim_j; j++) { 02631 //val = (*inputIm)(((int)((i*inputIm->ni())/dim_i)),((int)((j*inputIm->nj())/dim_j))); 02632 val = inputIm.at<unsigned char>(((int)((i*ni)/dim_i)),((int)((j*nj)/dim_j))); 02633 02634 newIm.at<unsigned char>(i,j) = val; 02635 } 02636 } 02637 02638 //inputIm->set_size(dim_i, dim_j); 02639 //inputIm->deep_copy(*newIm); 02640 inputIm = Mat(newIm); 02641 02642 } 02643 02644 void cScheme::forge_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double* params, double thresh) { 02645 02646 outputIm = Mat(thermIm.size(), CV_8UC3); 02647 02648 double working_params[2]; 02649 02650 if (params == NULL) { 02651 working_params[0] = 0.2; 02652 working_params[1] = 0.8; 02653 } else { 02654 working_params[0] = params[0]; 02655 working_params[1] = params[1]; 02656 } 02657 02658 double vals[2], percentiles[2]; 02659 percentiles[0] = thresh; 02660 percentiles[1] = 1 - thresh; 02661 02662 findPercentiles(thermIm, vals, percentiles, 2); 02663 02664 /* 02665 printf("%s << percentiles[0] = (%f), percentiles[1] = (%f)\n", __FUNCTION__, vals[0], vals[1]); 02666 printf("%s << red[0] = (%d), red[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][0], lookupTable_1[65535][0]); 02667 printf("%s << green[0] = (%d), green[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][1], lookupTable_1[65535][1]); 02668 printf("%s << blue[0] = (%d), blue[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][2], lookupTable_1[65535][2]); 02669 */ 02670 02671 double lumChange[3]; 02672 double maxLumChange; 02673 02674 for (unsigned int iii = 0; iii < thermIm.rows; iii++) { 02675 for (unsigned int jjj = 0; jjj < thermIm.cols; jjj++) { 02676 02677 if (thermIm.depth() == 2) { 02678 if (thermIm.at<unsigned short>(iii,jjj) < (unsigned short) vals[0]) { 02679 outputIm.at<Vec3b>(iii,jjj)[0] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][0]; 02680 outputIm.at<Vec3b>(iii,jjj)[1] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][1]; 02681 outputIm.at<Vec3b>(iii,jjj)[2] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][2]; 02682 } else if (thermIm.at<unsigned short>(iii,jjj) > (unsigned short) vals[1]) { 02683 outputIm.at<Vec3b>(iii,jjj)[0] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][0]; 02684 outputIm.at<Vec3b>(iii,jjj)[1] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][1]; 02685 outputIm.at<Vec3b>(iii,jjj)[2] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][2]; 02686 } else { 02687 02688 lumChange[0] = 2.0 * (((double) visualIm.at<Vec3b>(iii,jjj)[0])/255.0 - 0.5) * (working_params[1] - working_params[0]); 02689 lumChange[1] = 2.0 * (((double) visualIm.at<Vec3b>(iii,jjj)[1])/255.0 - 0.5) * (working_params[1] - working_params[0]); 02690 lumChange[2] = 2.0 * (((double) visualIm.at<Vec3b>(iii,jjj)[2])/255.0 - 0.5) * (working_params[1] - working_params[0]); 02691 02692 maxLumChange = max(lumChange[0], lumChange[1]); 02693 maxLumChange = max(maxLumChange, lumChange[2]); 02694 02695 outputIm.at<Vec3b>(iii,jjj)[0] = ((double) visualIm.at<Vec3b>(iii, jjj)[0]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0); 02696 outputIm.at<Vec3b>(iii,jjj)[1] = ((double) visualIm.at<Vec3b>(iii, jjj)[1]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0); 02697 outputIm.at<Vec3b>(iii,jjj)[2] = ((double) visualIm.at<Vec3b>(iii, jjj)[2]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0); 02698 /* 02699 if (lumChange[0] > 0) { 02700 outputIm.at<Vec3b>(iii,jjj)[0] = outputIm.at<Vec3b>(iii, jjj)[0] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * maxLumChange; 02701 } else { 02702 outputIm.at<Vec3b>(iii,jjj)[0] = outputIm.at<Vec3b>(iii, jjj)[0] + (outputIm.at<Vec3b>(iii, jjj)[0] * maxLumChange); 02703 } 02704 02705 if (lumChange[1] > 0) { 02706 outputIm.at<Vec3b>(iii,jjj)[1] = outputIm.at<Vec3b>(iii, jjj)[1] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * maxLumChange; 02707 } else { 02708 outputIm.at<Vec3b>(iii,jjj)[1] = outputIm.at<Vec3b>(iii, jjj)[1] + (outputIm.at<Vec3b>(iii, jjj)[0] * maxLumChange); 02709 } 02710 02711 if (lumChange[2] > 0) { 02712 outputIm.at<Vec3b>(iii,jjj)[2] = outputIm.at<Vec3b>(iii, jjj)[2] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * maxLumChange; 02713 } else { 02714 outputIm.at<Vec3b>(iii,jjj)[2] = outputIm.at<Vec3b>(iii, jjj)[2] + (outputIm.at<Vec3b>(iii, jjj)[0] * maxLumChange); 02715 } 02716 */ 02717 /* 02718 if (lumChange[0] > 0) { 02719 outputIm.at<Vec3b>(iii,jjj)[0] = outputIm.at<Vec3b>(iii, jjj)[0] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * lumChange[0]; 02720 } else { 02721 outputIm.at<Vec3b>(iii,jjj)[0] = outputIm.at<Vec3b>(iii, jjj)[0] + (outputIm.at<Vec3b>(iii, jjj)[0] * lumChange[0]); 02722 } 02723 02724 if (lumChange[1] > 0) { 02725 outputIm.at<Vec3b>(iii,jjj)[1] = outputIm.at<Vec3b>(iii, jjj)[1] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * lumChange[1]; 02726 } else { 02727 outputIm.at<Vec3b>(iii,jjj)[1] = outputIm.at<Vec3b>(iii, jjj)[1] + (outputIm.at<Vec3b>(iii, jjj)[0] * lumChange[1]); 02728 } 02729 02730 if (lumChange[2] > 0) { 02731 outputIm.at<Vec3b>(iii,jjj)[2] = outputIm.at<Vec3b>(iii, jjj)[2] + (255.0 - outputIm.at<Vec3b>(iii, jjj)[0]) * lumChange[2]; 02732 } else { 02733 outputIm.at<Vec3b>(iii,jjj)[2] = outputIm.at<Vec3b>(iii, jjj)[2] + (outputIm.at<Vec3b>(iii, jjj)[0] * lumChange[2]); 02734 } 02735 */ 02736 02737 /* 02738 outputIm.at<Vec3b>(iii,jjj)[0] = visualIm.at<Vec3b>(iii,jjj)[0]; 02739 outputIm.at<Vec3b>(iii,jjj)[1] = visualIm.at<Vec3b>(iii,jjj)[1]; 02740 outputIm.at<Vec3b>(iii,jjj)[2] = visualIm.at<Vec3b>(iii,jjj)[2]; 02741 */ 02742 } 02743 02744 02745 } 02746 02747 02748 } 02749 } 02750 02751 } 02752 02753 void cScheme::fuse_image(Mat& thermIm, Mat& visualIm, Mat& outputIm, double* params) { 02754 02755 double working_params[2]; 02756 02757 bool alreadyMapped = false; 02758 02759 if (params == NULL) { 02760 working_params[0] = 0.2; 02761 working_params[1] = 0.8; 02762 } else { 02763 working_params[0] = params[0]; 02764 working_params[1] = params[1]; 02765 } 02766 02767 int falseParam = 1; 02768 double lumChange; 02769 02770 unsigned char sr, sg, sb; 02771 02772 Mat newTherm; 02773 02774 outputIm = Mat(newTherm.size(), CV_8UC3); 02775 02776 if (thermIm.channels() > 1) { 02777 02778 if (checkIfActuallyGray(thermIm)) { 02779 cvtColor(thermIm, newTherm, CV_RGB2GRAY); 02780 } else { 02781 thermIm.copyTo(outputIm); 02782 alreadyMapped = true; 02783 } 02784 02785 } else { 02786 thermIm.copyTo(newTherm); 02787 } 02788 02789 Mat newVisual; 02790 02791 if (visualIm.channels() > 1) { 02792 cvtColor(visualIm, newVisual, CV_RGB2GRAY); 02793 } else { 02794 visualIm.copyTo(newVisual); 02795 } 02796 02797 // If images aren't the same size, resize 02798 if (thermIm.size() != visualIm.size()) { 02799 // Determine which one is bigger and resize accordingly 02800 if (thermIm.size().height > thermIm.size().width) { 02801 image_resize(newVisual, thermIm.size().height, thermIm.size().width); 02802 } else { 02803 image_resize(newTherm, visualIm.size().height, visualIm.size().width); 02804 } 02805 } 02806 02807 if (!alreadyMapped) { 02808 falsify_image(newTherm, outputIm, falseParam); 02809 } 02810 02811 // For each pixel 02812 for (int i = 0; i < outputIm.size().height; i++) { 02813 for (int j = 0; j < outputIm.size().width; j++) { 02814 02815 lumChange = 2.0 * (((double) newVisual.at<unsigned char>(i,j))/255.0 - 0.5) * (working_params[1] - working_params[0]); 02816 02817 if (lumChange > 0) { 02818 sr = outputIm.at<Vec3b>(i, j)[0] + (255.0 - outputIm.at<Vec3b>(i, j)[0]) * lumChange; 02819 sg = outputIm.at<Vec3b>(i, j)[1] + (255.0 - outputIm.at<Vec3b>(i, j)[1]) * lumChange; 02820 sb = outputIm.at<Vec3b>(i, j)[2] + (255.0 - outputIm.at<Vec3b>(i, j)[2]) * lumChange; 02821 } else { 02822 sr = outputIm.at<Vec3b>(i, j)[0] + (outputIm.at<Vec3b>(i, j)[0] * lumChange); 02823 sg = outputIm.at<Vec3b>(i, j)[1] + (outputIm.at<Vec3b>(i, j)[1] * lumChange); 02824 sb = outputIm.at<Vec3b>(i, j)[2] + (outputIm.at<Vec3b>(i, j)[2] * lumChange); 02825 } 02826 02827 outputIm.at<Vec3b>(i,j)[0] = sr; 02828 outputIm.at<Vec3b>(i,j)[1] = sg; 02829 outputIm.at<Vec3b>(i,j)[2] = sb; 02830 } 02831 } 02832 02833 } 02834 02835 void generateHistogram(Mat& src, Mat& dst, double* im_hist, double* im_summ, double* im_stat) { 02836 02837 MatND hist; 02838 Mat img; 02839 02840 int nPixels = src.cols*src.rows; 02841 02842 //printf("%s << src.depth() = %d\n", __FUNCTION__, src.depth()); 02843 02844 src.convertTo(img, CV_32FC1); 02845 02846 //svLib::normalize_16(src, img); // no longer old 02847 02848 //imshow("converted", img); 02849 //waitKey(0); 02850 02851 double minIntensity = 9e50, maxIntensity=0; 02852 minMaxLoc(img, &minIntensity, &maxIntensity, 0, 0); 02853 02854 double midIntensity = (maxIntensity + minIntensity) / 2.0; 02855 double intensityRange = maxIntensity-minIntensity; 02856 02857 if (intensityRange < 64) { 02858 minIntensity = midIntensity - 32; 02859 maxIntensity = midIntensity + 32; 02860 } 02861 02862 //double newIntensityRange = maxIntensity-minIntensity; 02863 02864 printf("%s << intensity range = %f (%f, %f)\n", __FUNCTION__, intensityRange, minIntensity, maxIntensity); 02865 02866 int intensityBins = 64; 02867 int histSize[] = {intensityBins}; 02868 float intensityRanges[] = {minIntensity, maxIntensity}; 02869 const float* ranges[] = {intensityRanges}; 02870 int channels[] = {0}; 02871 02872 calcHist(&img, 1, channels, Mat(), hist, 1, histSize, ranges, true, false); 02873 02874 double minVal = 9e50, maxVal=0.0; 02875 minMaxLoc(hist, &minVal, &maxVal, 0, 0); 02876 02877 //printf("%s << minVal = %f; maxVal = %f\n", __FUNCTION__, minVal, maxVal); 02878 02879 int horizontalScale = 640 / intensityBins; 02880 02881 //printf("%s << horizontalScale = %d\n", __FUNCTION__, horizontalScale); 02882 int verticalScale = 480; 02883 Mat histImg = Mat::zeros(verticalScale, intensityBins*horizontalScale, CV_8UC3); //, Vec3b::all(255)); 02884 02885 Scalar col = CV_RGB(255, 255, 255); 02886 histImg.setTo(col); 02887 02888 //int quant01, quant05, quant50, quant95, quant99; 02889 02890 double quantileCount = 0.0; 02891 02892 for(int iii = 0; iii < intensityBins; iii++ ) { 02893 float binVal = hist.at<float>(iii, 0); 02894 float count = binVal/maxVal; 02895 02896 quantileCount += binVal; 02897 02898 /* 02899 printf("%s << iii = %d\n", __FUNCTION__, iii); 02900 printf("%s << binVal = %f\n", __FUNCTION__, binVal); 02901 printf("%s << fullCount = %f\n", __FUNCTION__, fullCount); 02902 */ 02903 02904 if (quantileCount < 0.01*double(nPixels)) { 02905 //quant01 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins)); 02906 } 02907 if (quantileCount < 0.05*double(nPixels)) { 02908 //quant05 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins)); 02909 } 02910 if (quantileCount < 0.50*double(nPixels)) { 02911 //quant50 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins)); 02912 } 02913 if (quantileCount < 0.95*double(nPixels)) { 02914 //quant95 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins)); 02915 } 02916 if (quantileCount < 0.99*double(nPixels)) { 02917 //quant99 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins)); 02918 } 02919 02920 //printf("%s << count = %f\n", __FUNCTION__, count); 02921 02922 rectangle(histImg, Point(iii*horizontalScale+1, verticalScale), Point((iii+1)*horizontalScale-2, (verticalScale-1)*(1-count)+1), CV_RGB(0, 64, 192), CV_FILLED); 02923 } 02924 02925 histImg.copyTo(dst); 02926 02927 double histMean = 0, histDev = 0, histRMS = 0, histSkew = 0; 02928 02929 double pixelCount = img.rows * img.cols; 02930 02931 // Calculate histogram statistics: 02932 for (int iii = 0; iii < img.rows; iii++) { 02933 for (int jjj = 0; jjj < img.cols; jjj++) { 02934 histMean += img.at<float>(iii,jjj) / pixelCount; 02935 } 02936 } 02937 02938 //printf("%s << histMean = %f\n", __FUNCTION__, histMean); 02939 im_stat[0] = histMean; 02940 02941 for (int iii = 0; iii < img.rows; iii++) { 02942 for (int jjj = 0; jjj < img.cols; jjj++) { 02943 histDev += pow((img.at<float>(iii,jjj) - histMean), 2) / pixelCount; 02944 } 02945 } 02946 02947 histDev = pow(histDev, 0.5); 02948 02949 //printf("%s << histDev = %f\n", __FUNCTION__, histDev); 02950 im_stat[1] = histDev; 02951 02952 for (int iii = 0; iii < img.rows; iii++) { 02953 for (int jjj = 0; jjj < img.cols; jjj++) { 02954 histRMS += pow(img.at<float>(iii,jjj), 2) / pixelCount; 02955 } 02956 } 02957 02958 histRMS = pow(histRMS, 0.5); 02959 02960 //printf("%s << histRMS = %f\n", __FUNCTION__, histRMS); 02961 02962 im_stat[2] = histRMS; 02963 02964 for (int iii = 0; iii < img.rows; iii++) { 02965 for (int jjj = 0; jjj < img.cols; jjj++) { 02966 histSkew += pow((img.at<float>(iii,jjj)- histMean) / histDev, 3) / pixelCount; 02967 } 02968 } 02969 02970 //printf("%s << histSkew = %f\n", __FUNCTION__, histSkew); 02971 02972 im_stat[3] = histSkew; 02973 02974 //printf("%s << qrange_0_100 = %d\n", __FUNCTION__, int(intensityRange)); 02975 02976 //printf("%s << qrange_1_99 = %d\n", __FUNCTION__, quant99-quant01); 02977 02978 //printf("%s << qrange_5_95 = %d\n", __FUNCTION__, quant95-quant05); 02979 02980 } 02981 02982 Mat normForDisplay(Mat origMat) { 02983 double minVal = 9e99, maxVal = -9e99; 02984 02985 for (int iii = 0; iii < origMat.rows; iii++) { 02986 for (int jjj = 0; jjj < origMat.cols; jjj++) { 02987 02988 // printf("%s << origMat.val = %f\n", __FUNCTION__, origMat.at<double>(iii,jjj)); 02989 02990 02991 if (origMat.at<double>(iii,jjj) > maxVal) { 02992 maxVal = origMat.at<double>(iii,jjj); 02993 } 02994 02995 if (origMat.at<double>(iii,jjj) < minVal) { 02996 minVal = origMat.at<double>(iii,jjj); 02997 } 02998 } 02999 } 03000 03001 Mat displayMat(origMat.size(), CV_8UC1); 03002 03003 for (int iii = 0; iii < origMat.rows; iii++) { 03004 for (int jjj = 0; jjj < origMat.cols; jjj++) { 03005 displayMat.at<unsigned char>(iii,jjj) = (unsigned char) ((origMat.at<double>(iii,jjj) - minVal) * 255.0 / (maxVal - minVal)); 03006 } 03007 } 03008 03009 Mat largerMat; 03010 03011 resize(displayMat, largerMat, Size(origMat.rows*1, origMat.cols*1), 0, 0, INTER_NEAREST); 03012 03013 return largerMat; 03014 }