ImagePropertiesCV.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  ImagePropertiesCV.h
00003  *
00004  *  (C) 2007 AG Aktives Sehen <agas@uni-koblenz.de>
00005  *           Universitaet Koblenz-Landau
00006  *
00007  *  Additional information:
00008  *  $Id: $
00009  *******************************************************************************/
00010 
00011 #ifndef ImagePropertiesCV_H
00012 #define ImagePropertiesCV_H
00013 
00014 #include <vector>
00015 #include <opencv2/highgui/highgui.hpp>
00016 #include <ros/ros.h>
00017 
00018 #include "../KeyPointExtraction/KeyPoint.h"
00019 #include "Workers/ImageHelpers/ImageMaskCV.h"
00020 
00021 #include "Workers/Math/Point2D.h"
00022 
00023 // include headers that implement an archive in binary format
00024 #include <boost/archive/binary_iarchive.hpp>
00025 #include <boost/archive/binary_oarchive.hpp>
00026 #include <boost/archive/text_iarchive.hpp>
00027 #include <boost/archive/text_oarchive.hpp>
00028 
00029 #include "Architecture/Serializer/cvmat_serialization.h"
00030 
00036 class ImagePropertiesCV
00037 {
00038 public:
00039 
00040     ImagePropertiesCV();
00041 
00043     ImagePropertiesCV ( std::string name, cv::Mat* imageY, cv::Mat* imageUV, ImageMaskCV* imageMask=0 );
00044 
00045     ImagePropertiesCV ( const ImagePropertiesCV& other );
00046 
00048     ~ImagePropertiesCV();
00049 
00050     ImagePropertiesCV& operator= ( const ImagePropertiesCV& other );
00051 
00053     void applyMask();
00054     void traceOutline();
00055     void extractKeyPoints();
00056 
00058     void calculateProperties();
00059 
00060     // GETTER FUNCTIONS
00061 
00062     std::string getName() const { return m_Name; }
00063 
00064     cv::Mat* getImageY() const { return m_ImageY; }
00065 
00066     cv::Mat* getImageUV() const { return m_ImageUV; }
00067 
00068     cv::Mat* getMaskedImageY() const { return m_MaskedImageY; }
00069 
00070     cv::Mat* getMaskedImageUV() const { return m_MaskedImageUV; }
00071 
00072     ImageMaskCV* getImageMask() const { return m_ImageMask; }
00073 
00074     std::vector< KeyPoint >* getKeyPoints() const { return m_KeyPoints; }
00075 
00076     std::vector<Point2D>* getOutline() const { return m_Outline; }
00077 
00078     std::vector<Point2D> getBoundingBox() const;
00079 
00080     Point2D getCenter() const { return m_Center; }
00081 
00082     // SERIALIZATION
00083 
00084     template<class Archive>
00085     void save(Archive & ar, const unsigned int version) const
00086     {
00087         unsigned x = 12;
00088         ar & x;
00089         ar & m_Name;
00090 
00091         ar & m_ImageY;
00092         ar & m_ImageUV;
00093 
00094         if ( m_ImageMask )
00095         {
00096             bool b = true;
00097             ar & b;
00098             int width = m_ImageMask->getWidth();
00099             ar & width;
00100             int height = m_ImageMask->getHeight();
00101             ar & height;
00102 
00103             ar & boost::serialization::make_array(m_ImageMask->getData(), m_ImageMask->getWidth()*m_ImageMask->getHeight());
00104         }
00105         else
00106         {
00107             bool b = false;
00108             ar & b;
00109         }
00110     }
00111 
00112     template<class Archive>
00113     void load(Archive & ar, const unsigned int version_b)
00114     {
00115         clear();
00116 
00117         unsigned version;
00118         ar & version;
00119 
00120         if ( version != 12 )
00121         {
00122           throw "File has wrong version number.";
00123         }
00124 
00125         ar & m_Name;
00126 
00127         m_ImageY = new cv::Mat();
00128         m_ImageUV = new cv::Mat();
00129 
00130         ar & m_ImageY;
00131         ar & m_ImageUV;
00132 
00133         bool hasMask;
00134         ar & hasMask;
00135 
00136         if ( hasMask )
00137         {
00138           int width;
00139           int height;
00140           ar & width;
00141           ar & height;
00142 
00143           // TODO check this for correct behavior
00144           m_ImageMask = new ImageMaskCV( width, height);
00145           ar & boost::serialization::make_array(m_ImageMask->getData(), width*height);
00146         }
00147         else
00148         {
00149           m_ImageMask = false;
00150         }
00151 
00152         calculateProperties();
00153     }
00154 
00155     BOOST_SERIALIZATION_SPLIT_MEMBER()
00156 
00157     private:
00158 
00159         void clear();
00160     void deleteAll();
00161 
00163     std::string m_Name;
00164     cv::Mat* m_ImageY;
00165     cv::Mat* m_ImageUV;
00166     ImageMaskCV* m_ImageMask;
00167     ImageMaskCV* m_ImageMaskWithBorder;
00168 
00170     cv::Mat* m_MaskedImageY;
00171     cv::Mat* m_MaskedImageUV;
00172     std::vector< KeyPoint >* m_KeyPoints;
00173     std::vector<Point2D>* m_Outline;
00174     Point2D m_Center;
00175 
00176     int m_Border;
00177 };
00178 
00179 BOOST_CLASS_VERSION(ImagePropertiesCV, 12)
00180 
00181 #endif


or_libs
Author(s): Viktor Seib
autogenerated on Tue Jan 7 2014 11:24:03