NumberManipulation.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
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 the LABUST 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 #ifndef NUMBERMANIPULATION_HPP_
00035 #define NUMBERMANIPULATION_HPP_
00036 
00037 #define _USE_MATH_DEFINES
00038 #include <cmath>
00039 #include <labust/math/Limits.hpp>
00040 
00041 namespace labust
00042 {
00043   namespace math
00044   {
00045     //const double M_2PI = 2*M_PI;
00052     inline double wrapRad(double angle)
00053     {
00054       angle = fmod(angle,2*M_PI);
00055       if (angle > M_PI) return -2*M_PI + angle;
00056       if (angle <= -M_PI) return 2*M_PI + angle;
00057       return angle;
00058     }
00065     inline double wrapDeg(double angle)
00066     {
00067       angle = fmod(angle,360.);
00068       if (angle > 180) return -360. + angle;
00069       if (angle <= -180) return 360. + angle;
00070       return angle;
00071     }
00079     template <class type, typename precission>
00080     inline type coerce(type value, const Limit<precission>& limit)
00081     {
00082       if (value>limit.max) return limit.max;
00083       if (value<limit.min) return limit.min;
00084       return value;
00085     }
00094     template<class type>
00095     inline type coerce(type value, double min, double max)
00096     {
00097       if (value>max) return max;
00098       if (value<min) return min;
00099       return value;
00100     }
00109     template <class Iterator>
00110     inline double mean(const Iterator& first, const Iterator& last)
00111     {
00112         double sum(0);
00113         unsigned int size(0);
00114         for (Iterator cnt = first; cnt!=last; ++cnt,++size) sum += (*cnt);
00115         return (size)?(sum/size):0;
00116     }
00124     template <class Vector>
00125     inline double mean(const Vector& vec)
00126     {
00127         double sum(0);
00128         unsigned int size(0);
00129         for (typename Vector::const_iterator cnt = vec.begin(); cnt!=vec.end(); ++cnt,++size) sum += (*cnt);
00130         return (size)?(sum/size):0;
00131     }
00139     template<class Vector>
00140     inline double std2(const Vector& vec)
00141     {
00142       double sum(0),mean(labust::math::mean(vec));
00143       unsigned int size(0);
00144       for(typename Vector::const_iterator cnt = vec.begin(); cnt != vec.end(); ++cnt, ++size) sum+=std::pow(((*cnt) - mean),2);
00145       return size?std::sqrt(sum/size):-1;
00146     }
00147 
00157     template<class Vector>
00158     inline double std2(const Vector& vec, double mean)
00159     {
00160       double sum(0);
00161       unsigned int size(0);
00162       for(typename Vector::const_iterator cnt = vec.begin(); cnt != vec.end(); ++cnt, ++size) sum+=std::pow(((*cnt) - mean),2);
00163       return size?std::sqrt(sum/size):-1;
00164     }  
00165       
00171     struct unwrap
00172     {
00176         unwrap():anglek_1(0),index(0){};
00183         double operator()(double angle)
00184         {
00185                 double u = angle - this->anglek_1;
00186                 this->anglek_1=angle;
00187 
00188                 if (u<=-M_PI)
00189                 {
00190                         ++index;
00191                 }
00192                 else if (u>=M_PI) --index;
00193 
00194                 return this->index*2*M_PI + angle;
00195         }
00196 
00197     private:
00201         double anglek_1;
00205         int index;
00206     };
00207   }
00208 }
00209 /* NUMBERMANIPULATION_HPP_ */
00210 #endif


snippets
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:33