image_processing.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2012, PAL Robotics, S.L.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of PAL Robotics, S.L. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #ifndef __PAL_IMAGE_PROCESSING_H__
00038 #define __PAL_IMAGE_PROCESSING_H__
00039 
00040 //#include <opencv/cv.h>
00041 #include <opencv2/core/core.hpp>
00042 
00043 #include <vector>
00044 
00045 namespace pal_vision_util
00046 {
00055   void getConnectedComponents(const cv::Mat& binaryImage,
00056                               std::vector< std::vector<cv::Point2i> >& components,
00057                               std::vector< cv::Rect >& boundingBoxes);
00058 
00059 
00066   class ImageRoi
00067   {
00068     public:
00069     ImageRoi();
00070 
00071     ImageRoi(const ImageRoi& roi);
00072 
00073     ImageRoi(int left, int top, int w, int h);
00074 
00075     ImageRoi(CvRect rect);
00076 
00077     ~ImageRoi();
00078 
00079     void set(CvRect rect);
00080 
00081     void clear();
00082 
00083     bool empty() const;
00084 
00085     CvRect toCvRect() const;
00086 
00091     void keepInside(int imgWidth, int imgHeight);
00092 
00096     const ImageRoi& resize(double factorHorizontal, double factorVertical);
00097 
00098     int x, y, width, height;
00099   };
00100 
00107   class Image
00108   {
00109   public:
00110 
00114     Image();
00115 
00119     Image(IplImage *img);
00120 
00125     Image(const cv::Mat& mat);
00126 
00130     ~Image();
00131 
00135     void freeImage();
00136 
00137     void loadImage(const std::string& fileName);
00138 
00142     void set(IplImage *img);
00143 
00148     IplImage *release();
00149 
00150     void resizeImage(int width, int height, int channels, int depth);
00151 
00152     int getWidth() const { return _img->width; };
00153     int getHeight() const { return _img->height; };
00154     int getChannel() const { return _img->nChannels; };
00155     int getDepth() const { return _img->depth; };
00156 
00157     unsigned char getPixelB(int col, int row, int ch) const;
00158 
00159     float getPixelF(int col, int row, int ch) const;
00160 
00161     short getPixelS(int col, int row, int ch) const;
00162 
00163     void setPixelB(int col, int row, int ch, unsigned char value);
00164 
00165     void setPixelS(int col, int row, int ch, short value);
00166 
00167     void setPixelF(int col, int row, int ch, float value);
00168 
00169     IplImage* getIplImg() { return _img; };
00170 
00171     IplImage* operator->(void) const { return _img; }
00172 
00173     operator IplImage*()  const { return _img; }   //overloads cast to IplImage* operator
00174 
00175   private:
00176 
00177     IplImage _iplFromMat;
00178     IplImage *_img;
00179     bool _releaseOnDestroyer;
00180   };
00181 
00185   void getLab(const Image& img, Image& L, Image& a, Image& b);
00186 
00190   void setLab(const Image& L, const Image& a, const Image& b, Image& img);
00191 
00200   void dctNormalization(const Image& img, Image& normalizedImg, int coefficientsToCancel, const ImageRoi& roi = ImageRoi(0,0,0,0));
00201 
00205   void dctNormalization(const cv::Mat& img, cv::Mat& normalizedImg, int coefficientsToCancel, const ImageRoi& roi = ImageRoi(0,0,0,0));
00206 
00207 } // namespace pal_vision_util
00208 
00209 #endif // __PAL_IMAGE_PROCESSING_H__


pal_vision_segmentation
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 11:57:00