improc.cpp
Go to the documentation of this file.
00001 
00005 #include "improc.hpp"
00006 
00007 double scoreColorImage(const cv::Mat& src) {
00008         
00009         double score = 0.00;
00010         
00011         double percentileVals[3] = { 0.001, 0.500, 0.999 };
00012         double intensityVals[3];
00013         findPercentiles(src, intensityVals, percentileVals, 3);
00014 
00015         
00016         double range = std::max(abs(intensityVals[2] - intensityVals[1]), abs(intensityVals[0] - intensityVals[1]));
00017         
00018         //printf("%s << range = (%f)\n", __FUNCTION__, range);
00019         
00020         score = min(range, 128.0) / 128.0;
00021         
00022         return score;
00023         
00024 }
00025 
00026 double scoreThermalImage(const cv::Mat& src) {
00027         
00028         double score = 0.00;
00029         
00030         /*
00031         for (unsigned int iii = 0; iii < src.rows; iii++) {
00032                 for (unsigned int jjj = 0; jjj < src.cols; jjj++) {
00033                         
00034                 }
00035         }
00036         */
00037         
00038         double percentileVals[3] = { 0.001, 0.500, 0.999 };
00039         double intensityVals[3];
00040         findPercentiles(src, intensityVals, percentileVals, 3);
00041 
00042         
00043         double range = std::max(abs(intensityVals[2] - intensityVals[1]), abs(intensityVals[0] - intensityVals[1]));
00044         
00045         range /= 10.0;
00046         
00047         // printf("%s << range = (%f)\n", __FUNCTION__, range);
00048         
00049         score = min(range, 10.0) / 10.0;
00050         
00051         return score;
00052 }
00053 
00054 void combineImages(const cv::Mat& im1, const cv::Mat& im2, cv::Mat& dst) {
00055         
00056         //printf("%s << im1.size() = (%d, %d); im2.size() = (%d, %d); types = (%d, %d, %d, %d)\n", __FUNCTION__, im1.rows, im1.cols, im2.rows, im2.cols, im1.channels(), im1.depth(), im2.channels(), im2.depth());
00057         
00058         dst = cv::Mat::zeros(im1.size(), CV_8UC3);
00059         
00060         for (int iii = 0; iii < im1.rows; iii++) {
00061                 for (int jjj = 0; jjj < im1.cols; jjj++) {
00062                         
00063                         dst.at<cv::Vec3b>(iii,jjj)[1] = im1.at<unsigned char>(iii,jjj);
00064                         dst.at<cv::Vec3b>(iii,jjj)[2] = im2.at<unsigned char>(iii,jjj);
00065                         
00066                 }
00067         }
00068         
00069 }
00070 
00071 void unpackTo8bit3Channel(const cv::Mat& src, cv::Mat& dst) {
00072         
00073         dst = cv::Mat(src.size(), CV_8UC3);
00074         
00075         for (int iii = 0; iii < src.rows; iii++) {
00076                 for (int jjj = 0; jjj < src.cols; jjj++) {
00077                         
00078                         // First byte should be the major component
00079                         dst.at<cv::Vec3b>(iii,jjj)[0] = src.at<unsigned short>(iii,jjj) >> 8;
00080                         
00081                         // Second byte should be the minor component
00082                         dst.at<cv::Vec3b>(iii,jjj)[1] = src.at<unsigned short>(iii,jjj) & 0x00FF;
00083                         dst.at<cv::Vec3b>(iii,jjj)[2] = 0;
00084                         
00085                         if (src.at<unsigned short>(iii,jjj) != (256 * dst.at<cv::Vec3b>(iii,jjj)[0]) + dst.at<cv::Vec3b>(iii,jjj)[1]) {
00086                                 printf("%s << ERROR! (%d) != (%d, %d)\n", __FUNCTION__, src.at<unsigned short>(iii,jjj), dst.at<cv::Vec3b>(iii,jjj)[0], dst.at<cv::Vec3b>(iii,jjj)[1]);
00087                                 cin.get();
00088                         }
00089                         
00090                 }
00091         }
00092         
00093 }
00094 
00095 double findBestAlpha(const cv::Mat& K, const cv::Mat& coeff, const cv::Size& camSize) {
00096         
00097         cv::Mat newCamMat;
00098         
00099         cv::Rect roi;
00100         
00101         double alpha = 0.00;
00102         bool centerPrincipalPoint = true;
00103         
00104         cv::Mat map1, map2;
00105         
00106         unsigned int protectionCounter = 0;
00107         
00108         cv::Mat R_default = cv::Mat::eye(3, 3, CV_64FC1);
00109         
00110         while (1) {
00111                 
00112                 cv::Mat white = cv::Mat::ones(camSize, CV_16UC1);
00113                 cv::Mat mapped;
00114                 
00115                 newCamMat = getOptimalNewCameraMatrix(K, coeff, camSize, alpha, camSize, &roi, centerPrincipalPoint);
00116                 
00117                 initUndistortRectifyMap(K, coeff, R_default, newCamMat, camSize, CV_32FC1, map1, map2);
00118                 
00119                 double minVal, maxVal;
00120                 
00121                 cv::Mat scaled_white;
00122                 white.convertTo(scaled_white, CV_16UC1, 65535, 0);
00123                 
00124                 remap(scaled_white, mapped, map1, map2, cv::INTER_LINEAR, cv::BORDER_CONSTANT, 0);
00125                 
00126                 //imshow("scaled_white", mapped);
00127                 //waitKey();
00128                 
00129                 minMaxLoc(mapped, &minVal, &maxVal);
00130                 
00131                 if (minVal == 65535.0) {
00132                         break;
00133                 }
00134                 
00135                 if (protectionCounter == 100) {
00136                         alpha = 0.0;
00137                         break;
00138                 }
00139                 
00140                 alpha -= 0.01;
00141                 protectionCounter++;
00142         }
00143 
00144         return alpha;
00145         
00146 }
00147 
00148 void splitMultimodalImage(const cv::Mat& src, cv::Mat& therm, cv::Mat& vis) {
00149 
00150         therm = cv::Mat::zeros(src.size(), CV_8UC1);
00151         vis = cv::Mat::zeros(src.size(), CV_8UC1);
00152         
00153         #pragma omp parallel for
00154         for (int iii = 0; iii < src.rows; iii++) {
00155                 for (int jjj = 0; jjj < src.cols; jjj++) {
00156                         therm.at<unsigned char>(iii,jjj) = src.at<cv::Vec3b>(iii,jjj)[2];
00157                         vis.at<unsigned char>(iii,jjj) = src.at<cv::Vec3b>(iii,jjj)[1];
00158                 }
00159         }
00160         
00161 }
00162 
00163 void applyFilter(const cv::Mat& src, cv::Mat& dst, int filter, double param) {
00164         
00165         int ksize;
00166         
00167         if (filter == GAUSSIAN_FILTERING) {
00168                 ksize = int(param * 2);
00169         } else {
00170                 if (filter != BILATERAL_FILTERING) { printf("%s << ERROR!\n", __FUNCTION__); }
00171                 ksize = int(param);
00172         }
00173         
00174         if ((int(ksize) % 2) == 0) {
00175                 ksize++;
00176         }
00177         
00178         //double bilateralVal = param;
00179         
00180         if (filter == GAUSSIAN_FILTERING) {
00181                 GaussianBlur(src, dst, cv::Size(ksize, ksize), sqrt(param));
00182         } else if (filter == BILATERAL_FILTERING) {
00183                 bilateralFilter(src, dst, ksize, param * 2.0, param * 2.0); //, double sigmaColor, double sigmaSpace, int borderType=BORDER_DEFAULT );
00184         } else {
00185                 src.copyTo(dst);
00186         }
00187         
00188 }
00189 
00190 /*
00191 void straightCLAHE(const cv::Mat& src, cv::Mat& dst, double factor) {
00192         
00193         int xdivs = 2;
00194         int ydivs = 2;
00195         int bins = 256;
00196         //int limit_counter = 255.0 * factor;
00197         
00198         IplImage tmp_ipl(src);
00199         
00200         
00201         IplImage* dst_ipl = cvCreateImage(cvSize(tmp_ipl.width,tmp_ipl.height), tmp_ipl.depth, 1);
00202         dst_ipl->origin = tmp_ipl.origin;
00203           
00204         //IplImage dst_ipl;
00205         
00206         #ifdef USE_CLAHE
00207         cvCLAdaptEqualize(&tmp_ipl, dst_ipl, (unsigned int) xdivs, (unsigned int) ydivs, 
00208                                         (unsigned int) bins, (1.0 + factor * 14.0), CV_CLAHE_RANGE_FULL);
00209         // (float) limit_counter * 0.1
00210         #endif
00211         
00212         
00213         dst = cv::Mat(dst_ipl);
00214         
00215 }
00216 */
00217 
00218 /*
00219 void downsampleCLAHE(const cv::Mat& src, cv::Mat& dst, double factor) {
00220         
00221         cv::Mat tmp;
00222         
00223         if (factor == 0.0) {
00224                 
00225                 adaptiveDownsample(src, dst, NORMALIZATION_STANDARD, 0.001);
00226         
00227                 return;
00228         }
00229         
00230         // from: https://github.com/joshdoe/opencv-clahe
00231 
00232         // ...
00233         
00234         //printf("%s << entered...\n", __FUNCTION__);
00235         
00236         cv::Mat tmp_2;
00237         
00238         adaptiveDownsample(src, tmp_2, NORMALIZATION_STANDARD, 0.001);
00239         
00240         straightCLAHE(tmp_2, dst, factor);
00241         
00242         
00243         //int xdivs = 2;
00244         //int ydivs = 2;
00245         //int bins = 256;
00247         
00248         //IplImage tmp_ipl(tmp_2);
00249         
00250         
00251         //IplImage* dst_ipl = cvCreateImage(cvSize(tmp_ipl.width,tmp_ipl.height), tmp_ipl.depth, 1);
00252         //dst_ipl->origin = tmp_ipl.origin;
00253           
00255         
00256         //cvCLAdaptEqualize(&tmp_ipl, dst_ipl, (unsigned int) xdivs, (unsigned int) ydivs, 
00257                                         //(unsigned int) bins, (1.0 + factor * 14.0), CV_CLAHE_RANGE_FULL);
00259         
00260         
00261         //dst = Mat(dst_ipl);
00262         
00264         
00265 }
00266 */
00267 
00268 void temperatureDownsample(const cv::Mat& src, cv::Mat& dst, double minVal, double maxVal) {
00269         
00270         if (dst.rows == 0) {
00271                 dst = cv::Mat::zeros(src.size(), CV_8UC1);
00272         }
00273         
00274         #pragma omp parallel for
00275         for (int iii = 0; iii < src.rows; iii++) {
00276                 for (int jjj = 0; jjj < src.cols; jjj++) {
00277 
00278                         dst.at<unsigned char>(iii,jjj) = std::min(255.0, std::max(0.0, (std::max(src.at<float>(iii,jjj) - minVal, 0.0) / (maxVal - minVal)) * 255.0));
00279                         
00280                         /*
00281                         if ((iii % 10 == 0) && (jjj % 10 == 0)) {
00282                                 printf("%s << (%f) to (%d)\n", __FUNCTION__, src.at<float>(iii,jjj), dst.at<unsigned char>(iii,jjj));
00283                         }
00284                         */
00285 
00286                 }
00287         }
00288         
00289 }
00290 
00291 void convertToTemperatureMat(const cv::Mat& src, cv::Mat& dst) {
00292         
00293         if (dst.rows == 0) {
00294                 dst = cv::Mat::zeros(src.size(), CV_32FC1);
00295         }
00296         
00297         #pragma omp parallel for
00298         for (int iii = 0; iii < src.rows; iii++) {
00299                 for (int jjj = 0; jjj < src.cols; jjj++) {
00300 
00301                         dst.at<float>(iii,jjj) = (float(src.at<unsigned short>(iii,jjj)) - 1000.0) / 10.0;
00302 
00303                 }
00304         }
00305         
00306 }
00307 
00308 void temperatureDownsample16(const cv::Mat& src, cv::Mat& dst) {
00309         
00310         if (dst.rows == 0) {
00311                 dst = cv::Mat::zeros(src.size(), CV_16UC1);
00312         }
00313         
00314         #pragma omp parallel for
00315         for (int iii = 0; iii < src.rows; iii++) {
00316                 for (int jjj = 0; jjj < src.cols; jjj++) {
00317 
00318                         dst.at<unsigned short>(iii,jjj) = floor(((src.at<float>(iii,jjj) * 10.0) + 1000.0) + 0.5);
00319                         
00320 
00321                 }
00322         }
00323         
00324 }
00325 
00326 void convert16bitTo8bitConfidence(const cv::Mat& src, const cv::Mat& conf, cv::Mat& dst) {
00327         
00328         if (dst.rows == 0) {
00329                 dst = cv::Mat::zeros(src.size(), CV_8UC3);
00330         }
00331         
00332         #pragma omp parallel for
00333         for (int iii = 0; iii < src.rows; iii++) {
00334                 for (int jjj = 0; jjj < src.cols; jjj++) {
00335 
00336                         // ORIGINAL PLAN!
00337                         
00338                         dst.at<cv::Vec3b>(iii,jjj)[1] = src.at<unsigned short>(iii,jjj) % 256;
00339                         dst.at<cv::Vec3b>(iii,jjj)[0] = (src.at<unsigned short>(iii,jjj) - (src.at<unsigned short>(iii,jjj) % 256) ) / 256;
00340                         
00341                         
00342                         /*
00343                         dst.at<cv::Vec3b>(iii,jjj)[0] = (unsigned char) ((max(20.0, min(45.0, (float(src.at<unsigned short>(iii,jjj)) - 1000.0) / 10.0))-20.0)*10.0);
00344                         dst.at<cv::Vec3b>(iii,jjj)[1] = 0;
00345                         */
00346                         
00347                         // printf("%s << splitting (%d) (%f) into (%d) and (%d)\n", __FUNCTION__, src.at<unsigned short>(iii,jjj), float((src.at<unsigned short>(iii,jjj) - 1000) / 10), dst.at<cv::Vec3b>(iii,jjj)[0], dst.at<cv::Vec3b>(iii,jjj)[1]);
00348                         
00349                         dst.at<cv::Vec3b>(iii,jjj)[2] = (unsigned char) (255.0 * conf.at<double>(iii,jjj));
00350 
00351                 }
00352         }
00353         
00354 }
00355 
00356 void fixedDownsample(const cv::Mat& src, cv::Mat& dst, double center, double range) {
00357 
00358         dst = cv::Mat::zeros(src.rows, src.cols, CV_8UC1);
00359 
00360         #pragma omp parallel for
00361         for (int iii = 0; iii < src.rows; iii++) {
00362                 for (int jjj = 0; jjj < src.cols; jjj++) {
00363 
00364                         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)));
00365 
00366                 }
00367         }
00368 
00369 }
00370 
00371 void applyIntensityShift(const cv::Mat& src1, cv::Mat& dst1, const cv::Mat& src2, cv::Mat& dst2, double grad, double shift) {
00372 
00373         double center = 8000.0, range = 1.0;
00374 
00375         double percentileVals[3] = { 0.001, 0.500, 0.999 };
00376         double intensityVals[3];
00377         findPercentiles(src1, intensityVals, percentileVals, 3);
00378 
00379         center = intensityVals[1];
00380         range = std::max(abs(intensityVals[2] - intensityVals[1]), abs(intensityVals[0] - intensityVals[1]));
00381 
00382         //printf("%s << normalizing with center = (%f) and range = (%f)\n", __FUNCTION__, center, range);
00383 
00384         //adaptiveDownsample(src1, dst1);
00385         fixedDownsample(src1, dst1, center, 2.0*range);
00386 
00387         cv::Mat src2_shifted(src2.rows, src2.cols, src2.type());
00388         // src2.copyTo(src2_shifted);
00389 
00390         #pragma omp parallel for
00391         for (int iii = 0; iii < src2_shifted.rows; iii++) {
00392                 for (int jjj = 0; jjj < src2_shifted.cols; jjj++) {
00393 
00394                         src2_shifted.at<unsigned short>(iii,jjj) = grad * double(src2.at<unsigned short>(iii,jjj)) + shift;
00395 
00396                 }
00397         }
00398 
00399         //adaptiveDownsample(src2_shifted, dst2);
00400         fixedDownsample(src2_shifted, dst2, center, range);
00401 
00402 }
00403 
00404 void drawGrid(const cv::Mat& src, cv::Mat& dst, int mode) {
00405 
00406         src.copyTo(dst);
00407 
00408         cv::Scalar col;
00409 
00410         int shift;
00411 
00412         if (mode == 0) {
00413                 shift = 0;
00414                 col = CV_RGB(255, 0, 0);
00415         } else {
00416                 shift = 1;
00417                 col = CV_RGB(0, 0, 255);
00418         }
00419 
00420         cv::Point2f startPt, endPt;
00421 
00422         double amt = double(src.cols) / 8.0;
00423 
00424         // Vertical lines
00425         for (int iii = shift; iii <= 8-shift; iii++) {
00426                 startPt = cv::Point2f(16.0 * double(iii)*amt, 16.0 * double(shift)*amt);
00427                 endPt = cv::Point2f(16.0 * double(iii)*amt, 16.0 * (double(src.rows) - double(shift)*amt));
00428 
00429                 line(dst, startPt, endPt, col, 1, CV_AA, 4);
00430         }
00431 
00432         // Horizontal lines
00433         for (int iii = shift; iii <= 6-shift; iii++) {
00434 
00435                 startPt = cv::Point2f(16.0 * double(shift)*amt, 16.0 * double(iii)*amt);
00436                 endPt = cv::Point2f(16.0 * (double(src.cols) - double(shift)*amt), 16.0 * double(iii)*amt);
00437 
00438                 line(dst, startPt, endPt, col, 1, CV_AA, 4);
00439 
00440         }
00441 
00442 
00443 }
00444 
00445 void histExpand8(const cv::Mat& src, cv::Mat& dst) {
00446 
00447         double minVal, maxVal;
00448         minMaxLoc(src, &minVal, &maxVal);
00449 
00450         dst = cv::Mat::zeros(src.size(), src.type());
00451 
00452         #pragma omp parallel for
00453         for (int iii = 0; iii < src.rows; iii++) {
00454                 for (int jjj = 0; jjj < src.cols; jjj++) {
00455 
00456                         unsigned char val = (unsigned char) (((double)src.at<unsigned char>(iii,jjj)) - minVal) * 255.0 / (maxVal - minVal);
00457 
00458                         dst.at<unsigned char>(iii,jjj) = val;
00459                 }
00460         }
00461 
00462 }
00463 
00464 void clusterRectangles(vector<cv::Rect>& rectangles, double minOverlap) {
00465 
00466     if (rectangles.size() == 0) {
00467         return;
00468     }
00469 
00470     unsigned int j,k;
00471 
00472     bool hasBeenClustered;
00473 
00474     vector<cv::Rect> falseVector;
00475 
00476     cv::Rect tempRect;
00477 
00478     vector<vector<cv::Rect> > clusteredRectangles;
00479 
00480     clusteredRectangles.push_back(falseVector);
00481 
00482     clusteredRectangles.at(0).push_back(rectangles.at(0));
00483 
00484     // For each remaining rectangle
00485     for (unsigned int i = 1; i < rectangles.size(); i++) {
00486 
00487         hasBeenClustered = false;
00488 
00489         j = 0;
00490         k = 0;
00491 
00492         while (!hasBeenClustered) {
00493             if (rectangleOverlap(rectangles.at(i), clusteredRectangles.at(j).at(k)) > minOverlap) {
00494                 clusteredRectangles.at(j).push_back(rectangles.at(i));
00495                 hasBeenClustered = true;
00496             } else if (k < clusteredRectangles.at(j).size()-1) {
00497                 k++;
00498             } else if (j < clusteredRectangles.size()-1) {
00499                 j++;
00500                 k = 0;
00501             } else {
00502                 clusteredRectangles.push_back(falseVector);
00503                 clusteredRectangles.at(j+1).push_back(rectangles.at(i));
00504                 hasBeenClustered = true;
00505             }
00506         }
00507 
00508         //printf("%s << overlapProp = %f\n", __FUNCTION__, overlapProp);
00509 
00510     }
00511 
00512     rectangles.clear();
00513 
00514     for (unsigned int i = 0; i < clusteredRectangles.size(); i++) {
00515         tempRect = meanRectangle(clusteredRectangles.at(i));
00516         rectangles.push_back(tempRect);
00517     }
00518 
00519 }
00520 
00521 cv::Rect meanRectangle(vector<cv::Rect>& rectangles) {
00522 
00523     cv::Rect retVal;
00524     double xSum = 0.0, ySum = 0.0, wSum = 0.0, hSum = 0.0;
00525 
00526     for (unsigned int i = 0; i < rectangles.size(); i++) {
00527         xSum += rectangles.at(i).x;
00528         ySum += rectangles.at(i).y;
00529         wSum += rectangles.at(i).width;
00530         hSum += rectangles.at(i).height;
00531     }
00532 
00533     xSum /= rectangles.size();
00534     ySum /= rectangles.size();
00535     wSum /= rectangles.size();
00536     hSum /= rectangles.size();
00537 
00538     retVal = cv::Rect(int(xSum), int(ySum), int(wSum), int(hSum));
00539 
00540     return retVal;
00541 }
00542 
00543 void weightedMixture(cv::Mat& dst, const cv::vector<cv::Mat>& srcs, const std::vector<double>& weightings) {
00544 
00545     double totalWeighting = 0.0;
00546     vector<double> newWeightings;
00547     newWeightings.insert(newWeightings.end(), weightings.begin(), weightings.end());
00548 
00549     for (unsigned int iii = 0; iii < weightings.size(); iii++) {
00550         totalWeighting += weightings.at(iii);
00551     }
00552 
00553     for (unsigned int iii = 0; iii < weightings.size(); iii++) {
00554         newWeightings.at(iii) /= totalWeighting;
00555     }
00556 
00557     cv::Mat tmpDst = cv::Mat::zeros(srcs.at(0).size(), CV_64FC3);
00558 
00559     for (unsigned int i = 0; i < srcs.size(); i++) {
00560 
00561         for (int m = 0; m < srcs.at(i).rows; m++) {
00562 
00563             for (int n = 0; n < srcs.at(i).cols; n++) {
00564 
00565                 for (int k = 0; k < 3; k++) {
00566                     tmpDst.at<cv::Vec3d>(m,n)[k] += double((srcs.at(i)).at<cv::Vec3b>(m,n)[k]) * newWeightings.at(i);
00567                 }
00568 
00569             }
00570 
00571         }
00572 
00573     }
00574 
00575     cv::Mat normMat;
00576     normalize_64_vec(normMat, tmpDst);
00577 
00578     dst = cv::Mat(normMat.size(), CV_8UC3);
00579     convertScaleAbs(normMat, dst, 255);
00580 
00581 }
00582 
00583 void mixImages(cv::Mat& dst, cv::vector<cv::Mat>& images) {
00584     // No checks at present...
00585 
00586     dst = cv::Mat::zeros(images.at(0).size(), CV_64FC3);
00587     cv::Mat tmp;
00588     dst.copyTo(tmp);
00589 
00590         
00591     for (unsigned int i = 0; i < images.size(); i++) {
00592 
00593         for (int m = 0; m < images.at(i).rows; m++) {
00594 
00595             for (int n = 0; n < images.at(i).cols; n++) {
00596 
00597                 for (int k = 0; k < 3; k++) {
00598                     dst.at<cv::Vec3d>(m,n)[k] += double((images.at(i)).at<cv::Vec3b>(m,n)[k]) / images.size();
00599                 }
00600 
00601 
00602 
00603             }
00604 
00605 
00606         }
00607 
00608         normalize_64_vec(tmp, dst);
00609 
00610         //imshow("tmp", tmp);
00611         //waitKey(0);
00612 
00613     }
00614 
00615 }
00616 
00617 bool rectangle_contains_centroid(cv::Rect mainRectangle, cv::Rect innerRectangle) {
00618     bool retVal = false;
00619 
00620     //printf("%s << Main Rectangle: [%d, %d] : [%d, %d]\n", __FUNCTION__, mainRectangle.x, mainRectangle.y, mainRectangle.x+mainRectangle.width, mainRectangle.y+mainRectangle.height);
00621     //printf("%s << Centroid: [%d, %d]\n", __FUNCTION__, innerRectangle.x + innerRectangle.width/2, innerRectangle.y + innerRectangle.height/2);
00622 
00623     retVal = mainRectangle.contains(cv::Point(innerRectangle.x + innerRectangle.width/2, innerRectangle.y + innerRectangle.height/2));
00624 
00625     return retVal;
00626 }
00627 
00628 cv::Point rectangle_center(cv::Rect input) {
00629     cv::Point center;
00630 
00631     center.x = input.x + input.width/2;
00632     center.y = input.y + input.height/2;
00633 
00634 
00635     return center;
00636 }
00637 
00638 double rectangleOverlap(cv::Rect rectangle1, cv::Rect rectangle2) {
00639 
00640     double area1, area2, exLeft, exRight, exTop, exBot, overlapArea, overlapProp;
00641 
00642     area1 = rectangle1.width*rectangle1.height;
00643     area2 = rectangle2.width*rectangle2.height;
00644 
00645     exLeft = max(rectangle1.x, rectangle2.x);
00646     exRight = min(rectangle1.x+rectangle1.width, rectangle2.x+rectangle2.width);
00647     exTop = max(rectangle1.y, rectangle2.y);
00648     exBot = min(rectangle1.y+rectangle1.height, rectangle2.y+rectangle2.height);
00649 
00650     if ((exLeft > exRight) || (exTop > exBot)) {
00651         return 0.0;
00652     }
00653 
00654     overlapArea = (exRight-exLeft)*(exBot-exTop);
00655 
00656     overlapProp = overlapArea / (max(area1, area2));
00657 
00658     return overlapProp;
00659 
00660 }
00661 
00662 void trimToDimensions(cv::Mat& image, int width, int height) {
00663 
00664     cv::Mat dst;
00665 
00666     int imWidth = image.cols;
00667     int imHeight = image.rows;
00668 
00669     double actualRatio = double(imWidth)/double(imHeight);
00670     double wantedRatio = double(width)/double(height);
00671 
00672     int initialWidth, initialHeight;
00673 
00674     //imshow("cropping", image);
00675     //waitKey(0);
00676 
00677     printf("%s << image dimensions = %d x %d.\n", __FUNCTION__, imWidth, imHeight);
00678     printf("%s << desired dimensions = %d x %d.\n", __FUNCTION__, width, height);
00679 
00680     printf("%s << actualRatio = %f; wantedRatio = %f\n", __FUNCTION__, actualRatio, wantedRatio);
00681 
00682     if (actualRatio < wantedRatio) {
00683         printf("%s << taller than we want.\n", __FUNCTION__);
00684 
00685         initialWidth = width;
00686         initialHeight = int(double(width)/actualRatio);
00687 
00688         // resize to get width to exactly desired width
00689         resize(image, dst, cv::Size(initialWidth, initialHeight));
00690 
00691         //imshow("cropping", dst);
00692         //waitKey(0);
00693 
00694         // cut down height to desired height
00695         int topY = (dst.rows - height)/2;
00696         int botY = topY + height;
00697 
00698         printf("%s << topY = %d; botY = %d\n", __FUNCTION__, topY, botY);
00699 
00700         cropImage(dst, cv::Point(0, topY), cv::Point(width, botY));
00701 
00702         //imshow("cropping", dst);
00703         //waitKey(0);
00704 
00705     } else if (actualRatio >= wantedRatio) {
00706         printf("%s << wider than we want.\n", __FUNCTION__);
00707 
00708         initialWidth = int(double(height)*actualRatio);
00709         initialHeight = height;
00710 
00711         // resize to get width to exactly desired width
00712         resize(image, dst, cv::Size(initialWidth, initialHeight));
00713 
00714         //imshow("cropping", dst);
00715         //waitKey(0);
00716 
00717         // cut down height to desired height
00718         int leftX = (dst.cols - width)/2;
00719         int rightX = leftX + width;
00720 
00721         printf("%s << leftX  = %d; rightX = %d\n", __FUNCTION__, leftX , rightX);
00722 
00723         cropImage(dst, cv::Point(leftX, 0), cv::Point(rightX, height));
00724 
00725         //imshow("cropping", dst);
00726         //waitKey(0);
00727 
00728     }
00729 
00730     dst.copyTo(image);
00731 
00732 
00733 }
00734 
00735 void process8bitImage(const cv::Mat& src, cv::Mat& dst, int code, double factor) {
00736         
00737         //printf("%s << processing... (%d)\n", __FUNCTION__, code);
00738         
00739         if (code == NORMALIZATION_EQUALIZE) {
00740 
00741                 equalizeHist(src, dst);
00742 
00743         } /*else if (code == NORMALIZATION_CLAHE) { 
00744         
00745                 //downsampleCLAHE(src, dst, factor);
00746                 //printf("%s << Trying to perform CLAHE...\n", __FUNCTION__);
00747                 straightCLAHE(src, dst, factor);
00748         
00749         } */ else {
00750                 src.copyTo(dst);
00751         }
00752 }
00753 
00754 void adaptiveDownsample(const cv::Mat& src, cv::Mat& dst, int code, double factor) {
00755 
00756         cv::Mat dwn, _16;
00757 
00758         double minVal, maxVal;
00759         minMaxLoc(src, &minVal, &maxVal);
00760         
00761         //printf("%s << min/max = (%f / %f)\n", __FUNCTION__, minVal, maxVal);
00762         
00763         
00764 
00765         //double percentileVals[3] = { MIN_PROP_THRESHOLD, 0.500, 1 - MIN_PROP_THRESHOLD };
00766         double percentileVals[5] = { 0.001, (factor / 2.0), 0.500, 1.0 - (factor / 2.0), 0.999 };
00767         double intensityVals[5];
00768 
00769         findPercentiles(src, intensityVals, percentileVals, 5);
00770         
00771         intensityVals[1] = max(intensityVals[1], minVal);
00772         intensityVals[3] = min(intensityVals[3], maxVal);
00773 
00774         //printf("%s << factor = (%f); vals = (%f, %f)\n", __FUNCTION__, factor, intensityVals[0], intensityVals[2]);
00775 
00776         double midVal = (intensityVals[0] + intensityVals[4]) / 2.0; // (intensityVals[0] + intensityVals[2]) / 2.0;
00777         double centralVal = intensityVals[1]; // (maxVal + minVal) / 2.0; // 
00778         //double halfRange = max(abs(intensityVals[3] - midVal), abs(intensityVals[1] - midVal));
00779         double fullRange = abs(intensityVals[3] - intensityVals[1]);
00780         double compressionFactor = 1.0;
00781 
00782         if (code == NORMALIZATION_STANDARD) {
00783 
00784                 if (fullRange > 255.0) {
00785                         compressionFactor = fullRange / 255.0;
00786                 }
00787 
00788                 minVal = intensityVals[1];
00789                 maxVal = intensityVals[3];
00790                 
00791                 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl;
00792                 
00793                 normalize_16(_16, src, minVal, maxVal);
00794                 down_level(dst, _16);
00795 
00796         } else if (code == NORMALIZATION_CENTRALIZED) {
00797 
00798                 compressionFactor = 255.0 / (4.0 * max(factor, 0.01));
00799 
00800                 //printf("%s << centralVal = (%f); compressionFactor = (%f)\n", __FUNCTION__, centralVal, compressionFactor);
00801                 minVal = centralVal - compressionFactor;
00802                 maxVal = centralVal + compressionFactor;
00803                 
00804                 minVal = max(minVal, 0.0);
00805                 maxVal = min(maxVal, 65535.0);
00806                 
00807                 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl;
00808                 
00809                 //minVal = ((intensityVals[0] + intensityVals[2]) / 2.0) - 127.5 * compressionFactor;
00810                 //maxVal = ((intensityVals[0] + intensityVals[2]) / 2.0) + 127.5 * compressionFactor;
00811                 
00812                 normalize_16(_16, src, minVal, maxVal);
00813                 
00814                 //imshow("test", _16);
00815                 //waitKey(1);
00816                 down_level(dst, _16);
00817 
00818         } else if (code == NORMALIZATION_EXPANDED) {
00819 
00820                 compressionFactor = 255.0 / (4.0 * max(factor, 0.01));
00821 
00822                 //printf("%s << centralVal = (%f); compressionFactor = (%f)\n", __FUNCTION__, centralVal, compressionFactor);
00823                 minVal = midVal - compressionFactor;
00824                 maxVal = midVal + compressionFactor;
00825                 
00826                 minVal = max(minVal, 0.0);
00827                 maxVal = min(maxVal, 65535.0);
00828                 
00829                 //cout << "minVal = " << minVal << ", maxVal = " << maxVal << endl;
00830                 
00831                 //minVal = ((intensityVals[0] + intensityVals[2]) / 2.0) - 127.5 * compressionFactor;
00832                 //maxVal = ((intensityVals[0] + intensityVals[2]) / 2.0) + 127.5 * compressionFactor;
00833                 
00834                 normalize_16(_16, src, minVal, maxVal);
00835                 
00836                 //imshow("test", _16);
00837                 //waitKey(1);
00838                 down_level(dst, _16);
00839 
00840         } else if (code == NORMALIZATION_EQUALIZE) {
00841 
00842                 normalize_16(_16, src, intensityVals[1], intensityVals[3]);
00843                 down_level(dwn, _16);
00844                 equalizeHist(dwn, dst);
00845 
00846         } /* else if (code == NORMALIZATION_CLAHE) { 
00847                 cv::Mat dst_inter;
00848                 adaptiveDownsample(src, dst_inter, NORMALIZATION_STANDARD, 0.001);
00849                 straightCLAHE(dst_inter, dst, factor);
00850                 
00851         } */ /* else if (code == NORMALIZATION_ADAPTIVE) {
00852                 cv::Mat dst_inter;
00853                 double adaptive_factor = min(1.0, (255.0 / (maxVal - minVal)) * factor);
00854                 adaptiveDownsample(src, dst_inter, NORMALIZATION_STANDARD, 0.001);
00855                 straightCLAHE(dst_inter, dst, adaptive_factor);
00856                 
00857         } */ else {
00858 
00859                 src.convertTo(dst, CV_8UC1);
00860 
00861         }
00862 
00863 }
00864 
00865 
00866 
00867 void drawLinesBetweenPoints(cv::Mat& image, const vector<cv::Point2f>& src, const vector<cv::Point2f>& dst)
00868 {
00869 
00870     cv::Point p1, p2;
00871 
00872     for (unsigned int i = 0; i < src.size(); i++)
00873     {
00874         p1 = cv::Point(src.at(i).x*16, src.at(i).y*16);
00875         p2 = cv::Point(dst.at(i).x*16, dst.at(i).y*16);
00876 
00877         //line(image, p1, p2, CV_RGB(0,0,255), 1, CV_AA, 4);
00878         circle(image, p2, 4*16, CV_RGB(0,0,255), 1, CV_AA, 4);
00879     }
00880 
00881 }
00882 
00883 cv::Point findCentroid(vector<cv::Point>& contour)
00884 {
00885     cv::Moments momentSet;
00886 
00887     double x,y;
00888 
00889     momentSet = moments(cv::Mat(contour));
00890     x = momentSet.m10/momentSet.m00;
00891     y = momentSet.m01/momentSet.m00;
00892 
00893     return cv::Point((int)x,(int)y);
00894 }
00895 
00896 cv::Point2f findCentroid2f(vector<cv::Point>& contour)
00897 {
00898     cv::Moments momentSet;
00899 
00900     double x,y;
00901 
00902     momentSet = moments(cv::Mat(contour));
00903     x = momentSet.m10/momentSet.m00;
00904     y = momentSet.m01/momentSet.m00;
00905 
00906     return cv::Point2f(x,y);
00907 }
00908 
00909 void createGaussianMatrix(cv::Mat& gaussianMat, double sigmaFactor)
00910 {
00911 
00912     cv::Mat distributionDisplay(cv::Size(640, 480), CV_8UC1);
00913     cv::Mat binTemp(gaussianMat.size(), CV_8UC1);
00914 
00915     // sigmaFactor says how many standard deviations should span from the center to the nearest edge
00916     // (i.e. along the shortest axis)
00917 
00918 
00919     // What about an elliptical gaussian function?
00920 
00921     cv::Point2f center((float)((double(gaussianMat.size().height-1))/2), (float)((double(gaussianMat.size().width-1))/2));
00922     cv::Point2f tmpPt;
00923     double dist = 0.0;//, average = 0.0, maxVal = 0.0;
00924     double sigma = min(gaussianMat.size().width, gaussianMat.size().height)/(2*sigmaFactor);
00925 
00926     //double A = (gaussianMat.size().width*gaussianMat.size().height) / (sigma * pow(2*3.142, 0.5));
00927     double A = 1.0;
00928 
00929 
00930     for (int i = 0; i < gaussianMat.size().width; i++)
00931     {
00932         for (int j = 0; j < gaussianMat.size().height; j++)
00933         {
00934             tmpPt = cv::Point2f(float(j), float(i));
00935             dist = distBetweenPts2f(center, tmpPt);
00936             
00937             gaussianMat.at<double>(j,i) = A*exp(-(pow(dist,2)/(2*pow(sigma,2))));
00938 
00939                         /*
00940             //gaussianMat.at<double>(j,i) = A*exp(-(pow(dist,2)/(2*pow(sigma,2))));
00941             //gaussianMat.at<double>(j,i) = dist;
00942             if (dist < max(double(gaussianMat.size().width)/2, double(gaussianMat.size().height)/2))
00943             {
00944                 gaussianMat.at<double>(j,i) = 1.0;
00945             }
00946             else
00947             {
00948                 gaussianMat.at<double>(j,i) = 0.0;
00949             }
00950 
00951             average += gaussianMat.at<double>(j,i);
00952 
00953             if (gaussianMat.at<double>(j,i) > maxVal)
00954             {
00955                 maxVal = gaussianMat.at<double>(j,i);
00956             }
00957                         */
00958             //printf("val = %f\n", gaussianMat.at<double>(j,i));
00959 
00960             //gaussianMat.at<double>(j,i) = double(rand()) / RAND_MAX;
00961         }
00962     }
00963 
00964     //average /= gaussianMat.size().width*gaussianMat.size().height;
00965 
00966     //gaussianMat /= average;
00967     
00968     /*
00969      * 
00970     average = 0.0;
00971     maxVal = 0.0;
00972 
00973     for (int i = 0; i < gaussianMat.size().width; i++)
00974     {
00975         for (int j = 0; j < gaussianMat.size().height; j++)
00976         {
00977             average += gaussianMat.at<double>(j,i);
00978             if (gaussianMat.at<double>(j,i) > maxVal)
00979             {
00980                 maxVal = gaussianMat.at<double>(j,i);
00981             }
00982         }
00983     }
00984 
00985     average /= gaussianMat.size().width*gaussianMat.size().height;
00986 
00987         */
00988         
00989     //printf("%s << average val = %f\n", __FUNCTION__, average);
00990     //cin.get();
00991 
00992     /*
00993     convertScaleAbs(gaussianMat, binTemp, (255.0/maxVal), 0);
00994     svLib::simpleResize(binTemp, distributionDisplay, Size(480, 640));
00995     //equalizeHist(distributionDisplay, distributionDisplay);
00996     imshow("gaussianMat", distributionDisplay);
00997     waitKey(40);
00998     */
00999 }
01000 
01001 void cropImage(cv::Mat& image, cv::Point tl, cv::Point br)
01002 {
01003     // not compatible with all image types yet...
01004 
01005     int width, height, xOff, yOff;
01006 
01007     //printf("%s << Starting function.\n", __FUNCTION__);
01008 
01009     //printf("%s << TL = (%d, %d); BR = (%d, %d)\n", __FUNCTION__, tl.x, tl.y, br.x, br.y);
01010 
01011     width = abs(br.x-tl.x);
01012     height = abs(br.y-tl.y);
01013 
01014     xOff = min(tl.x, br.x);
01015     yOff = min(tl.y, br.y);
01016 
01017     //printf("%s << width = %d, height = %d, xOff = %d, yOff = %d\n", __FUNCTION__, width, height, xOff, yOff);
01018 
01019     //cin.get();
01020 
01021     cv::Mat tmpMat;
01022 
01023     if (image.channels() == 3)
01024     {
01025         tmpMat = cv::Mat(height, width, CV_8UC3);
01026     }
01027     else if (image.channels() == 1)
01028     {
01029         tmpMat = cv::Mat(height, width, CV_8UC1);
01030     }
01031 
01032 
01033 
01034     for (int i = 0; i < width; i++)
01035     {
01036         for (int j = 0; j < height; j++)
01037         {
01038             //printf("%s << %d / %d\n", __FUNCTION__, i, j);
01039 
01040             if (image.channels() == 3)
01041             {
01042                 if ((j+yOff < 0) || (j+yOff > image.rows-1) || (i+xOff < 0) || (i+xOff > image.cols-1))
01043                 {
01044                     tmpMat.at<cv::Vec3b>(j,i)[0] = 0;
01045                     tmpMat.at<cv::Vec3b>(j,i)[1] = 0;
01046                     tmpMat.at<cv::Vec3b>(j,i)[2] = 0;
01047                 }
01048                 else
01049                 {
01050                     tmpMat.at<cv::Vec3b>(j,i) = image.at<cv::Vec3b>(j+yOff,i+xOff);
01051                 }
01052             }
01053             else if (image.channels() == 1)
01054             {
01055                 if ((j+yOff < 0) || (j+yOff > image.rows-1) || (i+xOff < 0) || (i+xOff > image.cols-1))
01056                 {
01057                     tmpMat.at<unsigned char>(j,i) = 0;
01058                 }
01059                 else
01060                 {
01061                     tmpMat.at<unsigned char>(j,i) = image.at<unsigned char>(j+yOff,i+xOff);
01062                 }
01063 
01064 
01065             }
01066 
01067 
01068 
01069 
01070         }
01071     }
01072 
01073     //tmpMat.copyTo(image);
01074     resize(tmpMat, image, cv::Size(width, height)); // working
01075 
01076     //printf("%s << Completing function.\n", __FUNCTION__);
01077 
01078 }
01079 
01080 void convertVectorToPoint(vector<cv::Point2f>& input, vector<cv::Point>& output)
01081 {
01082     output.clear();
01083 
01084     for (unsigned int i = 0; i < input.size(); i++)
01085     {
01086         output.push_back(cv::Point((int)input.at(i).x, (int)input.at(i).y));
01087     }
01088 }
01089 
01090 void convertVectorToPoint2f(vector<cv::Point>& input, vector<cv::Point2f>& output)
01091 {
01092     // TODO:
01093     // Nothing much.
01094 
01095     output.clear();
01096 
01097     for (unsigned int i = 0; i < input.size(); i++)
01098     {
01099         output.push_back(cv::Point2f((float)input.at(i).x, (float)input.at(i).y));
01100     }
01101 }
01102 
01103 void simpleResize(cv::Mat& src, cv::Mat& dst, cv::Size size)
01104 {
01105 
01106     dst = cv::Mat::zeros(size, src.type());
01107 
01108     for (int i = 0; i < dst.size().width; i++)
01109     {
01110         for (int j = 0; j < dst.size().height; j++)
01111         {
01112             if (src.depth() == 1)
01113             {
01114                 dst.at<unsigned char>(j,i) = src.at<unsigned char>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width);
01115             }
01116             else if (src.depth() == 8)
01117             {
01118                 dst.at<double>(j,i) = src.at<double>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width);
01119             }
01120             else if (src.depth() == CV_16U)
01121             {
01122                 dst.at<unsigned short>(j,i) = src.at<unsigned short>(j*src.size().height/dst.size().height,i*src.size().width/dst.size().width);
01123             }
01124 
01125         }
01126     }
01127 }
01128 
01129 void copyContour(vector<cv::Point>& src, vector<cv::Point>& dst)
01130 {
01131     // TODO:
01132     // Make safer.
01133 
01134     dst.clear();
01135 
01136     for (unsigned int i = 0; i < src.size(); i++)
01137     {
01138         dst.push_back(src.at(i));
01139     }
01140 }
01141 
01142 void swapElements(vector<cv::Point2f>& corners, int index1, int index2)
01143 {
01144     // TODO:
01145     // Nothing much.
01146 
01147     cv::Point2f tempPt;
01148 
01149     tempPt = corners.at(index1);    // copy first element to temp
01150     corners.at(index1) = corners.at(index2);  // put best element in first
01151     corners.at(index2) = tempPt;  // copy temp to where best element was
01152 }
01153 
01154 void invertMatIntensities(const cv::Mat& src, cv::Mat& dst)
01155 {
01156     
01157     if ((dst.size() != src.size()) && (dst.type() != src.type())) {
01158                 dst.release();
01159                 dst = cv::Mat(src.size(), src.type());
01160         }
01161 
01162     if (src.type() == CV_8UC1)
01163     {
01164 
01165 
01166                 #pragma omp parallel for
01167         for (int iii = 0; iii < src.rows; iii++)
01168         {
01169             for (int jjj = 0; jjj < src.cols; jjj++)
01170             {
01171                 dst.at<unsigned char>(iii,jjj) = 255 - src.at<unsigned char>(iii, jjj);
01172             }
01173         }
01174 
01175     }
01176     else if (src.type() == CV_8UC3)
01177     {
01178 
01179         // printf("%s << here.\n", __FUNCTION__);
01180                 #pragma omp parallel for
01181         for (int iii = 0; iii < src.rows; iii++)
01182         {
01183             for (int jjj = 0; jjj < src.cols; jjj++)
01184             {
01185                 //a = src.at<cv::Vec3b>(iii, jjj)[0];
01186                 //z = std::max(std::min(255, int(255 - (1.5*(a - 128)+128))),0);
01187                 //dst.at<cv::Vec3b>(iii, jjj)[0] = z;
01188                 //dst.at<cv::Vec3b>(iii, jjj)[1] = z;
01189                 //dst.at<cv::Vec3b>(iii, jjj)[2] = z;
01190 
01191                 dst.at<cv::Vec3b>(iii, jjj)[0] = 255 - src.at<cv::Vec3b>(iii, jjj)[0];
01192                 dst.at<cv::Vec3b>(iii, jjj)[1] = 255 - src.at<cv::Vec3b>(iii, jjj)[1];
01193                 dst.at<cv::Vec3b>(iii, jjj)[2] = 255 - src.at<cv::Vec3b>(iii, jjj)[2];
01194             }
01195         }
01196     }
01197 
01198     //imshow("dst", dst);
01199     //waitKey();
01200 
01201 }
01202 
01203 void contourDimensions(vector<cv::Point> contour, double& width, double& height)
01204 {
01205     // TODO:
01206     // May want to replace this with something that finds the longest and shortest distances across
01207     // Because the idea of this is to help determine if it's a square or not.
01208 
01209     // new methodology
01210     cv::RotatedRect wrapperRectangle;
01211     cv::Size size;
01212     vector<cv::Point> contourCpy;
01213     cv::Point meanPoint;
01214 
01215     // Interpolate contour to get it to an adequate size for "fitEllipse" function
01216     if (contour.size() < 6)
01217     {
01218         for (unsigned int i = 0; i < contour.size()-1; i++)
01219         {
01220             contourCpy.push_back(contour.at(i));
01221             meanPoint.x = (2*contour.at(i).x + 1*contour.at(i+1).x) / 3;
01222             meanPoint.y = (2*contour.at(i).y + 1*contour.at(i+1).y) / 3;
01223             contourCpy.push_back(meanPoint);
01224             meanPoint.x = (1*contour.at(i).x + 2*contour.at(i+1).x) / 3;
01225             meanPoint.y = (1*contour.at(i).y + 2*contour.at(i+1).y) / 3;
01226             contourCpy.push_back(meanPoint);
01227         }
01228 
01229         contourCpy.push_back(contour.at(contour.size()-1));
01230         meanPoint.x = (2*contour.at(contour.size()-1).x + 1*contour.at(0).x) / 3;
01231         meanPoint.y = (2*contour.at(contour.size()-1).y + 1*contour.at(0).y) / 3;
01232         contourCpy.push_back(meanPoint);
01233         meanPoint.x = (1*contour.at(contour.size()-1).x + 2*contour.at(0).x) / 3;
01234         meanPoint.y = (1*contour.at(contour.size()-1).y + 2*contour.at(0).y) / 3;
01235         contourCpy.push_back(meanPoint);
01236 
01237     }
01238     else
01239     {
01240         contourCpy.assign(contour.begin(), contour.end());
01241     }
01242 
01243     wrapperRectangle = fitEllipse(cv::Mat(contourCpy));
01244     size = wrapperRectangle.size;
01245     width = size.width;
01246     height = size.height;
01247 
01248     // old methodology... (simply using highest and lowest X and Y values..)
01249     /*
01250     double xMax = 0.0, yMax = 0.0, xMin = 99999.0, yMin = 99999.0;
01251 
01252     for (unsigned int i = 0; i < contour.size(); i++) {
01253 
01254         if (contour.at(i).x > xMax) {
01255             xMax = contour.at(i).x;
01256         }
01257 
01258         if (contour.at(i).y > yMax) {
01259             yMax = contour.at(i).y;
01260         }
01261 
01262         if (contour.at(i).x < xMin) {
01263             xMin = contour.at(i).x;
01264         }
01265 
01266         if (contour.at(i).y < yMin) {
01267             yMin = contour.at(i).y;
01268         }
01269 
01270     }
01271 
01272     width = xMax - xMin;
01273     height = yMax - yMin;
01274     */
01275 }
01276 
01277 
01278 
01279 
01280 
01281 
01282 
01283 void transferElement(vector<cv::Point2f>& dst, vector<cv::Point2f>& src, int index)
01284 {
01285     cv::Point2f pointCpy;
01286 
01287     pointCpy = src.at(index);
01288 
01289     // Move from old one to new one
01290     dst.push_back(pointCpy);
01291 
01292     // Replace and shift points in old one
01293     for (unsigned int i = index; i < src.size()-1; i++)
01294     {
01295         src.at(i) = src.at(i+1);
01296     }
01297 
01298     // Truncate the original vector (effectively discarding old point)
01299     src.pop_back();
01300 }
01301 
01302 
01303 bool checkIfActuallyGray(const cv::Mat& im) {
01304 
01305         bool retVal = true;
01306 
01307         for (int iii = 0; iii < im.rows; iii++) {
01308                 for (int jjj = 0; jjj < im.cols; jjj++) {
01309 
01310                         if (im.at<cv::Vec3b>(iii,jjj)[0] != im.at<cv::Vec3b>(iii,jjj)[1]) {
01311                                 //printf("%s << (%d, %d) = (%d, %d, %d)\n", __FUNCTION__, iii, jjj, im.at<cv::Vec3b>(iii,jjj)[0], im.at<cv::Vec3b>(iii,jjj)[1], im.at<cv::Vec3b>(iii,jjj)[2]);
01312                                 return false;
01313                         }
01314 
01315                         if (im.at<cv::Vec3b>(iii,jjj)[2] != im.at<cv::Vec3b>(iii,jjj)[1]) {
01316                                 //printf("%s << (%d, %d) = (%d, %d, %d)\n", __FUNCTION__, iii, jjj, im.at<cv::Vec3b>(iii,jjj)[0], im.at<cv::Vec3b>(iii,jjj)[1], im.at<cv::Vec3b>(iii,jjj)[2]);
01317                                 return false;
01318                         }
01319 
01320                 }
01321         }
01322 
01323         return retVal;
01324 
01325 }
01326 
01327 void thresholdRawImage(cv::Mat& img, double *vals) {
01328         
01329         for (int iii = 0; iii < img.rows; iii++) {
01330                 for (int jjj = 0; jjj < img.cols; jjj++) {
01331                         
01332                         if (double(img.at<unsigned short>(iii,jjj)) < vals[0]) {
01333                                 img.at<unsigned short>(iii,jjj) = (unsigned short) vals[0];
01334                         }
01335                         
01336                         if (double(img.at<unsigned short>(iii,jjj)) > vals[1]) {
01337                                 img.at<unsigned short>(iii,jjj) = (unsigned short) vals[1];
01338                         }
01339                         
01340                 }
01341         }
01342 }
01343 
01344 void findPercentiles(const cv::Mat& img, double *vals, double *percentiles, unsigned int num) {
01345 
01346         //double median = 0.0;
01347 
01348         cv::Mat mx;
01349 
01350         unsigned int *aimedPixelCounts;
01351         aimedPixelCounts = new unsigned int[num];
01352         bool *found;
01353         found = new bool[num];
01354         
01355         //int maxPixels = img.rows * img.cols;
01356 
01357         for (unsigned int iii = 0; iii < num; iii++) {
01358                 found[iii] = false;
01359                 aimedPixelCounts[iii] = (unsigned int) (((double) img.rows) * ((double) img.cols) * ((double) percentiles[iii]));
01360                 
01361                 if (((int)aimedPixelCounts[iii]) == img.rows*img.cols) {
01362                         aimedPixelCounts[iii]--;
01363                 }
01364                 
01365                 //printf("%s << aimedPixelCounts[%d] = %d (%f)\n", __FUNCTION__, iii, aimedPixelCounts[iii], percentiles[iii]);
01366         }
01367 
01368         //cin.get();
01369 
01370         //if (img.type() == CV_16UC1) {
01371                 img.convertTo(mx, CV_32FC1);
01372         //}
01373 
01374         cv::MatND hist;
01375         int channels[] = {0};
01376         int ibins = 65536;
01377         int histSize[] = {ibins};
01378         float iranges[] = { 0, 65535 };
01379         const float* ranges[] = { iranges };
01380 
01381         calcHist(&mx, 1, channels, cv::Mat(), hist, 1, histSize, ranges);
01382 
01383         unsigned int pointsTally = 0;
01384 
01385         //bool allCountsReached = false;
01386 
01387         for (int i = 0; i < ibins; i++) {
01388 
01389                 pointsTally += (unsigned int)(hist.at<float>(i));
01390 
01391                 for (unsigned int iii = 0; iii < num; iii++) {
01392                         
01393                         if (pointsTally <= aimedPixelCounts[iii]) {
01394                                 vals[iii] = double(i);
01395                                 
01396                         } else if (!found[iii]) {
01397                                 found[iii] = true;
01398                                 vals[iii] = double(i);
01399                         }
01400 
01401                 }
01402 
01403                 bool allCountsReached = true;
01404                 
01405                 for (unsigned int iii = 0; iii < num; iii++) {
01406                         if (found[iii] == false) {
01407                                 allCountsReached = false;
01408                                 break;
01409                         }
01410                 }
01411                 
01412                 if (allCountsReached) return;
01413 
01414         }
01415 
01416 }
01417 
01418 void shiftIntensities(cv::Mat& im, double scaler, double shifter, double downer) {
01419 
01420         double val;
01421         for (int iii = 0; iii < im.rows; iii++) {
01422                 for (int jjj = 0; jjj < im.cols; jjj++) {
01423 
01424                         val = ((double) im.at<unsigned char>(iii,jjj));
01425 
01426                         val -= downer;
01427 
01428                         val *= scaler;
01429 
01430                         val += (downer + shifter);
01431 
01432                         im.at<unsigned char>(iii,jjj) = ((unsigned char) val);
01433 
01434                 }
01435         }
01436 
01437 }
01438 
01439 void findIntensityValues(double *vals, cv::Mat& im, cv::Mat& mask) {
01440 
01441         vals[0] = 9e99;
01442         vals[1] = -9e99;
01443         vals[2] = 0.0;
01444 
01445         unsigned int activeCount = countNonZero(mask);
01446 
01447         if (activeCount == 0) {
01448                 return;
01449         }
01450 
01451         unsigned int hist[256];
01452 
01453         for (unsigned int iii = 0; iii < 256; iii++) {
01454                 hist[iii] = 0;
01455         }
01456 
01457         for (int iii = 0; iii < im.rows; iii++) {
01458                 for (int jjj = 0; jjj < im.cols; jjj++) {
01459 
01460                         if (mask.at<unsigned char>(iii,jjj) != 0) {
01461                                 vals[2] += ((double) im.at<unsigned char>(iii,jjj)) / ((double) activeCount);
01462 
01463                                 if (((double) im.at<unsigned char>(iii,jjj)) < vals[0]) {
01464                                         vals[0] = ((double) im.at<unsigned char>(iii,jjj));
01465                                 }
01466 
01467                                 if (((double) im.at<unsigned char>(iii,jjj)) > vals[1]) {
01468                                         vals[1] = ((double) im.at<unsigned char>(iii,jjj));
01469                                 }
01470 
01471                                 hist[im.at<unsigned char>(iii,jjj)]++;
01472 
01473                         }
01474 
01475                 }
01476         }
01477 
01478         unsigned int intensityCount = 0;
01479         int intensityPtr = -1;
01480         unsigned int medianCount = countNonZero(mask);
01481 
01482         while (intensityCount < (medianCount/2)) {
01483                 intensityPtr++;
01484                 intensityCount += hist[intensityPtr];
01485         }
01486 
01487         vals[3] = intensityPtr;
01488 
01489 
01490 }
01491 
01492 void cScheme::setupLookupTable(unsigned int depth) {
01493 
01494         unsigned int maxIndex, level;
01495 
01496         if (depth == 2) {
01497                 maxIndex = 65536;
01498         } else if (depth == 1) {
01499                 maxIndex = 256;
01500         } else {
01501                 maxIndex = 256;
01502         }
01503 
01504         for (unsigned int iii = 0; iii < maxIndex; iii++) {
01505 
01506                 level = (int) floor(double((iii*(MAP_LENGTH-1))/((double) (maxIndex-1)))); // for 16 bits/pixel
01507 
01508                 if (depth == 2) {
01509                         lookupTable_2[iii][2] = (unsigned short) (255.0 * red[level]);
01510                         lookupTable_2[iii][1] = (unsigned short) (255.0 * green[level]);
01511                         lookupTable_2[iii][0] = (unsigned short) (255.0 * blue[level]);
01512 
01513                         //printf("%s << LT(%d) = (%d, %d, %d)\n", __FUNCTION__, iii, lookupTable_2[iii][2], lookupTable_2[iii][1], lookupTable_2[iii][0]);
01514                 } else if (depth == 1) {
01515                         lookupTable_1[iii][2] = (unsigned char) (255.0 * red[level]);
01516                         lookupTable_1[iii][1] = (unsigned char) (255.0 * green[level]);
01517                         lookupTable_1[iii][0] = (unsigned char) (255.0 * blue[level]);
01518                         //printf("%s << LT(%d) = (%d, %d, %d)\n", __FUNCTION__, iii, lookupTable_1[iii][2], lookupTable_1[iii][1], lookupTable_1[iii][0]);
01519                 }
01520 
01521 
01522         }
01523 
01524 }
01525 
01526 void obtainEightBitRepresentation(cv::Mat& src, cv::Mat& dst) {
01527         if (src.type() == CV_8UC1) {
01528                 dst = src;
01529         } else if (src.type() == CV_8UC3) {
01530                 cvtColor(src, dst, CV_RGB2GRAY);
01531         } else if (src.type() == CV_16UC1) {
01532                 cv::Mat nMat;
01533                 double currMin, currMax;
01534                 minMaxLoc(src, &currMin, &currMax);
01535                 normalize_16(nMat, src, currMin, currMax);
01536                 down_level(dst, nMat);
01537         } else if (src.type() == CV_16UC3) {
01538                 cv::Mat nMat, tMat;
01539                 cvtColor(src, tMat, CV_RGB2GRAY);
01540                 double currMin, currMax;
01541                 minMaxLoc(tMat, &currMin, &currMax);
01542                 normalize_16(nMat, tMat, currMin, currMax);
01543                 down_level(dst, nMat);
01544         }
01545 }
01546 
01547 void obtainColorRepresentation(cv::Mat& src, cv::Mat& dst) {
01548         if (src.type() == CV_8UC1) {
01549                 cvtColor(src, dst, CV_GRAY2RGB);
01550         } else if (src.type() == CV_8UC3) {
01551                 dst = src;
01552         } else if (src.type() == CV_16UC1) {
01553                 cv::Mat nMat, tMat;
01554                 double currMin, currMax;
01555                 minMaxLoc(src, &currMin, &currMax);
01556                 normalize_16(nMat, src, currMin, currMax);
01557                 down_level(tMat, nMat);
01558                 cvtColor(tMat, dst, CV_GRAY2RGB);
01559         } else if (src.type() == CV_16UC3) {
01560                 cv::Mat nMat, tMat, tMat2;
01561                 double currMin, currMax;
01562                 cvtColor(src, tMat, CV_RGB2GRAY);
01563                 minMaxLoc(tMat, &currMin, &currMax);
01564                 normalize_16(nMat, tMat, currMin, currMax);
01565                 down_level(tMat2, nMat);
01566                 cvtColor(tMat2, dst, CV_GRAY2RGB);
01567         }
01568 }
01569 
01570 void fix_bottom_right(cv::Mat& mat) {
01571 
01572         if (mat.type() == CV_16UC3) {
01573                 for (int iii = (mat.cols-6); iii < mat.cols; iii++) {
01574                         mat.at<cv::Vec3s>(mat.rows-1, iii)[0] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3s>(mat.rows-2, iii)[0] + mat.at<cv::Vec3s>(mat.rows-1, iii-1)[0]) / 2) ), (unsigned int) 65535) , (unsigned int) 0);
01575                         mat.at<cv::Vec3s>(mat.rows-1, iii)[1] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3s>(mat.rows-2, iii)[1] + mat.at<cv::Vec3s>(mat.rows-1, iii-1)[1]) / 2) ), (unsigned int) 65535) , (unsigned int) 0);
01576                         mat.at<cv::Vec3s>(mat.rows-1, iii)[2] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3s>(mat.rows-2, iii)[2] + mat.at<cv::Vec3s>(mat.rows-1, iii-1)[2]) / 2) ), (unsigned int) 65535) , (unsigned int) 0);
01577                 }
01578         } else if (mat.type() == CV_8UC3) {
01579                 for (int iii = (mat.cols-6); iii < mat.cols; iii++) {
01580                         mat.at<cv::Vec3b>(mat.rows-1, iii)[0] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3b>(mat.rows-2, iii)[0] + mat.at<cv::Vec3b>(mat.rows-1, iii-1)[0]) / 2) ), (unsigned int) 255) , (unsigned int) 0);
01581                         mat.at<cv::Vec3b>(mat.rows-1, iii)[1] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3b>(mat.rows-2, iii)[1] + mat.at<cv::Vec3b>(mat.rows-1, iii-1)[1]) / 2) ), (unsigned int) 255) , (unsigned int) 0);
01582                         mat.at<cv::Vec3b>(mat.rows-1, iii)[2] = std::max( std::min(( (unsigned int) ((mat.at<cv::Vec3b>(mat.rows-2, iii)[2] + mat.at<cv::Vec3b>(mat.rows-1, iii-1)[2]) / 2) ), (unsigned int) 255) , (unsigned int) 0);
01583                 }
01584         } else if (mat.type() == CV_16UC1) { 
01585                 for (int iii = (mat.cols-6); iii < mat.cols; iii++) {
01586                         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) ), (unsigned int) 65535) , (unsigned int) 0);
01587                 }
01588         } else if (mat.type() == CV_8UC1) {
01589                 for (int iii = (mat.cols-6); iii < mat.cols; iii++) {
01590                         mat.at<unsigned char>(mat.rows-1, iii) = std::max( std::min(( (unsigned int) ((mat.at<unsigned char>(mat.rows-2, iii) + mat.at<unsigned char>(mat.rows-1, iii-1)) / 2) ), (unsigned int) 255) , (unsigned int) 0);
01591                 }
01592         }
01593         
01594         
01595 }
01596 
01597 void down_level(cv::Mat& dst, cv::Mat& src) {
01598 
01599     // Currently only works for a single channel image i.e. CV_16UC1
01600         dst = cv::Mat(src.rows, src.cols, CV_8UC1);
01601 
01602     //unsigned int val;
01603     for (int i = 0; i < dst.size().height; i++) {
01604         for (int j = 0; j < dst.size().width; j++) {
01605            dst.at<unsigned char>(i,j) = (src.at<unsigned short>(i,j)) / 256;
01606         }
01607 
01608     }
01609 }
01610 
01611 void reduceToPureImage(cv::Mat& dst, cv::Mat& src) {
01612 
01613 
01614         if (dst.cols == 0) {
01615                 if (src.type() == CV_16UC3) {
01616                         dst = cv::Mat(src.size(), CV_16UC1);
01617                 } else if (src.type() == CV_8UC3) {
01618                         dst = cv::Mat(src.size(), CV_8UC1);
01619                 }
01620 
01621         }
01622 
01623                 for (int iii = 0; iii < src.cols; iii++) {
01624                         for (int jjj = 0; jjj < src.rows; jjj++) {
01625                                 if (src.type() == CV_16UC3) {
01626                                         if (((src.at<cv::Vec3s>(jjj,iii)[0]) == (src.at<cv::Vec3s>(jjj,iii)[1])) && ((src.at<cv::Vec3s>(jjj,iii)[2]) == (src.at<cv::Vec3s>(jjj,iii)[1]))) {
01627                                                 dst.at<unsigned short>(jjj,iii) = src.at<cv::Vec3s>(jjj,iii)[0];
01628                                         } else {
01629                                                 dst.at<unsigned short>(jjj,iii) = (unsigned short) (0.299 * (double) src.at<cv::Vec3s>(jjj,iii)[0] + 0.587 * (double) src.at<cv::Vec3s>(jjj,iii)[1] + 0.114 * (double) src.at<cv::Vec3s>(jjj,iii)[2]);
01630                                         }
01631 
01632                                 } else if (src.type() == CV_8UC3) {
01633                                         if (((src.at<cv::Vec3b>(jjj,iii)[0]) == (src.at<cv::Vec3b>(jjj,iii)[1])) && ((src.at<cv::Vec3b>(jjj,iii)[2]) == (src.at<cv::Vec3b>(jjj,iii)[1]))) {
01634                                                 dst.at<unsigned char>(jjj,iii) = src.at<cv::Vec3b>(jjj,iii)[0];
01635                                         } else {
01636                                                 dst.at<unsigned char>(jjj,iii) = (unsigned char) (0.299 * (double) src.at<cv::Vec3b>(jjj,iii)[0] + 0.587 * (double) src.at<cv::Vec3b>(jjj,iii)[1] + 0.114 * (double) src.at<cv::Vec3b>(jjj,iii)[2]);
01637                                         }
01638 
01639                                 }
01640 
01641                         }
01642                 }
01643 }
01644 
01645 void addBorder(cv::Mat& inputMat, int borderSize) {
01646     cv::Mat newMat = cv::Mat::zeros(inputMat.rows + 2*borderSize, inputMat.cols + 2*borderSize, CV_8UC3);
01647 
01648     for (int i = borderSize; i < newMat.rows-borderSize; i++) {
01649         for (int j = borderSize; j < newMat.cols-borderSize; j++) {
01650             newMat.at<cv::Vec3b>(i,j) = inputMat.at<cv::Vec3b>(i-borderSize, j-borderSize);
01651         }
01652     }
01653 
01654     newMat.copyTo(inputMat);
01655 
01656 }
01657 
01658 void normalize_64_vec(cv::Mat& dst, cv::Mat& src) {
01659 
01660     //printf("%s << Entered...\n", __FUNCTION__);
01661 
01662     dst = cv::Mat(src.size(), src.type());
01663 
01664     double minVal = 9e50, maxVal = -9e50;
01665 
01666     for (int i = 0; i < src.rows; i++) {
01667         for (int j = 0; j < src.cols; j++) {
01668             for (int k = 0; k < src.channels(); k++) {
01669                 if (src.at<cv::Vec3d>(i,j)[k] > maxVal) {
01670                     maxVal = src.at<cv::Vec3d>(i,j)[k];
01671                 }
01672 
01673                 if (src.at<cv::Vec3d>(i,j)[k] < minVal) {
01674                     minVal = src.at<cv::Vec3d>(i,j)[k];
01675                 }
01676             }
01677 
01678 
01679         }
01680     }
01681 
01682     for (int i = 0; i < src.rows; i++) {
01683         for (int j = 0; j < src.cols; j++) {
01684             for (int k = 0; k < src.channels(); k++) {
01685                 dst.at<cv::Vec3d>(i,j)[k] = max(min(((src.at<cv::Vec3d>(i,j)[k] - minVal) / (maxVal - minVal)), 1.0),0.0);
01686             }
01687 
01688 
01689         }
01690     }
01691 }
01692 
01693 void normalize_16(cv::Mat& dst, const cv::Mat& src, double dblmin, double dblmax) {
01694 
01695     unsigned short minv, maxv;
01696     bool presetLimits;
01697 
01698     double lower_bound = 0.0, upper_bound = 65535.0;
01699 
01700     if ((dblmin > -1.0) && (dblmax > -1.0)) {
01701         presetLimits = true;
01702         //cout << "preset == true" << endl;
01703     } else {
01704                 presetLimits = false;
01705         }
01706 
01707     minv = 65535;
01708         maxv = 0;
01709 
01710     //printf("%s << min = %d; max = %d\n", __FUNCTION__, min, max);
01711 
01712     unsigned short val; //, new_val;
01713     //double limitTester;
01714 
01715     cv::Size matSize = src.size();
01716     src.copyTo(dst);
01717 
01718     // Safety checks
01719         if ((src.size().height != dst.size().height) || (src.size().width != dst.size().width)) {
01720                 printf("svLib::normalize_16() << Image dimensions don't match.\n");
01721                 return;
01722         }
01723 
01724 
01725 
01726     if (1) { // (!presetLimits) {
01727 
01728         for (int i = 0; i < matSize.height; i++) {
01729             for (int j = 0; j < matSize.width; j++) {
01730                 val = src.at<unsigned short>(i,j);             // how do I incorporate channels?
01731 
01732                 if (val < minv) {
01733                     minv = val;
01734                 }
01735 
01736                 if (val > maxv) {
01737                     maxv = val;
01738                 }
01739             }
01740         }
01741 
01742         } else {
01743                 minv = (unsigned short) dblmin;
01744                 maxv = (unsigned short) dblmax;
01745                 
01746         }
01747         
01748         if (!presetLimits) {
01749                 dblmin = double(minv);
01750                 dblmax = double(maxv);
01751         }
01752         
01753         // dblmin, dblmax are the limits you want to use for normalization
01754         // minv, maxv are the actual limits of the image
01755         
01756         //cout << "minv = " << minv << ", maxv = " << maxv << endl;
01757 
01758         //unsigned short abs_min = std::max(minv, (unsigned short) dblmin);
01759         //unsigned short abs_max = std::min(maxv, (unsigned short) dblmax);
01760 
01761         #pragma omp parallel for
01762         for (int i = 0; i < matSize.height; i++) {
01763         for (int j = 0; j < matSize.width; j++) {
01764             dst.at<unsigned short>(i,j) = std::max((unsigned short) dblmin, std::min((unsigned short) dblmax, src.at<unsigned short>(i,j)));
01765                 }
01766         }
01767 
01768         // Compare actual min with the desired min in order to determine lower bound...
01769 
01770         //double total_range = abs(std::min(dblmin, double(minv)) - std::max(dblmax, double(maxv)));
01771         
01772         double total_range = dblmax - dblmin;
01773 
01774         //printf("%s << (minv / dblmin) = (%f, %f); (maxv / dblmax) = (%f, %f)\n", __FUNCTION__, double(minv), dblmin, double(maxv), dblmax);
01775 
01776         //cout << "total_range = " << total_range << endl;
01777 
01778         if (double(minv) > dblmin) {
01779                 lower_bound = 65535.0 * (abs(double(minv) - dblmin) / total_range);
01780         }
01781 
01782         if (double(maxv) < dblmax) {
01783                 upper_bound = 65535.0 - 65535.0 * (abs(double(maxv) - dblmax) / total_range);
01784         }
01785 
01786         //printf("%s << lower_bound = (%f); upper_bound = (%f)\n", __FUNCTION__, lower_bound, upper_bound);
01787 
01788 
01789         normalize(dst, dst, lower_bound, upper_bound, cv::NORM_MINMAX);
01790 
01791         return;
01792 
01793         /*
01794     //printf("PURPLE MONKEY!\n");
01795 
01796     //printf("%s << Debug %d.\n", __FUNCTION__, -1);
01797 
01798     // Perform image processing
01799     for (int i = 0; i < matSize.height; i++) {
01800         for (int j = 0; j < matSize.width; j++) {
01801             for (int k = 0; k < src.channels(); k++) {
01802                 val = src.at<unsigned short>(i,j);             // how do I incorporate channels?
01803 
01804                 if (val < min) {
01805                     val = min;
01806                 } else if (val > max) {
01807                     val = max;
01808                 }
01809                 // attempt at normalization
01810 
01811                 limitTester = std::max(double(val - min), 0.0);
01812                 limitTester *= 65535.0/(max-min);
01813 
01814                 if (limitTester < 0) {
01815                     //printf("%s << limitTester too low: %f\n", __FUNCTION__, limitTester);
01816                     //cin.get();
01817                         limitTester = 0;
01818                 } else if (limitTester > 65535) {
01819                     //printf("%s << limitTester too high: %f\n", __FUNCTION__, limitTester);
01820                     //cin.get();
01821                         limitTester = 65535;
01822                 }
01823 
01824                 new_val = (unsigned short) limitTester;
01825 
01826                 //new_val = (unsigned short) (65535*((double(val - min))/(double(max - min))));   // 255 for VXL..
01827 
01828                 //printf("%s << val = %d; new_val = %d\n", __FUNCTION__, val, new_val);
01829 
01830                 if (new_val == 0) {
01831                     if (1) {
01832                         //printf("%s << val = %d; new_val = %d\n", __FUNCTION__, val, new_val);
01833                         //cin.get();
01834                     }
01835                 }
01836 
01837                 dst.at<unsigned short>(i,j) = new_val;
01838             }
01839         }
01840     }
01841 
01842     //printf("%s << min = %d; max = %d\n", __FUNCTION__, min, max);
01843     //cin.get();
01844         */
01845 }
01846 
01847 cScheme::cScheme() {
01848         load_standard(100);
01849 }
01850 
01851 cScheme::cScheme(double *d, double *r, double *g, double *b, int len) {
01852         code = CUSTOM;
01853         dx = d;
01854         rx = r;
01855         gx = g;
01856         bx = b;
01857         length = len;
01858 }
01859 
01860 cScheme::~cScheme() { }
01861 
01862 void cScheme::create_long_map() {
01863 
01864         int element;
01865 
01866         double segs, fact;
01867 
01868         segs = (double) (length-1);
01869         //M = (double) MAP_LENGTH;
01870 
01871         // Fill in initial elements
01872         red[0] = rx[0];
01873         green[0] = gx[0];
01874         blue[0] = bx[0];
01875         
01876         int start_el = 0, finish_el;
01877         
01878         //cout << "Starting interpolation..." << endl;
01879 
01880         // Interpolate
01881         for (int iii = 0; iii < segs; iii++) {
01882         
01883                 //cout << "start_el = " << start_el << endl;
01884                 
01885                 //cout << "dx[iii] = " << dx[iii] << endl;
01886                 //cout << "dx[iii+1] = " << dx[iii+1] << endl;
01887                 //cout << "MAP_LENGTH = " << MAP_LENGTH << endl;
01888                 
01889                 finish_el = int(dx[iii+1] * double(MAP_LENGTH-1));
01890                 
01891                 //cout << "finish_el = " << finish_el << endl;
01892                 
01893                 for (int jjj = start_el; jjj < finish_el; jjj++) {
01894                         
01895                         element = iii;
01896                         
01897                         //e = (double) element;
01898                         //iy = (double) jjj;
01899                         fact = (double(jjj) - double(start_el)) / (double(finish_el) - double(start_el));
01900                         
01901                         //cout << "jjj = " << jjj << endl;
01902                         //cout << "fact = " << fact << endl;
01903                         
01904                         
01905                         //cout << "start_el = " << start_el << endl;
01906                         
01907                         //cout << "rx[element] = " << rx[element] << endl;
01908                         //cout << "gx[element] = " << gx[element] << endl;
01909                         //cout << "bx[element] = " << bx[element] << endl;
01910 
01911                         red[jjj] = rx[element] + fact*(rx[element+1] - rx[element]);
01912                         green[jjj] = gx[element] + fact*(gx[element+1] - gx[element]);
01913                         blue[jjj] = bx[element] + fact*(bx[element+1] - bx[element]);
01914                         
01915                         //cout << "red[jjj] = " << red[jjj] << endl;
01916                         //cout << "green[jjj] = " << green[jjj] << endl;
01917                         //cout << "blue[jjj] = " << blue[jjj] << endl;
01918                         
01919                 }
01920                 
01921                 start_el = finish_el;
01922         }
01923         
01924         //cout << "Finishing interpolation..." << endl;
01925         
01926 
01927         // Fill in final elements
01928         red[MAP_LENGTH-1] = rx[length-1];
01929         green[MAP_LENGTH-1] = gx[length-1];
01930         blue[MAP_LENGTH-1] = bx[length-1];
01931 
01932 }
01933 
01934 // Should be:
01935 // Every ten units from 100 - 990 corresponds to a new colour scheme
01936 // 100*N + 2*v + a: v corresponds to a different 'variation'; a can equal 1 or 0 - if 1, can include black
01937 // and/or white (a = 0 is basically a safe version [if needed] for image fusion)
01938 
01939 void cScheme::load_standard(int mapCode, int mapParam) {
01940 
01941         code = mapCode + mapParam;
01942         
01943         double *dd;
01944         double da[256];
01945         
01946         bool flexibleMarkers = false;
01947 
01948         if (code == GRAYSCALE) {
01949                 length = 2;
01950                 double rr [] = { 0, 1 };
01951                 double gg [] = { 0, 1 };
01952                 double bb [] = { 0, 1 };
01953                 rx = rr;
01954                 gx = gg;
01955                 bx = bb;
01956         } else if (code == (GRAYSCALE + 1)) {
01957                 length = 2;
01958                 double rr [] = { 0.2, 0.8 };
01959                 double gg [] = { 0.2, 0.8 };
01960                 double bb [] = { 0.2, 0.8 };
01961                 rx = rr;
01962                 gx = gg;
01963                 
01964                 bx = bb;
01965         } else if (code == HIGHLIGHTED) {
01966                 length = 4;
01967                 flexibleMarkers = true;
01968                 double da [] = { 0.0, 0.5, 0.5, 1.0 };
01969                 double rr [] = { 0, 1.0, 1.0, 1.0 };
01970                 double gg [] = { 0, 1.0, 0.0, 0.0 };
01971                 double bb [] = { 0, 1.0, 0.0, 0.0 };
01972                 dd = da;
01973                 rx = rr;
01974                 gx = gg;
01975                 bx = bb;
01976         } else if (code == (HIGHLIGHTED + 1)) {
01977                 length = 4;
01978                 flexibleMarkers = true;
01979                 double da [] = { 0.25, 0.5, 0.5, 1.0 };
01980                 double rr [] = { 0.25, 0.75, 1.0, 1.0 };
01981                 double gg [] = { 0.25, 0.75, 0.0, 0.0 };
01982                 double bb [] = { 0.25, 0.75, 0.0, 0.0 };
01983                 dd = da;
01984                 rx = rr;
01985                 gx = gg;
01986                 bx = bb;
01987         } else if (code == CIECOMP) {
01988                 length = 33;
01989                 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 };
01990                 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 };
01991                 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 };
01992                 rx = rr;
01993                 gx = gg;
01994                 bx = bb;
01995         } else if (code == (CIECOMP + 1)) {
01996                 length = 27;
01997                 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 };
01998                 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 };
01999                 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 };
02000                 rx = rr;
02001                 gx = gg;
02002                 bx = bb;
02003         } else if (code == CIELUV) {
02004                 
02005                 length = 256;
02006                 double rr [] = { 0.842177, 0.794977, 0.750163, 0.707767, 0.667803, 0.630272, 0.595162, 0.562454, 0.532123, 0.504139, 0.478468, 0.455072, 0.433912, 0.414943, 0.398116, 0.383375, 0.370656, 0.359886, 0.350982, 0.343846, 0.338373, 0.334443, 0.331931, 0.330701, 0.330613, 0.331523, 0.333288, 0.335765, 0.338815, 0.342302, 0.346096, 0.350074, 0.354119, 0.358123, 0.361987, 0.365620, 0.368941, 0.371881, 0.374382, 0.376396, 0.377888, 0.378834, 0.379224, 0.379055, 0.378337, 0.377089, 0.375339, 0.373119, 0.370469, 0.367432, 0.364056, 0.360387, 0.356475, 0.352367, 0.348177, 0.344033, 0.339930, 0.335863, 0.331828, 0.327822, 0.323845, 0.319895, 0.315974, 0.312085, 0.308239, 0.304624, 0.301316, 0.298312, 0.295589, 0.292946, 0.290334, 0.287754, 0.285221, 0.282813, 0.280575, 0.278556, 0.276814, 0.275416, 0.274438, 0.273965, 0.274086, 0.274893, 0.276466, 0.278358, 0.276193, 0.269380, 0.262945, 0.256883, 0.251183, 0.245828, 0.240792, 0.236049, 0.231567, 0.227315, 0.223260, 0.219371, 0.215616, 0.211965, 0.208390, 0.204865, 0.201365, 0.197869, 0.194355, 0.190492, 0.185659, 0.179914, 0.173325, 0.166000, 0.158005, 0.149365, 0.140095, 0.130191, 0.120303, 0.112076, 0.105348, 0.099834, 0.095248, 0.091329, 0.088284, 0.085891, 0.081563, 0.074709, 0.065822, 0.055525, 0.043346, 0.029178, 0.014689, 0.000000, 0.000251, 0.018106, 0.036585, 0.053895, 0.068328, 0.081397, 0.093947, 0.106180, 0.118242, 0.131384, 0.146221, 0.162413, 0.179542, 0.197562, 0.215541, 0.232589, 0.248725, 0.263953, 0.278274, 0.291681, 0.304591, 0.317481, 0.330359, 0.343226, 0.356086, 0.368940, 0.381791, 0.394642, 0.407495, 0.420352, 0.433217, 0.446090, 0.458975, 0.471875, 0.485069, 0.498636, 0.512175, 0.525691, 0.539190, 0.552677, 0.566156, 0.579633, 0.593113, 0.606599, 0.620097, 0.633612, 0.647158, 0.660734, 0.674337, 0.687965, 0.701617, 0.715291, 0.728989, 0.742711, 0.756461, 0.770242, 0.784060, 0.797928, 0.811853, 0.825837, 0.839878, 0.853975, 0.868129, 0.882345, 0.896639, 0.911064, 0.925714, 0.940606, 0.952238, 0.960612, 0.968771, 0.976875, 0.984960, 0.993082, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 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.995905, 0.987520, 0.978928, 0.970117, 0.961069, 0.951756, 0.942144, 0.932186, 0.921823, 0.910991, 0.899620 };
02007                 double gg [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.997193, 0.987772, 0.977945, 0.967751, 0.957223, 0.946391, 0.935282, 0.923916, 0.912314, 0.900494, 0.888469, 0.876254, 0.863862, 0.851304, 0.838592, 0.825738, 0.812754, 0.799653, 0.786450, 0.773159, 0.759799, 0.746387, 0.732946, 0.719498, 0.706067, 0.692679, 0.679361, 0.666139, 0.653042, 0.640094, 0.627321, 0.614744, 0.602383, 0.590254, 0.578368, 0.566732, 0.555350, 0.544221, 0.533338, 0.522692, 0.512272, 0.502062, 0.492045, 0.482203, 0.472517, 0.462933, 0.453383, 0.443871, 0.434400, 0.424976, 0.415601, 0.406280, 0.397015, 0.387812, 0.378673, 0.369599, 0.360503, 0.351344, 0.342116, 0.332815, 0.323467, 0.314071, 0.304619, 0.295099, 0.285488, 0.275762, 0.265891, 0.255836, 0.245550, 0.234967, 0.224007, 0.212563, 0.200497, 0.187641, 0.174266, 0.164865, 0.160603, 0.156434, 0.152357, 0.148375, 0.144486, 0.140688, 0.136979, 0.133355, 0.129811, 0.126341, 0.122938, 0.119595, 0.116304, 0.113057, 0.109845, 0.106661, 0.103495, 0.100341, 0.097456, 0.095335, 0.093882, 0.092971, 0.092454, 0.092203, 0.092108, 0.092078, 0.092034, 0.091657, 0.090349, 0.088259, 0.085536, 0.082298, 0.078629, 0.074017, 0.068165, 0.061625, 0.054555, 0.046727, 0.037788, 0.028338, 0.018891, 0.009446, 0.000000, 0.000160, 0.008872, 0.017691, 0.026453, 0.035166, 0.043509, 0.050663, 0.056788, 0.062048, 0.065920, 0.068030, 0.068653, 0.068291, 0.066748, 0.064598, 0.062725, 0.061358, 0.060744, 0.061117, 0.062683, 0.064964, 0.067306, 0.069710, 0.072180, 0.074716, 0.077319, 0.079991, 0.082730, 0.085535, 0.088406, 0.091340, 0.094335, 0.097389, 0.100497, 0.105193, 0.111848, 0.118233, 0.124379, 0.130311, 0.136052, 0.141624, 0.147045, 0.152335, 0.157511, 0.162589, 0.167591, 0.172561, 0.177501, 0.182411, 0.187293, 0.192148, 0.196982, 0.201804, 0.206624, 0.211456, 0.216317, 0.221229, 0.226253, 0.231410, 0.236711, 0.242158, 0.247746, 0.253489, 0.259410, 0.265607, 0.272360, 0.280060, 0.288737, 0.297592, 0.306705, 0.315913, 0.324994, 0.333996, 0.343098, 0.352261, 0.361527, 0.370938, 0.380468, 0.389927, 0.399285, 0.408544, 0.417698, 0.426737, 0.435925, 0.445700, 0.456026, 0.466869, 0.478203, 0.490003, 0.502247, 0.514911, 0.527972, 0.541405, 0.555182, 0.569274, 0.583734, 0.599017, 0.614443, 0.629991, 0.645638, 0.661362, 0.677139, 0.692949, 0.708770, 0.724580, 0.740345, 0.756043, 0.771656, 0.787163, 0.802548, 0.817793, 0.832881, 0.847796, 0.862520, 0.877037, 0.891329, 0.905377, 0.919160, 0.932656, 0.945842, 0.958689, 0.971169, 0.983249, 0.994896, 1.000000, 1.000000, 1.000000, 1.000000 };
02008                 double bb [] = { 0.843510, 0.862611, 0.880857, 0.898336, 0.915130, 0.931314, 0.946956, 0.962114, 0.976843, 0.991186, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 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.990786, 0.979782, 0.968809, 0.957866, 0.946955, 0.936080, 0.925245, 0.914461, 0.903738, 0.893093, 0.882543, 0.872100, 0.861432, 0.847487, 0.829818, 0.811864, 0.793625, 0.775109, 0.756325, 0.737289, 0.718016, 0.698526, 0.678841, 0.658982, 0.638974, 0.618840, 0.598604, 0.578291, 0.557925, 0.537530, 0.517130, 0.496748, 0.476263, 0.455416, 0.434246, 0.412803, 0.391125, 0.369266, 0.347289, 0.325252, 0.303210, 0.281218, 0.259336, 0.237606, 0.216067, 0.194752, 0.173693, 0.153010, 0.133050, 0.115371, 0.100014, 0.086122, 0.072022, 0.056948, 0.038945, 0.019175, 0.000000, 0.000000, 0.014793, 0.029022, 0.042462, 0.053753, 0.062949, 0.070501, 0.076757, 0.081933, 0.086202, 0.089686, 0.092423, 0.094438, 0.095797, 0.096470, 0.096419, 0.095634, 0.094106, 0.091820, 0.088757, 0.085165, 0.081301, 0.077127, 0.072619, 0.067746, 0.062465, 0.056720, 0.050433, 0.043491, 0.035809, 0.027973, 0.020130, 0.012305, 0.004521, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.001181, 0.010993, 0.020202, 0.028872, 0.037072, 0.044670, 0.051287, 0.057190, 0.062583, 0.068320, 0.077287, 0.089581, 0.104867, 0.122799, 0.143094, 0.165557, 0.190073, 0.216592, 0.245115, 0.275679, 0.308349, 0.343211, 0.380366, 0.419924, 0.462001, 0.506715, 0.554177, 0.604492, 0.657741, 0.713974, 0.773186, 0.835275, 0.899958 };
02009                 rx = rr;
02010                 gx = gg;
02011                 bx = bb;
02012 
02013                 /*
02014                 length = 13;
02015                 double rr [] = { 1.000000, 0.000000, 0.000000, 0.000000, 0.350000, 0.630000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000 };
02016                 double gg [] = { 1.000000, 1.000000, 0.510000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.390000, 0.630000, 1.000000, 1.000000 };
02017                 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.670000, 0.000000, 0.000000, 0.000000, 0.000000, 1.000000 };
02018                 rx = rr;
02019                 gx = gg;
02020                 bx = bb;
02021                 */
02022         } else if (code == (CIELUV + 1)) {
02023                 
02024                 length = 256;
02025                 double rr [] = { 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.054719, 0.099579, 0.132524, 0.160076, 0.184437, 0.206645, 0.227268, 0.246651, 0.265009, 0.282477, 0.299142, 0.315054, 0.330238, 0.344699, 0.358430, 0.371414, 0.383626, 0.395038, 0.405620, 0.415342, 0.424175, 0.432096, 0.439085, 0.445130, 0.450225, 0.454373, 0.457583, 0.459874, 0.461272, 0.461810, 0.461525, 0.460461, 0.458665, 0.456187, 0.453077, 0.449386, 0.445162, 0.440454, 0.435306, 0.429820, 0.424110, 0.418167, 0.411980, 0.405537, 0.398828, 0.391839, 0.384558, 0.376969, 0.369056, 0.360811, 0.352436, 0.344007, 0.335514, 0.326940, 0.318272, 0.309490, 0.300575, 0.291539, 0.282529, 0.273618, 0.264889, 0.256442, 0.248393, 0.240877, 0.234041, 0.228044, 0.223040, 0.219163, 0.219144, 0.220152, 0.218614, 0.218585, 0.220007, 0.222757, 0.226671, 0.231552, 0.237187, 0.243365, 0.249884, 0.256560, 0.263229, 0.269748, 0.275999, 0.281881, 0.287316, 0.292238, 0.296600, 0.300365, 0.303508, 0.306014, 0.307876, 0.309091, 0.309665, 0.309606, 0.308927, 0.307644, 0.305773, 0.303334, 0.300347, 0.296833, 0.292814, 0.288311, 0.283352, 0.278286, 0.273324, 0.268495, 0.263833, 0.259371, 0.255145, 0.251190, 0.247543, 0.244237, 0.241305, 0.241363, 0.245876, 0.251343, 0.257741, 0.265034, 0.273171, 0.282099, 0.291756, 0.302079, 0.313007, 0.324481, 0.336297, 0.348161, 0.360057, 0.371973, 0.383899, 0.395826, 0.407749, 0.419660, 0.431554, 0.443427, 0.455276, 0.467099, 0.478894, 0.490660, 0.502398, 0.514107, 0.525789, 0.537446, 0.549080, 0.560693, 0.572289, 0.583869, 0.595439, 0.607000, 0.618557, 0.630113, 0.641671, 0.653236, 0.664810, 0.676396, 0.687998, 0.699618, 0.711258, 0.722921, 0.734609, 0.746329, 0.758080, 0.769860, 0.781665, 0.793496, 0.805349, 0.817225, 0.829122, 0.841041, 0.852983, 0.864950, 0.876944, 0.888968, 0.901021, 0.913100, 0.925203, 0.937325, 0.949466, 0.961619, 0.973774, 0.985928, 0.998102, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 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.991921, 0.982232, 0.972473, 0.962648, 0.952767, 0.942903, 0.933098 };
02026                 double gg [] = { 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.988214, 0.972972, 0.957391, 0.943527, 0.929950, 0.916226, 0.902349, 0.888316, 0.874124, 0.859773, 0.845260, 0.830589, 0.815761, 0.800784, 0.785664, 0.770412, 0.755043, 0.739572, 0.724020, 0.708409, 0.692766, 0.677118, 0.661496, 0.645934, 0.630463, 0.615118, 0.599932, 0.584935, 0.570155, 0.555619, 0.541346, 0.527353, 0.513651, 0.500245, 0.487135, 0.474318, 0.461783, 0.449519, 0.437507, 0.425730, 0.414166, 0.402794, 0.391546, 0.380338, 0.369176, 0.358063, 0.347005, 0.336007, 0.325073, 0.314209, 0.303421, 0.292714, 0.282090, 0.271423, 0.260650, 0.249758, 0.238731, 0.227549, 0.216190, 0.204627, 0.192817, 0.180682, 0.168141, 0.155084, 0.141361, 0.126758, 0.110953, 0.093423, 0.073213, 0.048211, 0.016697, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.001846, 0.043999, 0.079778, 0.110058, 0.135213, 0.157403, 0.177619, 0.196537, 0.214580, 0.231988, 0.248938, 0.265564, 0.281971, 0.298244, 0.314450, 0.330646, 0.346876, 0.363178, 0.379581, 0.396107, 0.412772, 0.429587, 0.446557, 0.463681, 0.480955, 0.498372, 0.515920, 0.533583, 0.551346, 0.569189, 0.587092, 0.605034, 0.622993, 0.640948, 0.658878, 0.676762, 0.694581, 0.712318, 0.729956, 0.747481, 0.764878, 0.782138, 0.799251, 0.816208, 0.833003, 0.849631, 0.866090, 0.882499, 0.899587, 0.916476, 0.933164, 0.949649, 0.965932, 0.982013, 0.997891, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000 };
02027                 double bb [] = { 0.945402, 0.957936, 0.970650, 0.983509, 0.996407, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 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.991458, 0.974268, 0.956565, 0.938351, 0.919639, 0.900449, 0.880809, 0.860756, 0.840330, 0.819579, 0.798553, 0.777306, 0.755894, 0.734375, 0.712805, 0.691241, 0.669738, 0.648349, 0.627124, 0.606111, 0.585354, 0.564893, 0.544766, 0.525006, 0.505643, 0.486701, 0.468204, 0.450169, 0.432612, 0.415545, 0.398976, 0.382913, 0.367360, 0.352446, 0.338263, 0.324839, 0.312197, 0.300362, 0.289354, 0.279190, 0.269884, 0.261446, 0.253880, 0.253758, 0.259407, 0.264843, 0.270034, 0.274960, 0.279608, 0.283974, 0.288060, 0.291875, 0.295431, 0.298748, 0.301747, 0.304273, 0.306336, 0.307953, 0.309141, 0.309918, 0.310301, 0.310309, 0.309960, 0.309275, 0.308272, 0.306974, 0.305400, 0.303572, 0.301513, 0.299245, 0.296790, 0.294170, 0.291408, 0.288526, 0.285543, 0.282481, 0.279357, 0.276188, 0.272989, 0.269771, 0.266544, 0.263314, 0.260084, 0.256851, 0.253613, 0.250360, 0.247080, 0.243757, 0.240359, 0.236799, 0.233074, 0.229189, 0.225147, 0.220944, 0.216568, 0.211998, 0.207200, 0.202128, 0.196719, 0.190889, 0.184426, 0.177218, 0.169168, 0.160198, 0.150252, 0.139185, 0.126802, 0.112619, 0.095469, 0.073767, 0.040440, 0.000000, 0.000000, 0.002703, 0.012629, 0.022977, 0.032503, 0.041849, 0.050711, 0.058910, 0.066584, 0.073818, 0.080671, 0.087179, 0.093367, 0.099248, 0.104830, 0.110113, 0.115095, 0.119768, 0.124123, 0.128147, 0.131827, 0.135146, 0.138088, 0.140635, 0.142768, 0.144467, 0.145711, 0.146481, 0.146753, 0.146507, 0.145717, 0.144359, 0.142406, 0.139826, 0.136582, 0.132633, 0.127925, 0.122391, 0.115944, 0.108464, 0.099782, 0.089648, 0.077664, 0.063131, 0.044608, 0.021258, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000 };
02028                 rx = rr;
02029                 gx = gg;
02030                 bx = bb;
02031 
02032 
02033                 /*
02034                 length = 11;
02035                 double rr [] = { 0.000000, 0.000000, 0.000000, 0.350000, 0.630000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000 };
02036                 double gg [] = { 1.000000, 0.510000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.390000, 0.630000, 1.000000 };
02037                 double bb [] = { 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 1.000000, 0.670000, 0.000000, 0.000000, 0.000000, 0.000000 };                
02038                 rx = rr;
02039                 gx = gg;
02040                 bx = bb;
02041                 */
02042         } else if (code == CIECOMP_ALT_1) {
02043                 length = 33;
02044                 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 };
02045                 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 };
02046                 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 };
02047                 rx = rr;
02048                 gx = gg;
02049                 bx = bb;
02050         } else if (code == (CIECOMP_ALT_1 + 1)) {
02051                 length = 33;
02052                 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 };
02053                 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 };
02054                 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 };
02055                 rx = rr;
02056                 gx = gg;
02057                 bx = bb;
02058         } else if (code == CIECOMP_ALT_2) {
02059                 length = 33;
02060                 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 };
02061                 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 };
02062                 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 };
02063                 rx = rr;
02064                 gx = gg;
02065                 bx = bb;
02066         } else if (code == (CIECOMP_ALT_2 + 1)) {
02067                 length = 26;
02068                 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 };
02069                 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 };
02070                 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 };
02071                 rx = rr;
02072                 gx = gg;
02073                 bx = bb;
02074         } else if (code == CIECOMP_ALT_3) {
02075                 length = 33;
02076                 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 };
02077                 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 };
02078                 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 };
02079                 rx = rr;
02080                 gx = gg;
02081                 bx = bb;
02082         } else if (code == (CIECOMP_ALT_3 + 1)) {
02083                 length = 27;
02084                 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 };
02085                 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 };
02086                 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 };
02087                 rx = rr;
02088                 gx = gg;
02089                 bx = bb;
02090         } else if (code == BLACKBODY) {
02091                 length = 33;
02092                 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 };
02093                 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 };
02094                 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 };
02095                 rx = rr;
02096                 gx = gg;
02097                 bx = bb;
02098         } else if (code == (BLACKBODY + 1)) {
02099                 length = 33;
02100                 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 };
02101                 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 };
02102                 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 };
02103                 rx = rr;
02104                 gx = gg;
02105                 bx = bb;
02106         } else if (code == RAINBOW) {
02107                 length = 33;
02108                 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 };
02109                 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 };
02110                 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 };
02111                 rx = rr;
02112                 gx = gg;
02113                 bx = bb;
02114         } else if (code == (RAINBOW + 1)) {
02115                 length = 25;
02116                 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 };
02117                 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 };
02118                 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 };
02119                 rx = rr;
02120                 gx = gg;
02121                 bx = bb;
02122         } else if (code == RAINBOW_ALT_1) {
02123                 length = 11;
02124                 double rr [] = { 0.00, 0.50, 0.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 1.00, 1.00 };
02125                 double gg [] = { 0.00, 0.00, 0.00, 0.50, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 1.00 };
02126                 double bb [] = { 0.00, 1.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 0.00, 0.50, 1.00 };
02127                 rx = rr;
02128                 gx = gg;
02129                 bx = bb;
02130         } else if (code == (RAINBOW_ALT_1 + 1)) {
02131                 length = 9;
02132                 double rr [] = { 0.50, 0.00, 0.00, 0.00, 0.00, 1.00, 1.00, 1.00, 1.00 };
02133                 double gg [] = { 0.00, 0.00, 0.50, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00 };
02134                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.00, 0.00, 0.00, 0.00, 0.50 };
02135                 rx = rr;
02136                 gx = gg;
02137                 bx = bb;
02138         } else if (code == RAINBOW_ALT_2) {
02139                 length = 13;
02140                 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 };
02141                 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 };
02142                 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 };
02143                 rx = rr;
02144                 gx = gg;
02145                 bx = bb;
02146         } else if (code == (RAINBOW_ALT_2 + 1)) {
02147                 length = 9;
02148                 double rr [] = { 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00 };
02149                 double gg [] = { 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00 };
02150                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00 };
02151                 rx = rr;
02152                 gx = gg;
02153                 bx = bb;
02154         } else if (code == RAINBOW_ALT_3) {
02155                 length = 13;
02156                 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 };
02157                 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 };
02158                 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 };
02159                 rx = rr;
02160                 gx = gg;
02161                 bx = bb;
02162         } else if (code == (RAINBOW_ALT_3 + 1)) {
02163                 length = 9;
02164                 double rr [] = { 1.00, 0.37, 0.00, 0.00, 0.00, 0.14, 0.76, 1.00, 1.00 };
02165                 double gg [] = { 0.00, 0.00, 0.26, 1.00, 1.00, 1.00, 1.00, 0.61, 0.00 };
02166                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00, 0.00 };
02167                 rx = rr;
02168                 gx = gg;
02169                 bx = bb;
02170         } else if (code == RAINBOW_ALT_4) {
02171                 length = 33;
02172                 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 };
02173                 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 };
02174                 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 };
02175                 rx = rr;
02176                 gx = gg;
02177                 bx = bb;
02178         } else if (code == (RAINBOW_ALT_4 + 1)) {
02179                 length = 22;
02180                 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 };
02181                 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 };
02182                 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 };
02183                 rx = rr;
02184                 gx = gg;
02185                 bx = bb;
02186         } else if (code == IRON) {
02187                 length = 33;
02188                 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 };
02189                 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 };
02190                 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 };
02191                 rx = rr;
02192                 gx = gg;
02193                 bx = bb;
02194         } else if (code == (IRON + 1)) {
02195                 length = 25;
02196                 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 };
02197                 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 };
02198                 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 };
02199                 rx = rr;
02200                 gx = gg;
02201                 bx = bb;
02202         } else if (code == IRON_ALT_1) {
02203                 length = 12;
02204                 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 };
02205                 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 };
02206                 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 };
02207                 rx = rr;
02208                 gx = gg;
02209                 bx = bb;
02210         } else if (code == (IRON_ALT_1 + 1)) {
02211                 length = 10;
02212                 double rr [] = { 0.05, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 };
02213                 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 };
02214                 double bb [] = { 0.25, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 };
02215                 rx = rr;
02216                 gx = gg;
02217                 bx = bb;
02218         } else if (code == IRON_ALT_2) {
02219                 length = 11;
02220                 double rr [] = { 0.00, 0.05, 0.10,  0.40, 0.80, 0.90, 0.95, 1.00,   1.00, 1.00, 1.00 };
02221                 double gg [] = { 0.00, 0.00, 0.00,  0.00, 0.10, 0.25, 0.45, 0.80,   0.95, 1.00, 1.00 };
02222                 double bb [] = { 0.00, 0.25, 0.50,  0.60, 0.50, 0.05, 0.00, 0.05,   0.45, 0.70, 1.00 };
02223                 rx = rr;
02224                 gx = gg;
02225                 bx = bb;
02226         } else if (code == (IRON_ALT_2 + 1)) {
02227                 length = 5;
02228                 double rr [] = { 0.40, 0.80, 0.90, 0.95, 1.00 };
02229                 double gg [] = { 0.60, 0.50, 0.05, 0.00, 0.05 };
02230                 double bb [] = { 0.00, 0.10, 0.25, 0.45, 0.80 };
02231                 rx = rr;
02232                 gx = gg;
02233                 bx = bb;
02234         } else if (code == (IRON_ALT_3)) {
02235                 length = 11;
02236                 double rr [] = { 0.00, 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00, 1.00 };
02237                 double gg [] = { 0.00, 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95, 1.00 };
02238                 double bb [] = { 0.00, 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45, 1.00 };
02239                 rx = rr;
02240                 gx = gg;
02241                 bx = bb;
02242         } else if (code == (IRON_ALT_3 + 1)) {
02243                 length = 9;
02244                 double rr [] = { 0.10, 0.40, 0.70, 0.80, 0.90, 0.95, 1.00, 1.00, 1.00 };
02245                 double gg [] = { 0.00, 0.00, 0.00, 0.10, 0.25, 0.45, 0.60, 0.80, 0.95 };
02246                 double bb [] = { 0.50, 0.60, 0.60, 0.50, 0.05, 0.00, 0.00, 0.05, 0.45 };
02247                 rx = rr;
02248                 gx = gg;
02249                 bx = bb;
02250         } else if (code == BLUERED) {
02251                 length = 3;
02252                 double rr [] = { 0.00, 1.00, 1.00 };
02253                 double gg [] = { 0.00, 1.00, 0.00 };
02254                 double bb [] = { 1.00, 1.00, 0.00 };
02255                 rx = rr;
02256                 gx = gg;
02257                 bx = bb;
02258         } else if (code == (BLUERED + 1)) {
02259                 length = 2;
02260                 double rr [] = { 0.00, 1.00 };
02261                 double gg [] = { 0.00, 0.00 };
02262                 double bb [] = { 1.00, 0.00 };
02263                 rx = rr;
02264                 gx = gg;
02265                 bx = bb;
02266         } else if (code == BLUERED_ALT_1) {
02267                 length = 4;
02268                 double rr [] = { 0.00, 0.00, 1.00, 1.00 };
02269                 double gg [] = { 0.00, 0.00, 0.00, 1.00 };
02270                 double bb [] = { 0.00, 1.00, 0.00, 1.00 };
02271                 rx = rr;
02272                 gx = gg;
02273                 bx = bb;
02274         } else if (code == (BLUERED_ALT_1 + 1)) {
02275                 length = 2;
02276                 double rr [] = { 0.00, 1.00 };
02277                 double gg [] = { 0.00, 0.00 };
02278                 double bb [] = { 1.00, 0.00 };
02279                 rx = rr;
02280                 gx = gg;
02281                 bx = bb;
02282         } else if (code == BLUERED_ALT_2) {
02283                 length = 7;
02284                 double rr [] = { 0.00, 0.50, 0.80, 1.00, 1.00, 1.00, 1.00 };
02285                 double gg [] = { 0.00, 0.50, 0.80, 1.00, 0.80, 0.50, 0.00 };
02286                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.80, 0.50, 0.00 };
02287                 rx = rr;
02288                 gx = gg;
02289                 bx = bb;
02290         } else if (code == (BLUERED_ALT_2 + 1)) {
02291                 length = 4;
02292                 double rr [] = { 0.00, 0.50, 1.00, 1.00 };
02293                 double gg [] = { 0.00, 0.50, 0.50, 0.00 };
02294                 double bb [] = { 1.00, 1.00, 0.50, 0.00 };
02295                 rx = rr;
02296                 gx = gg;
02297                 bx = bb;
02298         } else if (code == JET) {
02299                 length = 13;
02300                 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 };
02301                 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 };
02302                 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 };
02303                 rx = rr;
02304                 gx = gg;
02305                 bx = bb;
02306         } else if (code == (JET + 1)) {
02307                 length = 11;
02308                 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00, 1.00 };
02309                 double gg [] = { 0.00, 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00, 0.50 };
02310                 double bb [] = { 0.50, 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00, 0.50 };
02311                 rx = rr;
02312                 gx = gg;
02313                 bx = bb;
02314         } else if (code == JET_ALT_1) {
02315                 length = 11;
02316                 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00, 1.00 };
02317                 double gg [] = { 0.00, 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00, 1.00 };
02318                 double bb [] = { 0.00, 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00, 1.00 };
02319                 rx = rr;
02320                 gx = gg;
02321                 bx = bb;
02322         } else if (code == (JET_ALT_1 + 1)) {
02323                 length = 9;
02324                 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.70, 1.00, 1.00, 1.00 };
02325                 double gg [] = { 0.00, 0.20, 0.80, 1.00, 1.00, 1.00, 0.80, 0.20, 0.00 };
02326                 double bb [] = { 1.00, 1.00, 1.00, 0.70, 0.00, 0.00, 0.00, 0.00, 0.00 };
02327                 rx = rr;
02328                 gx = gg;
02329                 bx = bb;
02330         } else if (code == ICE) {
02331                 length = 10;
02332                 double rr [] = { 1.00, 0.25, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 };
02333                 double gg [] = { 1.00, 1.00, 0.88, 0.75, 0.68, 0.50, 0.38, 0.25, 0.13, 0.00 };
02334                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 1.00, 0.75, 0.50, 0.25, 0.00 };
02335                 rx = rr;
02336                 gx = gg;
02337                 bx = bb;
02338         } else if (code == (ICE + 1)) {
02339                 length = 6;
02340                 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 };
02341                 double gg [] = { 0.88, 0.75, 0.68, 0.50, 0.38, 0.25 };
02342                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.75, 0.50 };
02343                 rx = rr;
02344                 gx = gg;
02345                 bx = bb;
02346         } else if (code == ICE_ALT_1) {
02347                 length = 11;
02348                 double rr [] = { 1.00, 0.67, 0.33,     0.00, 0.00, 0.00, 0.00, 0.00,    0.00, 0.00, 0.00 };
02349                 double gg [] = { 1.00, 1.00, 1.00,     1.00, 0.75, 0.50, 0.25, 0.00,    0.00, 0.00, 0.00 };
02350                 double bb [] = { 1.00, 1.00, 1.00,     1.00, 1.00, 1.00, 1.00, 1.00,    0.67, 0.33, 0.00 };
02351                 rx = rr;
02352                 gx = gg;
02353                 bx = bb;
02354         } else if (code == (ICE_ALT_1 + 1)) {
02355                 length = 7;
02356                 double rr [] = { 0.33,     0.00, 0.00, 0.00, 0.00, 0.00,    0.00 };
02357                 double gg [] = { 1.00,     1.00, 0.75, 0.50, 0.25, 0.00,    0.00 };
02358                 double bb [] = { 1.00,     1.00, 1.00, 1.00, 1.00, 1.00,    0.67 };
02359                 rx = rr;
02360                 gx = gg;
02361                 bx = bb;
02362         } else if (code == ICE_ALT_2) {
02363                 length = 11;
02364                 double rr [] = { 1.00, 0.64, 0.36, 0.16, 0.04, 0.01, 0.00, 0.00, 0.00, 0.00, 0.00 };
02365                 double gg [] = { 1.00, 0.90, 0.80, 0.70, 0.60, 0.50, 0.40, 0.30, 0.20, 0.10, 0.00 };
02366                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.99, 0.89, 0.78, 0.63, 0.48, 0.00 };
02367                 rx = rr;
02368                 gx = gg;
02369                 bx = bb;
02370         } else if (code == (ICE_ALT_2 + 1)) {
02371                 length = 7;
02372                 double rr [] = { 0.36, 0.16, 0.04, 0.01, 0.00, 0.00, 0.00 };
02373                 double gg [] = { 0.80, 0.70, 0.60, 0.50, 0.40, 0.30, 0.20 };
02374                 double bb [] = { 1.00, 1.00, 1.00, 0.99, 0.89, 0.78, 0.63 };
02375                 rx = rr;
02376                 gx = gg;
02377                 bx = bb;
02378         } else if (code == ICE_ALT_3) {
02379                 length = 9;
02380                 double rr [] = { 1.00, 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 };
02381                 double gg [] = { 1.00, 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.50, 0.00 };
02382                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00, 0.00 };
02383                 rx = rr;
02384                 gx = gg;
02385                 bx = bb;
02386         } else if (code == (ICE_ALT_3 + 1)) {
02387                 length = 7;
02388                 double rr [] = { 0.50, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00 };
02389                 double gg [] = { 1.00, 1.00, 0.50, 0.00, 0.50, 1.00, 0.50 };
02390                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 0.50, 0.00, 0.00 };
02391                 rx = rr;
02392                 gx = gg;
02393                 bx = bb;
02394         } else if (code == ICEIRON) {
02395                 length = 19;
02396                 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 };
02397                 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 };
02398                 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 };
02399                 rx = rr;
02400                 gx = gg;
02401                 bx = bb;
02402         } else if (code == (ICEIRON + 1)) {
02403                 length = 12;
02404                 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 };
02405                 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 };
02406                 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 };
02407                 rx = rr;
02408                 gx = gg;
02409                 bx = bb;
02410         } else if (code == ICEIRON_ALT_1) {
02411                 length = 21;
02412                 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 };
02413                 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 };
02414                 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 };
02415                 rx = rr;
02416                 gx = gg;
02417                 bx = bb;
02418         } else if (code == (ICEIRON_ALT_1 + 1)) {
02419                 length = 10;
02420                 double rr [] = { 0.00, 0.00, 0.00, 0.00, 0.00,          0.40, 0.80, 0.90, 0.95, 1.00 };
02421                 double gg [] = { 1.00, 0.75, 0.50, 0.25, 0.00,          0.00, 0.10, 0.25, 0.45, 0.80 };
02422                 double bb [] = { 1.00, 1.00, 1.00, 1.00, 1.00,          0.60, 0.50, 0.05, 0.00, 0.05 };
02423                 rx = rr;
02424                 gx = gg;
02425                 bx = bb;
02426         } else if (code == ICEIRON_ALT_2) {
02427                 length = 19;
02428                 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 };
02429                 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 };
02430                 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 };
02431                 rx = rr;
02432                 gx = gg;
02433                 bx = bb;
02434         } else if (code == (ICEIRON_ALT_2 + 1)) {
02435                 length = 17;
02436                 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 };
02437                 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 };
02438                 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 };
02439                 rx = rr;
02440                 gx = gg;
02441                 bx = bb;
02442         } else if (code == ICEFIRE) {
02443                 length = 19;
02444                 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 };
02445                 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 };
02446                 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 };
02447                 rx = rr;
02448                 gx = gg;
02449                 bx = bb;
02450         } else if (code == (ICEFIRE + 1)) {
02451                 length = 12;
02452                 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 };
02453                 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 };
02454                 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 };
02455                 rx = rr;
02456                 gx = gg;
02457                 bx = bb;
02458         } else if (code == ICEFIRE_ALT_1) {
02459                 length = 17;
02460                 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 };
02461                 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 };
02462                 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 };
02463                 rx = rr;
02464                 gx = gg;
02465                 bx = bb;
02466         } else if (code == (ICEFIRE_ALT_1 + 1)) {
02467                 length = 10;
02468                 double rr [] = { 0.33,     0.00, 0.00, 0.00,    0.00, 0.67,     1.00, 1.00, 1.00,   1.00 };
02469                 double gg [] = { 1.00,     1.00, 0.50, 0.00,    0.00, 0.00,     0.00, 0.50, 1.00,   1.00 };
02470                 double bb [] = { 1.00,     1.00, 1.00, 1.00,    0.67, 0.00,     0.00, 0.00, 0.00,   0.33 };
02471                 rx = rr;
02472                 gx = gg;
02473                 bx = bb;
02474         } else if (code == ICEFIRE_ALT_2) {
02475                 length = 17;
02476                 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 };
02477                 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 };
02478                 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 };
02479                 rx = rr;
02480                 gx = gg;
02481                 bx = bb;
02482         } else if (code == (ICEFIRE_ALT_2 + 1)) {
02483                 length = 12;
02484                 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 };
02485                 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 };
02486                 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 };
02487                 rx = rr;
02488                 gx = gg;
02489                 bx = bb;
02490         } else if (code == ICEFIRE_ALT_3) {
02491                 length = 17;
02492                 //                  WHITE           CYAN            LBLUE           DBLUE           PURPLE          RED             ORANGE          YELLOW          WHITE
02493                 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 };
02494                 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 };
02495                 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 };
02496                 rx = rr;
02497                 gx = gg;
02498                 bx = bb;
02499         } else if (code == (ICEFIRE_ALT_3 + 1)) {
02500                 length = 13;
02501                 //                  CYAN            LBLUE           DBLUE           PURPLE          RED             ORANGE          YELLOW
02502                 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 };
02503                 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 };
02504                 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 };
02505                 rx = rr;
02506                 gx = gg;
02507                 bx = bb;
02508         } else if (code == REPEATED) {
02509                 length = 16;
02510                 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 };
02511                 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, };
02512                 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, };
02513                 rx = rr;
02514                 gx = gg;
02515                 bx = bb;
02516         } else if (code == (REPEATED + 1)) {
02517                 length = 12;
02518                 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 };
02519                 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 };
02520                 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 };
02521                 rx = rr;
02522                 gx = gg;
02523                 bx = bb;
02524         } else if (code == REPEATED_ALT_1) {
02525                 length = 6;
02526                 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 };
02527                 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 };
02528                 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 };
02529                 rx = rr;
02530                 gx = gg;
02531                 bx = bb;
02532         } else if (code == (REPEATED_ALT_1 + 1)) {
02533                 length = 6;
02534                 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 };
02535                 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 };
02536                 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 };
02537                 rx = rr;
02538                 gx = gg;
02539                 bx = bb;
02540         } else if (code == REPEATED_ALT_2) {
02541                 length = 48;
02542                 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 };
02543                 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 };
02544                 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 };
02545                 rx = rr;
02546                 gx = gg;
02547                 bx = bb;
02548         } else if (code == (REPEATED_ALT_2 + 1)) {
02549                 length = 48;
02550                 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 };
02551                 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 };
02552                 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 };
02553                 rx = rr;
02554                 gx = gg;
02555                 bx = bb;
02556         } else if (code == REPEATED_ALT_3) {
02557                 length = 41;
02558                 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 };
02559                 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 };
02560                 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 };
02561                 rx = rr;
02562                 gx = gg;
02563                 bx = bb;
02564         } else if (code == (REPEATED_ALT_3 + 1)) {
02565                 length = 28;
02566                 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 };
02567                 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 };
02568                 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 };
02569                 rx = rr;
02570                 gx = gg;
02571                 bx = bb;
02572         } else if (code == REPEATED_ALT_4) {
02573                 length = 12;
02574         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 };
02575         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 };
02576         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 };
02577         rx = rr;
02578         gx = gg;
02579         bx = bb;
02580         } else if (code == (REPEATED_ALT_4 + 1)) {
02581                 length = 12;
02582         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 };
02583         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 };
02584         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 };
02585         rx = rr;
02586         gx = gg;
02587         bx = bb;
02588         } else if (code == REPEATED_ALT_5) {
02589                 length = 6;
02590                 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 };
02591                 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 };
02592                 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 };
02593                 rx = rr;
02594                 gx = gg;
02595                 bx = bb;
02596         } else if (code == (REPEATED_ALT_5 + 1)) {
02597                 length = 6;
02598                 double rr [] = { 0.00, 0.00, 0.00, 1.00, 1.00, 1.00 };
02599                 double gg [] = { 0.00, 1.00, 1.00, 1.00, 0.00, 0.00 };
02600                 double bb [] = { 1.00, 1.00, 0.00, 0.00, 0.00, 1.00 };
02601                 rx = rr;
02602                 gx = gg;
02603                 bx = bb;
02604         } else if (code == REPEATED_ALT_6) {
02605                 length = 48;
02606                 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 };
02607                 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 };
02608                 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 };
02609                 rx = rr;
02610                 gx = gg;
02611                 bx = bb;
02612         } else if (code == (REPEATED_ALT_6 + 1)) {
02613                 length = 48;
02614                 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 };
02615                 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 };
02616                 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 };
02617                 rx = rr;
02618                 gx = gg;
02619                 bx = bb;
02620         }
02621         
02622         //cout << "gx[0] = " << gx[0] << endl;
02623         //cout << "gx[1] = " << gx[1] << endl;
02624         
02625         if (!flexibleMarkers) {
02626                 
02627                 for (int iii = 0; iii < length; iii++) {
02628                         da[iii] = (double(iii) / double((length-1)));
02629                 }
02630                 dd = da;
02631         }
02632         
02633         dx = dd;
02634         
02635         //cout << "gx[0] = " << gx[0] << endl;
02636         //cout << "gx[1] = " << gx[1] << endl;
02637 
02638         create_long_map();
02639         
02640         //cout << "gx[0] = " << gx[0] << endl;
02641         //cout << "gx[1] = " << gx[1] << endl;
02642 
02643         setupLookupTable(1);
02644         setupLookupTable(2);
02645 
02646 }
02647 
02648 int cScheme::current_scheme() {
02649         return code;
02650 }
02651 
02652 void cScheme::customize(double* d, double* r, double* g, double* b, int len) {
02653         code = CUSTOM;
02654         dx = d;
02655         rx = r;
02656         gx = g;
02657         bx = b;
02658         length = len;
02659 }
02660 
02661 void cScheme::falsify_image(const cv::Mat& thermIm, cv::Mat& outputIm, int param) {
02662 
02663         if ((outputIm.size() != thermIm.size()) || (outputIm.type() != CV_8UC3)) {
02664                 outputIm = cv::Mat::zeros(thermIm.size(), CV_8UC3);
02665         }
02666 
02667         //int level;
02668         // inputs can be 8 or 16 bits/pixel
02669         // output is 8 bits/pixel
02670         //int maxVal = 255;
02671 
02672         // some kind of check to figure out if input image is actual 16-bits/pixel
02673         if (thermIm.depth() == 2) {
02674         //maxVal = 65535;
02675         }
02676 
02677         // store the current standard, and then modify it according to params
02678         //int newCode, oldCode;
02679 
02680         if (param == 1) {
02681                 //oldCode = code;
02682                 //newCode = code + 1;
02683         }
02684 
02685         //printf("%s << code = %d; newCode = %d\n", __FUNCTION__, code, newCode);
02686 
02687         /*
02688         if (params[0] == 0) {   // if a variation hasn't been selected
02689 
02690             // start to deconstruct code...
02691         newCode = code;
02692 
02693         if (((newCode % 2) == 0) && (params[1] == 1)) {   // if it's unsafe but safety has been selected
02694             newCode += 1;
02695         }
02696 
02697 
02698         } else {    // otherwise, ignore last digit
02699         newCode = code - (code % 10);
02700 
02701         newCode += (params[0]-1)*2;    // add variation code
02702 
02703         if (params[1] == 1) {
02704             newCode += 1;              // add safety index
02705         }
02706 
02707         }
02708         */
02709 
02710         if (param == 1) {
02711                 //load_standard(newCode);
02712         }
02713 
02714         //setupLookupTable();
02715 
02716         //double sr, sg, sb;
02717 
02718     /*
02719         printf("%s << thermIm = %dx%d, %d, %d\n", __FUNCTION__, thermIm.size().width, thermIm.size().height, thermIm.depth(), thermIm.channels());
02720         printf("%s << outputIm = %dx%d, %d, %d\n", __FUNCTION__, outputIm.size().width, outputIm.size().height, outputIm.depth(), outputIm.channels());
02721     */
02722 
02723         // Create RGB output image
02724         //if (outputIm.empty()) {
02725         //outputIm = cv::Mat(thermIm.size(), CV_8UC3);
02726         //}
02727 
02728         //struct timeval timer;
02729         //double elapsedTime;
02730         //elapsedTime = timeElapsedMS(timer);
02731 
02732 
02733         //level = 0;
02734 
02735         int lookupIndex = 0;
02736 
02737         for (int i = 0; i < thermIm.size().height; i++) {
02738                 for (int j = 0; j < thermIm.size().width; j++) {
02739 
02740                         // find closest element...
02741 
02742                         //if ((*thermIm)(i, j) > 255
02743 
02744                         //level = (thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/65536;
02745             //level = (int) floor((thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/65535); // or 65536?
02746                         //printf("level = %d\n", level);
02747 
02748                         // removing this halves from 15 - 7
02749                         /*
02750                         if (thermIm.depth() == 2) {
02751                 level = (int) floor(double((thermIm.at<unsigned short>(i,j)*(MAP_LENGTH-1))/maxVal)); // for 16 bits/pixel
02752                         } else {
02753                 level = (int) floor(double((thermIm.at<unsigned char>(i,j)*(MAP_LENGTH-1))/maxVal)); // for standard 8bits/pixel
02754                         }
02755                         */
02756                         // removing this takes it down effectively to zero...
02757                         /*
02758             outputIm.at<cv::Vec3b>(i,j)[2] = (unsigned char) (255.0 * red[level]);
02759             outputIm.at<cv::Vec3b>(i,j)[1] = (unsigned char) (255.0 * green[level]);
02760             outputIm.at<cv::Vec3b>(i,j)[0] = (unsigned char) (255.0 * blue[level]);
02761                         */
02762 
02763                         //printf("%s << depth (%d) (%d, %d)\n", __FUNCTION__, thermIm.depth(), thermIm.cols, thermIm.rows);
02764 
02765                         //imshow("asda", thermIm);
02766                         //waitKey();
02767 
02768                         if (thermIm.depth() == 2) {
02769                                 lookupIndex = thermIm.at<unsigned short>(i,j);
02770                                 outputIm.at<cv::Vec3b>(i,j)[2] = lookupTable_2[lookupIndex][2];
02771                                 outputIm.at<cv::Vec3b>(i,j)[1] = lookupTable_2[lookupIndex][1];
02772                                 outputIm.at<cv::Vec3b>(i,j)[0] = lookupTable_2[lookupIndex][0];
02773                         } else if (thermIm.depth() == 0) {
02774 
02775                                 lookupIndex = thermIm.at<unsigned char>(i,j);
02776                                 //printf("%s << here (%d, %d, %d)\n", __FUNCTION__, lookupTable_1[lookupIndex][2], lookupTable_1[lookupIndex][1], lookupTable_1[lookupIndex][0]);
02777                                 outputIm.at<cv::Vec3b>(i,j)[2] = lookupTable_1[lookupIndex][2];
02778                                 outputIm.at<cv::Vec3b>(i,j)[1] = lookupTable_1[lookupIndex][1];
02779                                 outputIm.at<cv::Vec3b>(i,j)[0] = lookupTable_1[lookupIndex][0];
02780                         }
02781 
02782 
02783                         /*
02784                         sr = 255.0 * red[level];
02785                         sg = 255.0 * green[level];
02786                         sb = 255.0 * blue[level];
02787 
02788             outputIm.at<cv::Vec3b>(i,j)[2] = (unsigned char) sr;
02789             outputIm.at<cv::Vec3b>(i,j)[1] = (unsigned char) sg;
02790             outputIm.at<cv::Vec3b>(i,j)[0] = (unsigned char) sb;
02791                         */
02792 
02793                         //printf("raw = %f\n", thermIm(i, j));
02794                         //printf("lvl = %d\n", level);
02795                         //printf("red = %f\n", red[level]);
02796                         //printf("grn = %f\n", green[level]);
02797                         //printf("blu = %f\n", blue[level]);
02798                         //printf("/n");
02799 
02800                 }
02801                 //std::cin.get();
02802         }
02803 
02804         //elapsedTime = timeElapsedMS(timer);
02805         //printf("%s << Time elapsed [%d] = %f\n", __FUNCTION__, 0, elapsedTime);
02806 
02807         if (param == 1) {
02808                 //load_standard(oldCode);
02809         }
02810 
02811 }
02812 
02813 void cScheme::image_resize(cv::Mat& inputIm, int dim_i, int dim_j) {
02814         cv::Mat newIm;
02815         newIm = cv::Mat(dim_i,dim_j,inputIm.type());
02816 
02817         double val;
02818 
02819         int ni, nj;
02820 
02821         ni = inputIm.size().height;
02822         nj = inputIm.size().width;
02823 
02824         for (int i = 0; i < dim_i; i++) {
02825                 for (int j = 0; j < dim_j; j++) {
02826                         //val = (*inputIm)(((int)((i*inputIm->ni())/dim_i)),((int)((j*inputIm->nj())/dim_j)));
02827                         val = inputIm.at<unsigned char>(((int)((i*ni)/dim_i)),((int)((j*nj)/dim_j)));
02828 
02829                         newIm.at<unsigned char>(i,j) = val;
02830                 }
02831         }
02832 
02833         //inputIm->set_size(dim_i, dim_j);
02834         //inputIm->deep_copy(*newIm);
02835     inputIm = cv::Mat(newIm);
02836 
02837 }
02838 
02839 void cScheme::forge_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double* params, double thresh) {
02840         
02841         outputIm = cv::Mat(thermIm.size(), CV_8UC3);
02842         
02843         double working_params[2];
02844         
02845         if (params == NULL) {
02846                 working_params[0] = 0.2;
02847                 working_params[1] = 0.8;
02848         } else {
02849                 working_params[0] = params[0];
02850                 working_params[1] = params[1];
02851         }
02852         
02853         double vals[2], percentiles[2];
02854         percentiles[0] = thresh;
02855         percentiles[1] = 1 - thresh;
02856         
02857         findPercentiles(thermIm, vals, percentiles, 2);
02858         
02859         /*
02860         printf("%s << percentiles[0] = (%f), percentiles[1] = (%f)\n", __FUNCTION__, vals[0], vals[1]);
02861         printf("%s << red[0] = (%d), red[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][0], lookupTable_1[65535][0]);
02862         printf("%s << green[0] = (%d), green[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][1], lookupTable_1[65535][1]);
02863         printf("%s << blue[0] = (%d), blue[1] = (%d)\n", __FUNCTION__, lookupTable_1[0][2], lookupTable_1[65535][2]);
02864         */
02865         
02866         double lumChange[3];
02867         double maxLumChange;
02868         
02869         for (int iii = 0; iii < thermIm.rows; iii++) {
02870                 for (int jjj = 0; jjj < thermIm.cols; jjj++) {
02871                         
02872                         if (thermIm.depth() == 2) {
02873                                 if (thermIm.at<unsigned short>(iii,jjj) < (unsigned short) vals[0]) {
02874                                         outputIm.at<cv::Vec3b>(iii,jjj)[0] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][0];
02875                                         outputIm.at<cv::Vec3b>(iii,jjj)[1] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][1];
02876                                         outputIm.at<cv::Vec3b>(iii,jjj)[2] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][2];
02877                                 } else if (thermIm.at<unsigned short>(iii,jjj) > (unsigned short) vals[1]) {
02878                                         outputIm.at<cv::Vec3b>(iii,jjj)[0] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][0];
02879                                         outputIm.at<cv::Vec3b>(iii,jjj)[1] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][1];
02880                                         outputIm.at<cv::Vec3b>(iii,jjj)[2] = lookupTable_2[thermIm.at<unsigned short>(iii,jjj)][2];
02881                                 } else {
02882                                         
02883                                         lumChange[0] = 2.0 * (((double) visualIm.at<cv::Vec3b>(iii,jjj)[0])/255.0 - 0.5) * (working_params[1] - working_params[0]);
02884                                         lumChange[1] = 2.0 * (((double) visualIm.at<cv::Vec3b>(iii,jjj)[1])/255.0 - 0.5) * (working_params[1] - working_params[0]);
02885                                         lumChange[2] = 2.0 * (((double) visualIm.at<cv::Vec3b>(iii,jjj)[2])/255.0 - 0.5) * (working_params[1] - working_params[0]);
02886                                         
02887                                         maxLumChange = max(lumChange[0], lumChange[1]);
02888                                         maxLumChange = max(maxLumChange, lumChange[2]);
02889                                         
02890                                         outputIm.at<cv::Vec3b>(iii,jjj)[0] = ((double) visualIm.at<cv::Vec3b>(iii, jjj)[0]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0);
02891                                         outputIm.at<cv::Vec3b>(iii,jjj)[1] = ((double) visualIm.at<cv::Vec3b>(iii, jjj)[1]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0);
02892                                         outputIm.at<cv::Vec3b>(iii,jjj)[2] = ((double) visualIm.at<cv::Vec3b>(iii, jjj)[2]) * (working_params[1] - working_params[0]) + (working_params[0] * 255.0);
02893                                         /*
02894                                         if (lumChange[0] > 0) {
02895                                                 outputIm.at<cv::Vec3b>(iii,jjj)[0] = outputIm.at<cv::Vec3b>(iii, jjj)[0] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * maxLumChange;
02896                                         } else {
02897                                                 outputIm.at<cv::Vec3b>(iii,jjj)[0] = outputIm.at<cv::Vec3b>(iii, jjj)[0] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * maxLumChange);
02898                                         }
02899                                         
02900                                         if (lumChange[1] > 0) {
02901                                                 outputIm.at<cv::Vec3b>(iii,jjj)[1] = outputIm.at<cv::Vec3b>(iii, jjj)[1] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * maxLumChange;
02902                                         } else {
02903                                                 outputIm.at<cv::Vec3b>(iii,jjj)[1] = outputIm.at<cv::Vec3b>(iii, jjj)[1] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * maxLumChange);
02904                                         }
02905                                         
02906                                         if (lumChange[2] > 0) {
02907                                                 outputIm.at<cv::Vec3b>(iii,jjj)[2] = outputIm.at<cv::Vec3b>(iii, jjj)[2] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * maxLumChange;
02908                                         } else {
02909                                                 outputIm.at<cv::Vec3b>(iii,jjj)[2] = outputIm.at<cv::Vec3b>(iii, jjj)[2] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * maxLumChange);
02910                                         }
02911                                         */
02912                                         /*
02913                                         if (lumChange[0] > 0) {
02914                                                 outputIm.at<cv::Vec3b>(iii,jjj)[0] = outputIm.at<cv::Vec3b>(iii, jjj)[0] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * lumChange[0];
02915                                         } else {
02916                                                 outputIm.at<cv::Vec3b>(iii,jjj)[0] = outputIm.at<cv::Vec3b>(iii, jjj)[0] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * lumChange[0]);
02917                                         }
02918                                         
02919                                         if (lumChange[1] > 0) {
02920                                                 outputIm.at<cv::Vec3b>(iii,jjj)[1] = outputIm.at<cv::Vec3b>(iii, jjj)[1] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * lumChange[1];
02921                                         } else {
02922                                                 outputIm.at<cv::Vec3b>(iii,jjj)[1] = outputIm.at<cv::Vec3b>(iii, jjj)[1] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * lumChange[1]);
02923                                         }
02924                                         
02925                                         if (lumChange[2] > 0) {
02926                                                 outputIm.at<cv::Vec3b>(iii,jjj)[2] = outputIm.at<cv::Vec3b>(iii, jjj)[2] + (255.0 - outputIm.at<cv::Vec3b>(iii, jjj)[0]) * lumChange[2];
02927                                         } else {
02928                                                 outputIm.at<cv::Vec3b>(iii,jjj)[2] = outputIm.at<cv::Vec3b>(iii, jjj)[2] + (outputIm.at<cv::Vec3b>(iii, jjj)[0] * lumChange[2]);
02929                                         }
02930                                         */
02931                                         
02932                                         /*
02933                                         outputIm.at<cv::Vec3b>(iii,jjj)[0] = visualIm.at<cv::Vec3b>(iii,jjj)[0];
02934                                         outputIm.at<cv::Vec3b>(iii,jjj)[1] = visualIm.at<cv::Vec3b>(iii,jjj)[1];
02935                                         outputIm.at<cv::Vec3b>(iii,jjj)[2] = visualIm.at<cv::Vec3b>(iii,jjj)[2];
02936                                         */
02937                                 }
02938                                 
02939 
02940                         }
02941                         
02942                         
02943                 }
02944         }
02945         
02946 }
02947 
02948 void cScheme::fuse_image(cv::Mat& thermIm, cv::Mat& visualIm, cv::Mat& outputIm, double* params) {
02949 
02950         double working_params[2];
02951         
02952         bool alreadyMapped = false;
02953         
02954         if (params == NULL) {
02955                 working_params[0] = DEFAULT_LOWER_VISIBLE_FUSION_LIMIT;
02956                 working_params[1] = DEFAULT_UPPER_VISIBLE_FUSION_LIMIT;
02957         } else {
02958                 working_params[0] = params[0];
02959                 working_params[1] = params[1];
02960         }
02961 
02962         int falseParam = 1;
02963         double lumChange;
02964 
02965         unsigned char sr, sg, sb;
02966 
02967         cv::Mat newTherm;
02968         
02969         outputIm = cv::Mat(newTherm.size(), CV_8UC3);
02970 
02971         if (thermIm.channels() > 1) {
02972                 
02973                 if (checkIfActuallyGray(thermIm)) {
02974                         cvtColor(thermIm, newTherm, CV_RGB2GRAY);
02975                 } else {
02976                         thermIm.copyTo(outputIm);
02977                         alreadyMapped = true;
02978                 }
02979         
02980     } else {
02981         thermIm.copyTo(newTherm);
02982     }
02983 
02984         cv::Mat newVisual;
02985 
02986     if (visualIm.channels() > 1) {
02987         cvtColor(visualIm, newVisual, CV_RGB2GRAY);
02988     } else {
02989         visualIm.copyTo(newVisual);
02990     }
02991 
02992         // If images aren't the same size, resize
02993         if (thermIm.size() != visualIm.size()) {
02994                 // Determine which one is bigger and resize accordingly
02995                 if (thermIm.size().height > thermIm.size().width) {
02996                         image_resize(newVisual, thermIm.size().height, thermIm.size().width);
02997                 } else {
02998                         image_resize(newTherm, visualIm.size().height, visualIm.size().width);
02999                 }
03000         }
03001 
03002         if (!alreadyMapped) {
03003                 falsify_image(newTherm, outputIm, falseParam);
03004         }
03005 
03006         // For each pixel
03007         for (int i = 0; i < outputIm.size().height; i++)        {
03008                 for (int j = 0; j < outputIm.size().width; j++) {
03009 
03010                         lumChange = 2.0 * (((double) newVisual.at<unsigned char>(i,j))/255.0 - 0.5) * (working_params[1] - working_params[0]);
03011 
03012                         if (lumChange > 0) {
03013                                 sr = outputIm.at<cv::Vec3b>(i, j)[0] + (255.0 - outputIm.at<cv::Vec3b>(i, j)[0]) * lumChange;
03014                                 sg = outputIm.at<cv::Vec3b>(i, j)[1] + (255.0 - outputIm.at<cv::Vec3b>(i, j)[1]) * lumChange;
03015                                 sb = outputIm.at<cv::Vec3b>(i, j)[2] + (255.0 - outputIm.at<cv::Vec3b>(i, j)[2]) * lumChange;
03016                         } else {
03017                                 sr = outputIm.at<cv::Vec3b>(i, j)[0] + (outputIm.at<cv::Vec3b>(i, j)[0] * lumChange);
03018                                 sg = outputIm.at<cv::Vec3b>(i, j)[1] + (outputIm.at<cv::Vec3b>(i, j)[1] * lumChange);
03019                                 sb = outputIm.at<cv::Vec3b>(i, j)[2] + (outputIm.at<cv::Vec3b>(i, j)[2] * lumChange);
03020                         }
03021 
03022                         outputIm.at<cv::Vec3b>(i,j)[0] = sr;
03023                         outputIm.at<cv::Vec3b>(i,j)[1] = sg;
03024                         outputIm.at<cv::Vec3b>(i,j)[2] = sb;
03025                 }
03026         }
03027 
03028 }
03029 
03030 void generateHistogram(cv::Mat& src, cv::Mat& dst, double* im_hist, double* im_summ, double* im_stat) {
03031 
03032     cv::MatND hist;
03033     cv::Mat img;
03034 
03035     int nPixels = src.cols*src.rows;
03036 
03037     //printf("%s << src.depth() = %d\n", __FUNCTION__, src.depth());
03038 
03039     src.convertTo(img, CV_32FC1);
03040 
03041     //svLib::normalize_16(src, img);  // no longer old
03042 
03043     //imshow("converted", img);
03044     //waitKey(0);
03045 
03046     double minIntensity = 9e50, maxIntensity=0;
03047     minMaxLoc(img, &minIntensity, &maxIntensity, 0, 0);
03048 
03049     double midIntensity = (maxIntensity + minIntensity) / 2.0;
03050     double intensityRange = maxIntensity-minIntensity;
03051 
03052     if (intensityRange < 64) {
03053         minIntensity = midIntensity - 32;
03054         maxIntensity = midIntensity + 32;
03055     }
03056 
03057     //double newIntensityRange = maxIntensity-minIntensity;
03058 
03059     printf("%s << intensity range = %f (%f, %f)\n", __FUNCTION__, intensityRange, minIntensity, maxIntensity);
03060 
03061     int intensityBins = 64;
03062     int histSize[] = {intensityBins};
03063     float intensityRanges[] = {minIntensity, maxIntensity};
03064     const float* ranges[] = {intensityRanges};
03065     int channels[] = {0};
03066 
03067     calcHist(&img, 1, channels, cv::Mat(), hist, 1, histSize, ranges, true, false);
03068 
03069     double minVal = 9e50, maxVal=0.0;
03070     minMaxLoc(hist, &minVal, &maxVal, 0, 0);
03071 
03072     //printf("%s << minVal = %f; maxVal = %f\n", __FUNCTION__, minVal, maxVal);
03073 
03074     int horizontalScale = 640 / intensityBins;
03075 
03076     //printf("%s << horizontalScale = %d\n", __FUNCTION__, horizontalScale);
03077     int verticalScale = 480;
03078     cv::Mat histImg = cv::Mat::zeros(verticalScale, intensityBins*horizontalScale, CV_8UC3); //, cv::Vec3b::all(255));
03079 
03080     cv::Scalar col = CV_RGB(255, 255, 255);
03081     histImg.setTo(col);
03082 
03083     //int quant01, quant05, quant50, quant95, quant99;
03084 
03085     double quantileCount = 0.0;
03086 
03087     for(int iii = 0; iii < intensityBins; iii++ ) {
03088         float binVal = hist.at<float>(iii, 0);
03089         float count = binVal/maxVal;
03090 
03091         quantileCount += binVal;
03092 
03093         /*
03094         printf("%s << iii = %d\n", __FUNCTION__, iii);
03095         printf("%s << binVal = %f\n", __FUNCTION__, binVal);
03096         printf("%s << fullCount = %f\n", __FUNCTION__, fullCount);
03097         */
03098 
03099         if (quantileCount < 0.01*double(nPixels)) {
03100             //quant01 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins));
03101         }
03102         if (quantileCount < 0.05*double(nPixels)) {
03103             //quant05 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins));
03104         }
03105         if (quantileCount < 0.50*double(nPixels)) {
03106             //quant50 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins));
03107         }
03108         if (quantileCount < 0.95*double(nPixels)) {
03109             //quant95 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins));
03110         }
03111         if (quantileCount < 0.99*double(nPixels)) {
03112             //quant99 = minIntensity + int(double(iii)*newIntensityRange/double(intensityBins));
03113         }
03114 
03115         //printf("%s << count = %f\n", __FUNCTION__, count);
03116 
03117         rectangle(histImg, cv::Point(iii*horizontalScale+1, verticalScale), cv::Point((iii+1)*horizontalScale-2, (verticalScale-1)*(1-count)+1), CV_RGB(0, 64, 192), CV_FILLED);
03118     }
03119 
03120     histImg.copyTo(dst);
03121 
03122     double histMean = 0, histDev = 0, histRMS = 0, histSkew = 0;
03123 
03124     double pixelCount = img.rows * img.cols;
03125 
03126     // Calculate histogram statistics:
03127     for (int iii = 0; iii < img.rows; iii++) {
03128         for (int jjj = 0; jjj < img.cols; jjj++) {
03129             histMean += img.at<float>(iii,jjj) / pixelCount;
03130         }
03131     }
03132 
03133     //printf("%s << histMean = %f\n", __FUNCTION__, histMean);
03134     im_stat[0] = histMean;
03135 
03136     for (int iii = 0; iii < img.rows; iii++) {
03137         for (int jjj = 0; jjj < img.cols; jjj++) {
03138             histDev += pow((img.at<float>(iii,jjj) - histMean), 2) / pixelCount;
03139         }
03140     }
03141 
03142     histDev = pow(histDev, 0.5);
03143 
03144     //printf("%s << histDev = %f\n", __FUNCTION__, histDev);
03145     im_stat[1] = histDev;
03146 
03147     for (int iii = 0; iii < img.rows; iii++) {
03148         for (int jjj = 0; jjj < img.cols; jjj++) {
03149             histRMS += pow(img.at<float>(iii,jjj), 2) / pixelCount;
03150         }
03151     }
03152 
03153     histRMS = pow(histRMS, 0.5);
03154 
03155     //printf("%s << histRMS = %f\n", __FUNCTION__, histRMS);
03156 
03157     im_stat[2] = histRMS;
03158 
03159     for (int iii = 0; iii < img.rows; iii++) {
03160         for (int jjj = 0; jjj < img.cols; jjj++) {
03161             histSkew += pow((img.at<float>(iii,jjj)- histMean) / histDev, 3) / pixelCount;
03162         }
03163     }
03164 
03165     //printf("%s << histSkew = %f\n", __FUNCTION__, histSkew);
03166 
03167     im_stat[3] = histSkew;
03168 
03169     //printf("%s << qrange_0_100 = %d\n", __FUNCTION__, int(intensityRange));
03170 
03171     //printf("%s << qrange_1_99 = %d\n", __FUNCTION__, quant99-quant01);
03172 
03173     //printf("%s << qrange_5_95 = %d\n", __FUNCTION__, quant95-quant05);
03174 
03175 }
03176 
03177 cv::Mat normForDisplay(cv::Mat origMat) {
03178     double minVal = 9e99, maxVal = -9e99;
03179 
03180     for (int iii = 0; iii < origMat.rows; iii++) {
03181         for (int jjj = 0; jjj < origMat.cols; jjj++) {
03182 
03183             // printf("%s << origMat.val = %f\n", __FUNCTION__, origMat.at<double>(iii,jjj));
03184 
03185 
03186             if (origMat.at<double>(iii,jjj) > maxVal) {
03187                 maxVal = origMat.at<double>(iii,jjj);
03188             }
03189 
03190             if (origMat.at<double>(iii,jjj) < minVal) {
03191                 minVal = origMat.at<double>(iii,jjj);
03192             }
03193         }
03194     }
03195 
03196     cv::Mat displayMat(origMat.size(), CV_8UC1);
03197 
03198     for (int iii = 0; iii < origMat.rows; iii++) {
03199         for (int jjj = 0; jjj < origMat.cols; jjj++) {
03200             displayMat.at<unsigned char>(iii,jjj) = (unsigned char) ((origMat.at<double>(iii,jjj) - minVal) * 255.0 / (maxVal - minVal));
03201         }
03202     }
03203 
03204     cv::Mat largerMat;
03205 
03206     resize(displayMat, largerMat, cv::Size(origMat.rows*1, origMat.cols*1), 0, 0, cv::INTER_NEAREST);
03207 
03208     return largerMat;
03209 }


thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45