hash.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
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 Willow Garage, Inc. 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 FCL_HASH_H
00038 #define FCL_HASH_H
00039 
00040 #include <stdexcept>
00041 #include <set>
00042 #include <vector>
00043 #include <list>
00044 #include <boost/unordered_map.hpp>
00045 
00046 namespace fcl
00047 {
00048 
00050 template<typename Key, typename Data, typename HashFnc>
00051 class SimpleHashTable
00052 {
00053 protected:
00054   typedef std::list<Data> Bin;
00055 
00056   std::vector<Bin> table_;
00057 
00058   HashFnc h_;
00059 
00060   size_t table_size_;
00061 
00062 public:
00063   SimpleHashTable(const HashFnc& h) : h_(h)
00064   {
00065   }
00066 
00068   void init(size_t size)
00069   {
00070     if(size == 0) 
00071     {
00072       throw std::logic_error("SimpleHashTable must have non-zero size.");
00073     }
00074 
00075     table_.resize(size);
00076     table_size_ = size;
00077   }
00078 
00080   void insert(Key key, Data value)
00081   {
00082     std::vector<unsigned int> indices = h_(key);
00083     size_t range = table_.size();
00084     for(size_t i = 0; i < indices.size(); ++i)
00085       table_[indices[i] % range].push_back(value);
00086   }
00087 
00089   std::vector<Data> query(Key key) const
00090   {
00091     size_t range = table_.size();
00092     std::vector<unsigned int> indices = h_(key);
00093     std::set<Data> result;
00094     for(size_t i = 0; i < indices.size(); ++i)
00095     {
00096       unsigned int index = indices[i] % range;
00097       std::copy(table_[index].begin(), table_[index].end(), std::inserter(result, result.end()));
00098     }
00099 
00100     return std::vector<Data>(result.begin(), result.end());
00101   }
00102 
00104   void remove(Key key, Data value) 
00105   {
00106     size_t range = table_.size();
00107     std::vector<unsigned int> indices = h_(key);
00108     for(size_t i = 0; i < indices.size(); ++i)
00109     {
00110       unsigned int index = indices[i] % range;
00111       table_[index].remove(value);
00112     }
00113   }
00114 
00116   void clear() 
00117   {
00118     table_.clear();
00119     table_.resize(table_size_);
00120   }
00121 };
00122 
00123 
00124 template<typename U, typename V>
00125 class unordered_map_hash_table : public boost::unordered_map<U, V> {};
00126 
00128 template<typename Key, typename Data, typename HashFnc, template<typename, typename> class TableT = unordered_map_hash_table>
00129 class SparseHashTable
00130 {
00131 protected:
00132   HashFnc h_;
00133   typedef std::list<Data> Bin;
00134   typedef TableT<size_t, Bin> Table;
00135   
00136   Table table_;
00137 public:
00138   SparseHashTable(const HashFnc& h) : h_(h) {}
00139 
00141   void init(size_t) { table_.clear(); }
00142   
00144   void insert(Key key, Data value)
00145   {
00146     std::vector<unsigned int> indices = h_(key);
00147     for(size_t i = 0; i < indices.size(); ++i)
00148       table_[indices[i]].push_back(value);
00149   }
00150 
00152   std::vector<Data> query(Key key) const
00153   {
00154     std::vector<unsigned int> indices = h_(key);
00155     std::set<Data> result;
00156     for(size_t i = 0; i < indices.size(); ++i)
00157     {
00158       unsigned int index = indices[i];
00159       typename Table::const_iterator p = table_.find(index);
00160       if(p != table_.end())
00161         std::copy((*p).second.begin(), (*p).second.end(), std::inserter(result, result.end()));
00162     }
00163 
00164     return std::vector<Data>(result.begin(), result.end());
00165   }
00166 
00168   void remove(Key key, Data value)
00169   {
00170     std::vector<unsigned int> indices = h_(key);
00171     for(size_t i = 0; i < indices.size(); ++i)
00172     {
00173       unsigned int index = indices[i];
00174       table_[index].remove(value);
00175     }
00176   }
00177 
00179   void clear()
00180   {
00181     table_.clear();
00182   }
00183 };
00184 
00185 
00186 }
00187 
00188 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:30