Histogram2D.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Fraunhofer FKIE
00003  *
00004  * Authors: Bastian Gaspers
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  *
00009  * * Redistributions of source code must retain the above copyright
00010  *   notice, this list of conditions and the following disclaimer.
00011  * * Redistributions in binary form must reproduce the above copyright
00012  *   notice, this list of conditions and the following disclaimer in the
00013  *   documentation and/or other materials provided with the distribution.
00014  * * Neither the name of the Fraunhofer FKIE nor the names of its
00015  *   contributors may be used to endorse or promote products derived from
00016  *   this software without specific prior written permission.
00017  *
00018  * This file is part of the StructureColoring ROS package.
00019  *
00020  * The StructureColoring ROS package is free software:
00021  * you can redistribute it and/or modify it under the terms of the
00022  * GNU Lesser General Public License as published by the Free
00023  * Software Foundation, either version 3 of the License, or
00024  * (at your option) any later version.
00025  *
00026  * The StructureColoring ROS package is distributed in the hope that it will be useful,
00027  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00028  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00029  * GNU Lesser General Public License for more details.
00030  *
00031  * You should have received a copy of the GNU Lesser General Public License
00032  * along with The StructureColoring ROS package.
00033  * If not, see <http://www.gnu.org/licenses/>.
00034  */
00035 
00036 #ifndef HISTOGRAM2D_H_
00037 #define HISTOGRAM2D_H_
00038 
00039 #include <functional>
00040 #include <algorithm>
00041 #include <vector>
00042 #include <utility>
00043 #include <structureColoring/histograms/OutOfRangeException.h>
00044 
00045 template<class Key, class Value, class BinType = Value>
00046 class Histogram2D {
00047 public:
00048         typedef OutOfRangeException OutOfRange;
00049         typedef std::pair<Key, Key> Keys;
00050 
00056         Histogram2D(const Key& minX, const Key& maxX, const Key& minY, const Key& maxY, const Key& binSize) :
00057                 mMinX(minX), mMaxX(maxX), mMinY(minY), mMaxY(maxY), mBinSize(binSize),
00058                 mXSpan(floor( (mMaxX - mMinX) / mBinSize ) + 1), mYSpan(floor( (mMaxY - mMinY) / mBinSize ) + 1),
00059                 mBins(mXSpan * mYSpan){
00060         }
00061 
00062         Histogram2D(const Keys& min, const Keys& max, const Key& binSize) :
00063                 mMinX(min.first), mMaxX(max.first), mMinY(min.second), mMaxY(max.second), mBinSize(binSize),
00064                 mXSpan(floor( (mMaxX - mMinX) / mBinSize ) + 1), mYSpan(floor( (mMaxY - mMinY) / mBinSize ) + 1),
00065                 mBins(mXSpan * mYSpan){
00066         }
00067 
00068         BinType& bin(const Key& x, const Key& y) { return mBins[getIdx(x, y)]; }
00069         const BinType& bin(const Key& x, const Key& y) const { return mBins[getIdx(x, y)]; }
00070         BinType& bin(const Keys& k) { return mBins[getIdx(k.first, k.second)]; }
00071         const BinType& bin(const Keys& k) const { return mBins[getIdx(k.first, k.second)]; }
00072 
00073         void addToBin(const Key& x, const Key& y, const Value& v) { mBins[getIdx(x, y)] += v; }
00074         void addToBin(const Keys& k, const Value& v) { mBins[getIdx(k.first, k.second)] += v; }
00075 
00076         void getMaxBin(BinType& bin, Key& x, Key& y) const {
00077                 Keys k;
00078                 getMaxBin(bin, k, std::less<BinType>());
00079                 x = k.first;
00080                 y = k.second;
00081 //              std::cout << "Histogram2D.getMaxBin(bin, x, y)" << std::endl;
00082         }
00083         void getMaxBin(BinType& bin, Keys& k) const { getMaxBin(bin, k, std::less<BinType>()); std::cout << "Histogram2D.getMaxBin(bin, k)" << std::endl;}
00084         template<class Comp>
00085         void getMaxBin(BinType& bin, Key& x, Key& y, Comp comp) const {
00086                 Keys k = std::make_pair(x, y);
00087                 getMaxBin(bin, k, comp);
00088                 x = k.first;
00089                 y = k.second;
00090 //              std::cout << "Histogram2D.getMaxBin(bin, x, y, comp)" << std::endl;
00091         }
00092         template<class Comp>
00093         void getMaxBin(BinType& bin, Keys& k, Comp comp) const;
00094 protected:
00095         typedef std::vector<BinType> Bins;
00096 
00097         size_t getIdx(const Key& x, const Key& y) const {
00098                 size_t xIdx, yIdx;
00099                 if ((x < mMinX) || (x > mMaxX) || (y < mMinY) || (y < mMaxY))
00100                         throw OutOfRange("key is out of range");
00101                 xIdx = (x - mMinX) / mBinSize;
00102                 yIdx = (y - mMinY) / mBinSize;
00103                 return xIdx + mXSpan * yIdx;
00104 //              if (x == mMaxX) xIdx = mXSpan;
00105 //              else xIdx = (x - mMinX) / mBinSize;
00106 //              if (y == mMaxY) yIdx = mYSpan;
00107 //              else yIdx = (y - mMinY) / mBinSize;
00108 //              return xIdx + mXSpan * yIdx;
00109         }
00110 
00111         size_t getIdx(const size_t& xIdx, const size_t& yIdx) const {
00112                 if ((xIdx > mXSpan) || (yIdx > mYSpan)){
00113                         throw OutOfRange("key is out of range");
00114                 }
00115                 return xIdx + mXSpan * yIdx;
00116         }
00117 
00118         Keys getKeys(const size_t& idx) const {
00119 
00120                 size_t yIdx = floor( ((float)idx) / ((float)mXSpan) );
00121                 size_t xIdx = idx - mXSpan * yIdx;
00122 
00123                 Key x( mMinX + ((float)xIdx) * mBinSize );
00124                 Key y( mMinY + ((float)yIdx) * mBinSize );
00125 
00126                 return std::make_pair(x, y);
00127         }
00128 
00129         Key mMinX, mMaxX, mMinY, mMaxY, mBinSize;
00130         unsigned int mXSpan, mYSpan;
00131         Bins mBins;
00132 };
00133 
00134 template<class Key, class Value, class BinType>
00135 template<class Comp>
00136 void Histogram2D<Key, Value, BinType>::getMaxBin(BinType& bin, Keys& k, Comp comp) const{
00137         typename Bins::const_iterator it = std::max_element(mBins.begin(), mBins.end(), comp);
00138         size_t idx = it - mBins.begin();
00139 //      std::cout << "index of max (2D Histogram): " << idx << std::endl;
00140         k = getKeys(idx);
00141 //      std::cout << "keys of max (2D Histogram): (" << k.first << ", " << k.second << ")" << std::endl;
00142         bin = *it;
00143 //      std::cout << "Histogram2D.getMaxBin(bin, k, comp)" << std::endl;
00144 }
00145 
00146 
00147 #endif /* HISTOGRAM2D_H_ */


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09