Main MRPT website > C++ reference for MRPT 1.5.6
ts_hash_map.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #pragma once
10 
12 #include <mrpt/utils/mrpt_macros.h>
14 #include <mrpt/utils/CArray.h>
15 
16 namespace mrpt
17 {
18  namespace utils
19  {
20  template <typename KEY,typename VALUE >
21  struct ts_map_entry {
22  bool used;
23  KEY first;
24  VALUE second;
25  ts_map_entry() : used(false), first( KEY() ), second() {}
26  };
27 
28  void BASE_IMPEXP reduced_hash(const std::string &value, uint8_t &hash); //!< hash function used by ts_hash_map. Uses dbj2 method
29  void BASE_IMPEXP reduced_hash(const std::string &value, uint16_t &hash); //!< hash function used by ts_hash_map. Uses dbj2 method
30  void BASE_IMPEXP reduced_hash(const std::string &value, uint32_t &hash); //!< hash function used by ts_hash_map. Uses dbj2 method
31  void BASE_IMPEXP reduced_hash(const std::string &value, uint64_t &hash); //!< hash function used by ts_hash_map. Uses dbj2 method
32 
33  /** A thread-safe (ts) container which minimally emulates a std::map<>'s [] and find() methods but which is implemented as a linear vector indexed by a hash of KEY.
34  * Any custom hash function can be implemented, we don't rely by default on C++11 std::hash<> due to its limitation in some implementations.
35  *
36  * This implementation is much more efficient than std::map<> when the most common operation is accesing elements
37  * by KEY with find() or [], and is also thread-safe if different threads create entries with different hash values.
38  *
39  * The default underlying non-associative container is a "memory-aligned std::vector<>", but it can be changed to a
40  * standard vector<> or to a deque<> (to avoid memory reallocations) by changing the template parameter \a VECTOR_T.
41  *
42  * \note Defined in #include <mrpt/utils/ts_hash_map.h>
43  * \ingroup stlext_grp
44  */
45  template <
46  typename KEY,
47  typename VALUE,
48  unsigned int NUM_BYTES_HASH_TABLE = 1,
49  unsigned int NUM_HAS_TABLE_COLLISIONS_ALLOWED = 5,
50  typename VECTOR_T = mrpt::utils::CArray< mrpt::utils::CArray<ts_map_entry<KEY,VALUE>, NUM_HAS_TABLE_COLLISIONS_ALLOWED>, 1u << (8*NUM_BYTES_HASH_TABLE)>
51  >
52  class ts_hash_map
53  {
54  public:
55  /** @name Types
56  @{ */
57  typedef ts_hash_map<KEY, VALUE, NUM_BYTES_HASH_TABLE, NUM_HAS_TABLE_COLLISIONS_ALLOWED, VECTOR_T> self_t;
58  typedef KEY key_type;
59  typedef ts_map_entry<KEY,VALUE> value_type;
60  typedef VECTOR_T vec_t;
61 
62  struct iterator;
63  struct const_iterator
64  {
65  public:
66  const_iterator() : m_vec(NULL), m_parent(NULL), m_idx_outer(0), m_idx_inner(0) {}
67  const_iterator(const VECTOR_T &vec, const self_t &parent, int idx_outer, int idx_inner) : m_vec(const_cast<VECTOR_T*>(&vec)), m_parent(const_cast<self_t*>(&parent)), m_idx_outer(idx_outer), m_idx_inner(idx_inner) {}
68  const_iterator & operator = (const const_iterator& o) { m_vec = o.m_vec; m_idx_outer = o.m_idx_outer; m_idx_inner = o.m_idx_inner; return *this; }
69  bool operator == (const const_iterator& o) const { return m_vec == o.m_vec && m_idx_outer == o.m_idx_outer && m_idx_inner == o.m_idx_inner; }
70  bool operator != (const const_iterator& o) const { return !(*this==o); }
71  const value_type & operator *() const { return (*m_vec)[m_idx_outer][m_idx_inner]; }
72  const value_type * operator ->() const { return &(*m_vec)[m_idx_outer][m_idx_inner]; }
73  inline const_iterator operator ++(int) { /* Post: it++ */ const_iterator aux = *this; ++(*this); return aux; }
74  inline const_iterator& operator ++() { /* pre: ++it */ incr(); return *this; }
75  protected:
76  VECTOR_T *m_vec;
77  self_t *m_parent;
78  int m_idx_outer, m_idx_inner;
79  void incr() {
80  // This loop ends with the first used entry in the nested arrays, or an iterator pointing to "end()".
81  do {
82  if (++m_idx_inner >= (int)NUM_HAS_TABLE_COLLISIONS_ALLOWED) {
83  m_idx_inner = 0;
84  m_idx_outer++;
85  }
86  } while (m_idx_outer<(int)m_parent->m_vec.size() && !(*m_vec)[m_idx_outer][m_idx_inner].used);
87  }
88  };
89 
90  struct iterator : public const_iterator
91  {
92  public:
93  iterator() : const_iterator() {}
94  iterator(VECTOR_T &vec, self_t &parent, int idx_outer, int idx_inner) : const_iterator(vec,parent,idx_outer,idx_inner) {}
95  value_type & operator *() { return (*const_iterator::m_vec)[const_iterator::m_idx_outer][const_iterator::m_idx_inner]; }
96  value_type * operator ->() { return &(*const_iterator::m_vec)[const_iterator::m_idx_outer][const_iterator::m_idx_inner]; }
97  inline iterator operator ++(int) { /* Post: it++ */ iterator aux = *this; ++(*this); return aux; }
98  inline iterator& operator ++() { /* pre: ++it */ const_iterator::incr(); return *this; }
99  };
100  /** @} */
101  private:
102  vec_t m_vec; //!< The actual container
103  size_t m_size; //!< Number of elements accessed with write access so far
104 
105  public:
106  /** @name Constructors, read/write access and other operations
107  @{ */
108  //!< Default constructor */
110  {
111  }
112  /** Clear the contents of this container */
113  void clear() {
114  m_size = 0;
115  for (size_t oi = 0; oi < m_vec.size(); oi++)
116  for (size_t ii = 0; ii < NUM_HAS_TABLE_COLLISIONS_ALLOWED; ii++)
117  m_vec[oi][ii] = value_type();
118  }
119 
120  bool empty() const { return m_size == 0; }
121 
122  /** Write/read via [i] operator, that creates an element if it didn't exist already. */
123  VALUE & operator [](const KEY &key) {
125  reduced_hash(key, hash);
126  mrpt::utils::CArray<ts_map_entry<KEY, VALUE>,NUM_HAS_TABLE_COLLISIONS_ALLOWED> & match_arr = m_vec[hash];
127  for (unsigned int i = 0; i < NUM_HAS_TABLE_COLLISIONS_ALLOWED; i++)
128  {
129  if (!match_arr[i].used) {
130  m_size++;
131  match_arr[i].used = true;
132  match_arr[i].first = key;
133  return match_arr[i].second;
134  }
135  if (match_arr[i].first == key) return match_arr[i].second;
136  }
137  THROW_EXCEPTION("ts_hash_map: too many hash collisions!");
138  }
139  const_iterator find(const KEY &key) const {
141  reduced_hash(key, hash);
142  const mrpt::utils::CArray<ts_map_entry<KEY, VALUE>, NUM_HAS_TABLE_COLLISIONS_ALLOWED> & match_arr = m_vec[hash];
143  for (unsigned int i = 0; i < NUM_HAS_TABLE_COLLISIONS_ALLOWED; i++)
144  {
145  if (match_arr[i].used && match_arr[i].first == key)
146  return const_iterator(m_vec,*this, hash,i);
147  }
148  return this->end();
149  }
150 
151  const_iterator begin() const { const_iterator it(m_vec, *this, 0, -1); ++it; return it; }
152  const_iterator end() const { return const_iterator(m_vec, *this, m_vec.size(), 0); }
153  iterator begin() { iterator it(m_vec, *this, 0, -1); ++it; return it; }
154  iterator end() { return iterator(m_vec, *this, m_vec.size(), 0); }
155 
156  /** @} */
157 
158  }; // end class ts_hash_map
159 
160  } // End of namespace
161 } // End of namespace
const_iterator end() const
Definition: ts_hash_map.h:152
bool operator!=(const CArray< T, N > &x, const CArray< T, N > &y)
Definition: CArray.h:285
unsigned __int16 uint16_t
Definition: rptypes.h:46
KEY first
Definition: ts_hash_map.h:23
ts_hash_map()
< Default constructor */
Definition: ts_hash_map.h:109
iterator operator++(int)
A thread-safe (ts) container which minimally emulates a std::map<>&#39;s [] and find() methods but which ...
Definition: ts_hash_map.h:97
GLint * first
Definition: glext.h:3703
#define THROW_EXCEPTION(msg)
const_iterator begin() const
Definition: ts_hash_map.h:151
Scalar * iterator
Definition: eigen_plugins.h:23
Usage: uint_select_by_bytecount<N>type var; allows defining var as a unsigned integer with...
const Scalar * const_iterator
Definition: eigen_plugins.h:24
const_iterator find(const KEY &key) const
Definition: ts_hash_map.h:139
Definition: ts_hash_map.h:21
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:113
unsigned char uint8_t
Definition: rptypes.h:43
A STL container (as wrapper) for arrays of constant size defined at compile time. ...
Definition: CArray.h:53
VALUE & operator[](const KEY &key)
Write/read via [i] operator, that creates an element if it didn&#39;t exist already.
Definition: ts_hash_map.h:123
VALUE second
Definition: ts_hash_map.h:24
bool empty() const
Definition: ts_hash_map.h:120
GLsizei const GLchar ** string
Definition: glext.h:3919
void BASE_IMPEXP reduced_hash(const std::string &value, uint8_t &hash)
hash function used by ts_hash_map. Uses dbj2 method
Definition: ts_hash_map.cpp:27
size_t m_size
Number of elements accessed with write access so far.
Definition: ts_hash_map.h:103
vec_t m_vec
The actual container.
Definition: ts_hash_map.h:99
unsigned __int64 uint64_t
Definition: rptypes.h:52
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
ts_map_entry()
Definition: ts_hash_map.h:25
bool operator==(const CArray< T, N > &x, const CArray< T, N > &y)
Definition: CArray.h:277
GLsizei const GLfloat * value
Definition: glext.h:3929
unsigned __int32 uint32_t
Definition: rptypes.h:49
bool used
Definition: ts_hash_map.h:22
std::vector< T1 > operator*(const std::vector< T1 > &a, const std::vector< T2 > &b)
a*b (element-wise multiplication)
Definition: ops_vectors.h:59



Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019