Util.h
Go to the documentation of this file.
00001 /*
00002  * This file is part of ALVAR, A Library for Virtual and Augmented Reality.
00003  *
00004  * Copyright 2007-2012 VTT Technical Research Centre of Finland
00005  *
00006  * Contact: VTT Augmented Reality Team <alvar.info@vtt.fi>
00007  *          <http://www.vtt.fi/multimedia/alvar.html>
00008  *
00009  * ALVAR is free software; you can redistribute it and/or modify it under the
00010  * terms of the GNU Lesser General Public License as published by the Free
00011  * Software Foundation; either version 2.1 of the License, or (at your option)
00012  * any later version.
00013  *
00014  * This library is distributed in the hope that it will be useful, but WITHOUT
00015  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00016  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
00017  * for more details.
00018  *
00019  * You should have received a copy of the GNU Lesser General Public License
00020  * along with ALVAR; if not, see
00021  * <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>.
00022  */
00023 
00024 #ifndef UTIL_H
00025 #define UTIL_H
00026 
00034 #include "Alvar.h"
00035 #include "AlvarException.h"
00036 #include <vector>
00037 #include <iostream>
00038 #include <iomanip>
00039 #include <sstream>
00040 #include <cxcore.h>
00041 #include <cv.h>
00042 #include <cmath> //for abs
00043 #include <map>
00044 
00045 namespace alvar {
00046 
00047 const double PI = 3.14159265;
00048 
00052 template<class C> inline
00053 int ALVAR_EXPORT Sign(const C& v)
00054 {
00055         return (v<0?-1:1);
00056 }
00057 
00061 template<class C> inline
00062 double ALVAR_EXPORT Rad2Deg(const C& v)
00063 {
00064         return v*(180/PI);
00065 }
00066 
00070 template<class C> inline
00071 double ALVAR_EXPORT Deg2Rad(const C& v)
00072 {
00073         return v*(PI/180);
00074 }
00075 
00079 template<class C, class D = int> 
00080 struct ALVAR_EXPORT Point : public C
00081 {
00085         D val;
00086 
00087         Point(int vx=0, int vy=0)
00088         {
00089                 C::x = vx;
00090                 C::y = vy;
00091         }
00092         Point(double vx, double vy)
00093         {
00094                 C::x = vx;
00095                 C::y = vy;
00096         }
00097 };
00098 
00102 typedef ALVAR_EXPORT Point<CvPoint> PointInt;
00103 
00107 typedef ALVAR_EXPORT Point<CvPoint2D64f> PointDouble;
00108 
00114 template<class PointType>
00115 double PointSquaredDistance(PointType p1, PointType p2) {
00116         return ((p1.x-p2.x)*(p1.x-p2.x)) +
00117                 ((p1.y-p2.y)*(p1.y-p2.y));
00118 }
00119 
00120 
00121 //ttesis start
00122 
00123 
00128 int ALVAR_EXPORT dot(CvPoint *A, CvPoint *B, CvPoint *C);
00129 
00135 int ALVAR_EXPORT cross(CvPoint *A,CvPoint *B, CvPoint *C);
00136 
00137 
00142 double ALVAR_EXPORT distance(CvPoint *A,CvPoint *B);
00143 
00150 double ALVAR_EXPORT linePointDist(CvPoint *A,CvPoint *B,CvPoint *C, bool isSegment);
00151 
00152 
00161 double ALVAR_EXPORT angle(CvPoint *A,CvPoint *B, CvPoint *C,CvPoint *D, int isDirectionDependent);
00162 
00163 
00170 double ALVAR_EXPORT polyLinePointDist(CvPoint *PointList, int nPnts,CvPoint *C, int *index, int isClosedPolygon);
00171 
00172 //ttesis end
00173 
00174 
00180 void ALVAR_EXPORT FitCVEllipse(const std::vector<PointDouble> &points, CvBox2D& ellipse_box);
00181 
00182 int ALVAR_EXPORT exp_filt2(std::vector<double> &v,std:: vector<double> &ret, bool clamp);
00183 
00190 template<class C> inline
00191 int ALVAR_EXPORT diff(const std::vector<C> &v, std::vector<C> &ret)
00192 {       
00193         ret.clear();
00194         if (v.size() == 1) {
00195                 ret.push_back(0);
00196         } else if (v.size() > 1) {
00197                 ret.push_back(v.at(1)-v.at(0));
00198                 for(size_t i = 1; i < v.size(); ++i)
00199                 {
00200                         ret.push_back(v.at(i)-v.at(i-1));
00201                 }
00202         }
00203         return int(ret.size());
00204 }
00205 
00213 int ALVAR_EXPORT find_zero_crossings(const std::vector<double>& v, std::vector<int> &corners, int offs = 20);
00214 
00218 void ALVAR_EXPORT out_matrix(const CvMat *m, const char *name);
00219 
00227 double ALVAR_EXPORT Limit(double val, double min_val, double max_val);
00228 
00236 struct ALVAR_EXPORT Index {
00238         std::vector<int> val;
00240         Index(int a);
00242         Index(int a, int b);
00244         Index(int a, int b, int c);
00246         bool operator<(const Index &index) const;
00247 };
00248 
00252 class ALVAR_EXPORT Histogram {
00253 protected:
00254         std::map<Index, int> bins;
00255         std::vector<int> dim_binsize;
00256         int DimIndex(int dim, double val);
00257         double DimVal(int dim, int index);
00258 public:
00261         void AddDimension(int binsize);
00263         void Clear();
00265         void Inc(double dim0, double dim1=0, double dim2=0);
00269         int GetMax(double *dim0, double *dim1=0, double *dim2=0);
00270 };
00271 
00275 class ALVAR_EXPORT HistogramSubpixel : public Histogram {
00276 protected:
00277         std::map<Index, double> acc_dim0;
00278         std::map<Index, double> acc_dim1;
00279         std::map<Index, double> acc_dim2;
00280 public:
00282         void Clear();
00284         void Inc(double dim0, double dim1=0, double dim2=0);
00289         int GetMax(double *dim0, double *dim1=0, double *dim2=0);
00290 };
00291 
00292 #if (_MSC_VER >= 1400)
00293         inline void STRCPY(char *to, rsize_t size, const char *src) {
00294                 strcpy_s(to,size,src);
00295         }
00296 #else
00297         inline void STRCPY(char *to, size_t size, const char *src) {
00298                 strncpy(to,src,size-1);
00299         }
00300 #endif
00301 
00302 #ifdef min
00303 #undef min
00304 #endif
00305 
00306 #ifdef max
00307 #undef max
00308 #endif
00309 
00351 class ALVAR_EXPORT Serialization {
00352 protected:
00353         bool input;
00354         std::string filename;
00355         //std::iostream *stream;
00356         std::ios *stream;
00357         void *formatter_handle;
00358         bool Output();
00359         bool Input();
00360         bool Descend(const char *id);
00361         bool Ascend();
00362 public:
00394         Serialization(std::string _filename);
00396         Serialization(std::basic_iostream<char> &_stream);
00398         Serialization(std::basic_istream<char> &_stream);
00400         Serialization(std::basic_ostream<char> &_stream);
00402         ~Serialization();
00404         template <class C>
00405         Serialization& operator<<(C &serializable) {
00406                 input=false;
00407                 if (!SerializeClass(serializable) || !Output()) {
00408                         throw(AlvarException("Serialization failure"));
00409                 }
00410                 return *this;
00411         }
00413         template <class C>
00414         Serialization& operator>>(C &serializable) {
00415                 input=true;
00416                 if (!Input() || !SerializeClass(serializable)) {
00417                         throw(AlvarException("Serialization failure"));
00418                 }
00419                 return *this;
00420         }
00426         template <class C>
00427         bool SerializeClass(C &serializable) {
00428                 std::string s = serializable.SerializeId();
00429                 if (!Descend(s.c_str()) || !serializable.Serialize(this) || !Ascend()) {
00430                         return false;
00431                 }
00432                 return true;
00433         }
00435         bool Serialize(int &data, const std::string &name);
00437         bool Serialize(unsigned short &data, const std::string &name);
00439         bool Serialize(unsigned long &data, const std::string &name);
00441         bool Serialize(double &data, const std::string &name);
00443         bool Serialize(std::string &data, const std::string &name);
00445         bool Serialize(CvMat &data, const std::string &name);
00447         bool IsInput() { return input; }
00448 };
00449 
00450 } // namespace alvar
00451 
00452 #endif


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 21:12:54