image_normalization.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 /*
00030  * image_normalization.cpp
00031  *
00032  *  Created on: Jan 19, 2012
00033  *      Author: kkozak
00034  */
00035 
00036 #include <swri_image_util/image_normalization.h>
00037 
00038 namespace swri_image_util
00039 {
00040   void normalize_illumination(cv::Mat NormImage,
00041                               cv::Mat SourceImage,
00042                               cv::Mat& DestImage)
00043   {
00044     // note that Norm image should be of type CV_32FC1 and scaled between 0 and
00045     // 1 (but not exactly equal to 0 anywhere)
00046     cv::Mat tempIm1;
00047     SourceImage.convertTo(tempIm1, CV_32FC1, 1.0, 0.0);
00048     cv::divide(tempIm1, NormImage, tempIm1, 1.0);
00049     cv::Mat firstImage;
00050     cv::Mat secondImage;
00051     tempIm1.convertTo(DestImage, CV_8UC1);
00052   }
00053 
00054   cv::Mat generate_normalization_image(const std::vector<cv::Mat>& image_list)
00055   {
00056     cv::Mat norm_image;
00057     if (image_list.empty())
00058     {
00059       return cv::Mat();
00060     }
00061 
00062     const cv::Mat& rep_im = image_list.front();
00063 
00064     cv::Mat image_sum(cv::Size(rep_im.cols, rep_im.rows), CV_64F);
00065 
00066     for (uint32_t i = 0; i < image_list.size(); i++)
00067     {
00068       cv::Mat temp_im;
00069       image_list[i].convertTo(temp_im, CV_64F, 1.0, 0.0);
00070 
00071       image_sum = image_sum + temp_im;
00072     }
00073 
00074     image_sum = image_sum / static_cast<double>(image_list.size());
00075 
00076     cv::Mat mean_image;
00077     image_sum.convertTo(mean_image, CV_8U);
00078     cv::Mat temp_norm_image;
00079 
00080     cv::medianBlur(mean_image, temp_norm_image, 45);
00081 
00082     cv::Mat temp_norm_image2;
00083     temp_norm_image.convertTo(temp_norm_image2, CV_32F);
00084     double max1 = 0;
00085     for (int32_t i = 0; i < temp_norm_image2.rows; i++)
00086     {
00087       for (int32_t j = 0; j < temp_norm_image2.cols; j++)
00088       {
00089         if (temp_norm_image2.at<float>(i, j) > max1)
00090         {
00091           max1 = temp_norm_image2.at<float>(i, j);
00092         }
00093       }
00094     }
00095 
00096     temp_norm_image2 = temp_norm_image2 * (255.0 / max1);
00097 
00098     cv::Mat temp_norm_image3;
00099     temp_norm_image2.convertTo(temp_norm_image3, CV_8U, 1.0, 0.0);
00100 
00101 
00102     cv::GaussianBlur(temp_norm_image3,
00103                      norm_image,
00104                      cv::Size(25, 25),
00105                      5,
00106                      5);
00107 
00108     return norm_image;
00109   }
00110 
00111   void MaskedBoxFilter(cv::Mat& mat, cv::Mat& mask, int32_t kernel_size)
00112   {
00113     mask.setTo(1, mask);
00114     cv::Mat local_sums;
00115     cv::boxFilter(
00116       mat,
00117       local_sums,
00118       mat.depth(),
00119       cv::Size(kernel_size, kernel_size),
00120       cv::Point(-1, -1),
00121       false);
00122     cv::Mat local_mask_sums;
00123     cv::boxFilter(
00124       mask,
00125       local_mask_sums,
00126       mat.depth(),
00127       cv::Size(kernel_size, kernel_size),
00128       cv::Point(-1, -1),
00129       false);
00130     cv::Mat blurred;
00131     cv::divide(local_sums, local_mask_sums, blurred, 1, mat.type());
00132     blurred.copyTo(mat, local_mask_sums != 0);
00133   }
00134 
00135   void ContrastStretch(
00136     int32_t grid_size,
00137     const cv::Mat& source_image,
00138     cv::Mat& dest_image,
00139     const cv::Mat& mask,
00140     double max_min,
00141     double min_max)
00142   {
00143     double cell_width = static_cast<double>(source_image.cols) / grid_size;
00144     double cell_height = static_cast<double>(source_image.rows) / grid_size;
00145 
00146     cv::Mat max_vals(grid_size, grid_size, CV_32F);
00147     cv::Mat min_vals(grid_size, grid_size, CV_32F);
00148     cv::Mat grid_mask = cv::Mat::ones(grid_size, grid_size, CV_8U) * 255;
00149 
00150     bool has_mask = !mask.empty();
00151     for(int i = 0; i < grid_size; i++)
00152     {
00153       for(int j = 0; j < grid_size; j++)
00154       {
00155         double minVal = 0;
00156         double maxVal = 0;
00157 
00158         int x = j * cell_width;
00159         int y = i * cell_height;
00160         int x2 = (j + 1) * cell_width;
00161         int y2 = (i + 1) * cell_height;
00162         int w = x2 - x;
00163         int h = y2 - y;
00164 
00165         cv::Rect roi = cv::Rect(x, y, w, h);
00166         roi.width = std::min(source_image.cols - roi.x, roi.width);
00167         roi.height = std::min(source_image.rows - roi.y, roi.height);
00168 
00169         if (has_mask)
00170         {
00171           if (cv::countNonZero(mask(roi)) > 0)
00172           {
00173             cv::minMaxLoc(source_image(roi), &minVal, &maxVal, 0, 0, mask(roi));
00174           }
00175           else
00176           {
00177             grid_mask.at<uint8_t>(i, j) = 0;
00178           }
00179         }
00180         else
00181         {
00182           cv::minMaxLoc(source_image(roi), &minVal, &maxVal, 0, 0);
00183         }
00184 
00185         max_vals.at<float>(i, j) = maxVal;
00186         min_vals.at<float>(i, j) = minVal;
00187       }
00188     }
00189 
00190     MaskedBoxFilter(max_vals, grid_mask, 3);
00191     MaskedBoxFilter(min_vals, grid_mask, 3);
00192 
00193     // Stretch contrast accordingly
00194     for(int i = 0; i < source_image.rows; i++)
00195     {
00196       int cell_y = std::min(grid_size - 1, static_cast<int>(i / cell_height));
00197       int cell_y_start = cell_y * cell_height;
00198       int cell_y_end = std::min(source_image.rows - 1, static_cast<int>((cell_y + 1) * cell_height));
00199       double py = (i - cell_y_start) / static_cast<double>(cell_y_end - cell_y_start);
00200 
00201       for(int j = 0; j < source_image.cols; j++)
00202       {
00203         // Find relevant min and max values
00204         int cell_x = std::min(grid_size - 1, static_cast<int>(j / cell_width));
00205         int cell_x_start = cell_x * cell_width;
00206         int cell_x_end = std::min(source_image.cols - 1, static_cast<int>((cell_x + 1) * cell_width));
00207         double px = (j - cell_x_start) / static_cast<double>(cell_x_end - cell_x_start);
00208 
00209         int cell_x1 = cell_x;
00210         int cell_x2 = cell_x;
00211         double px1 = 0.5;
00212         double px2 = 0.5;
00213         if (px < 0.5 && cell_x > 0)
00214         {
00215           cell_x1 = cell_x - 1;
00216           cell_x2 = cell_x;
00217           px2 = px + 0.5;
00218           px1 = 1.0 - px2;
00219         }
00220         else if (px > 0.5 && cell_x + 1 < grid_size)
00221         {
00222           cell_x1 = cell_x;
00223           cell_x2 = cell_x + 1;
00224           px1 = 1.5 - px;
00225           px2 = 1.0 - px1;
00226         }
00227 
00228         int cell_y1 = cell_y;
00229         int cell_y2 = cell_y;
00230         double py1 = 0.5;
00231         double py2 = 0.5;
00232         if (py < 0.5 && cell_y > 0)
00233         {
00234           cell_y1 = cell_y - 1;
00235           cell_y2 = cell_y;
00236           py2 = py + 0.5;
00237           py1 = 1.0 - py2;
00238         }
00239         else if (py > 0.5 && cell_y + 1 < grid_size)
00240         {
00241           cell_y1 = cell_y;
00242           cell_y2 = cell_y + 1;
00243           py1 = 1.5 - py;
00244           py2 = 1.0 - py1;
00245         }
00246 
00247         // Stretch histogram
00248         double min_x1_y1 = min_vals.at<float>(cell_y1, cell_x1);
00249         double max_x1_y1 = max_vals.at<float>(cell_y1, cell_x1);
00250 
00251         double min_x2_y1 = min_vals.at<float>(cell_y1, cell_x2);
00252         double max_x2_y1 = max_vals.at<float>(cell_y1, cell_x2);
00253 
00254         double min_x1_y2 = min_vals.at<float>(cell_y2, cell_x1);
00255         double max_x1_y2 = max_vals.at<float>(cell_y2, cell_x1);
00256 
00257         double min_x2_y2 = min_vals.at<float>(cell_y2, cell_x2);
00258         double max_x2_y2 = max_vals.at<float>(cell_y2, cell_x2);
00259 
00260         //4-point interpolation
00261         double xM1 = max_x1_y1 * px1 + max_x2_y1 * px2;
00262         double xM2 = max_x1_y2 * px1 + max_x2_y2 * px2;
00263         double M = xM1 * py1 + xM2 * py2;
00264 
00265         double xm1 = min_x1_y1 * px1 + min_x2_y1 * px2;
00266         double xm2 = min_x1_y2 * px1 + min_x2_y2 * px2;
00267         double m = xm1 * py1 + xm2 * py2;
00268         double minVal = m;
00269         double maxVal = M;
00270 
00271         if(maxVal > 255) maxVal = 255;
00272         if(minVal < 0) minVal = 0;
00273 
00274         // Put a bound on maxVal and minVal
00275         maxVal = std::max(maxVal, min_max);
00276         minVal = std::min(minVal, max_min);
00277 
00278         double val = source_image.at<uint8_t>(i,j);
00279         val = 255.0 * (val - minVal) / (maxVal - minVal);
00280         if(val > 255) val = 255;
00281         if(val < 0) val = 0;
00282         dest_image.at<uint8_t>(i,j) = val;
00283       }
00284     }
00285 
00286     dest_image.setTo(0, mask == 0);
00287   }
00288 
00289   void NormalizeResponse(
00290       const cv::Mat& src,
00291       cv::Mat& dst,
00292       int winsize,
00293       int ftzero,
00294       uchar* buf)
00295   {
00296     if (dst.empty())
00297     {
00298       dst.create(src.size(), CV_8U);
00299     }
00300 
00301     // Source code from OpenCV: modules/calib3d/src/stereobm.cpp
00302     int x, y, wsz2 = winsize / 2;
00303     int* vsum = reinterpret_cast<int*>(cv::alignPtr(buf + (wsz2 + 1) * sizeof(vsum[0]), 32));
00304     int scale_g = winsize * winsize / 8, scale_s = (1024 + scale_g) / (scale_g * 2);
00305     const int OFS = 256 * 5, TABSZ = OFS * 2 + 256;
00306     uchar tab[TABSZ];
00307     const uchar* sptr = src.ptr();
00308     int srcstep = src.step;
00309     cv::Size size = src.size();
00310 
00311     scale_g *= scale_s;
00312 
00313     for (x = 0; x < TABSZ; x++)
00314     {
00315       tab[x] = (uchar)(x - OFS < -ftzero ? 0 : x - OFS > ftzero ? ftzero * 2 : x - OFS + ftzero);
00316     }
00317 
00318     for (x = 0; x < size.width; x++)
00319     {
00320       vsum[x] = (ushort)(sptr[x] * (wsz2 + 2));
00321     }
00322 
00323     for (y = 1; y < wsz2; y++)
00324     {
00325       for (x = 0; x < size.width; x++)
00326       {
00327         vsum[x] = (ushort)(vsum[x] + sptr[srcstep*y + x]);
00328       }
00329     }
00330 
00331     for (y = 0; y < size.height; y++)
00332     {
00333       const uchar* top = sptr + srcstep * MAX(y - wsz2 - 1, 0);
00334       const uchar* bottom = sptr + srcstep * MIN(y + wsz2, size.height - 1);
00335       const uchar* prev = sptr + srcstep * MAX(y - 1, 0);
00336       const uchar* curr = sptr + srcstep * y;
00337       const uchar* next = sptr + srcstep * MIN(y + 1, size.height - 1);
00338       uchar* dptr = dst.ptr<uchar>(y);
00339 
00340       for (x = 0; x < size.width; x++)
00341       {
00342         vsum[x] = (ushort)(vsum[x] + bottom[x] - top[x]);
00343       }
00344 
00345       for (x = 0; x <= wsz2; x++)
00346       {
00347         vsum[-x-1] = vsum[0];
00348         vsum[size.width + x] = vsum[size.width - 1];
00349       }
00350 
00351       int sum = vsum[0] * (wsz2 + 1);
00352       for( x = 1; x <= wsz2; x++ )
00353       {
00354         sum += vsum[x];
00355       }
00356 
00357       int val = ((curr[0] * 5 + curr[1] + prev[0] + next[0]) * scale_g - sum * scale_s) >> 10;
00358       dptr[0] = tab[val + OFS];
00359 
00360       for( x = 1; x < size.width-1; x++ )
00361       {
00362         sum += vsum[x + wsz2] - vsum[x - wsz2 - 1];
00363         val = ((curr[x] * 4 + curr[x - 1] + curr[x + 1] + prev[x] + next[x]) * scale_g - sum * scale_s) >> 10;
00364         dptr[x] = tab[val + OFS];
00365       }
00366 
00367       sum += vsum[x+wsz2] - vsum[x - wsz2 - 1];
00368       val = ((curr[x] * 5 + curr[x - 1] + prev[x] + next[x]) * scale_g - sum * scale_s) >> 10;
00369       dptr[x] = tab[val + OFS];
00370     }
00371   }
00372 
00373   cv::Mat scale_2_8bit(const cv::Mat& image)
00374        {
00375               if (image.type() == CV_8UC1)
00376                 return image;
00377               cv::Mat Image8Bit(image.rows, image.cols, CV_8U), Image8BitColor; //Define an 8bit image
00378               //Convert the image to 32bit float
00379               cv::Mat ImageFloat;
00380               image.convertTo(ImageFloat, CV_32F, 1, 0);
00381               double maxVal; //Define the max value of image
00382               cv::minMaxLoc(ImageFloat.reshape(1,1), NULL, &maxVal);//Extract the max value of image
00383               //ReScale the image to 0 to 255
00384               ImageFloat = ImageFloat*((1 << 8)/pow(2, ceil(log(maxVal)/log(2))));
00385               ImageFloat.convertTo(Image8Bit,CV_8U, 1, 0);
00386               return Image8Bit;
00387        }
00388 
00389        cv::Mat scale_2_8bit_color(const cv::Mat& image)
00390        {
00391               if (image.type() == CV_8UC3)
00392                 return image;
00393               cv::Mat Image8Bit = scale_2_8bit(image), Image8BitColor;
00394               cvtColor(Image8Bit, Image8BitColor, CV_GRAY2BGR);
00395               return Image8BitColor;
00396        }
00397 }


swri_image_util
Author(s): Kris Kozak
autogenerated on Thu Jun 6 2019 20:34:52