MRPT  1.9.9
ts_hash_map.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/core/common.h> // remove MSVC warnings
13 #include <array>
14 #include <stdexcept>
15 #include <string_view>
16 
17 namespace mrpt::containers
18 {
19 template <typename KEY, typename VALUE>
21 {
22  bool used{false};
23  KEY first;
24  VALUE second;
25  ts_map_entry() = default;
26 };
27 
28 /** hash function used by ts_hash_map. Uses dbj2 method */
29 void reduced_hash(const std::string_view& value, uint8_t& hash);
30 void reduced_hash(const std::string_view& value, uint16_t& hash);
31 void reduced_hash(const std::string_view& value, uint32_t& hash);
32 void reduced_hash(const std::string_view& value, uint64_t& hash);
33 
34 /** A thread-safe (ts) container which minimally emulates a std::map<>'s [] and
35  * find() methods but which is implemented as a linear vector indexed by a hash
36  * of KEY.
37  * Any custom hash function can be implemented, we don't rely by default on
38  * C++11 std::hash<> due to its limitation in some implementations.
39  *
40  * This implementation is much more efficient than std::map<> when the most
41  * common operation is accesing elements
42  * by KEY with find() or [], and is also thread-safe if different threads
43  * create entries with different hash values.
44  *
45  * The default underlying non-associative container is a "memory-aligned
46  * std::vector<>", but it can be changed to a
47  * standard vector<> or to a deque<> (to avoid memory reallocations) by
48  * changing the template parameter \a VECTOR_T.
49  *
50  * \note Defined in #include <mrpt/containers/ts_hash_map.h>
51  * \ingroup mrpt_containers_grp
52  */
53 template <
54  typename KEY, typename VALUE, unsigned int NUM_BYTES_HASH_TABLE = 1,
55  unsigned int NUM_HAS_TABLE_COLLISIONS_ALLOWED = 5,
56  typename VECTOR_T = std::array<
57  std::array<ts_map_entry<KEY, VALUE>, NUM_HAS_TABLE_COLLISIONS_ALLOWED>,
58  1u << (8 * NUM_BYTES_HASH_TABLE)>>
59 class ts_hash_map
60 {
61  public:
62  /** @name Types
63  @{ */
64  using self_t = ts_hash_map<
65  KEY, VALUE, NUM_BYTES_HASH_TABLE, NUM_HAS_TABLE_COLLISIONS_ALLOWED,
66  VECTOR_T>;
67  using key_type = KEY;
68  using value_type = ts_map_entry<KEY, VALUE>;
69  using vec_t = VECTOR_T;
70 
71  struct iterator;
72  struct const_iterator
73  {
74  public:
75  const_iterator() : m_vec(nullptr), m_parent(nullptr) {}
76  const_iterator(
77  const VECTOR_T& vec, const self_t& parent, int idx_outer,
78  int idx_inner)
79  : m_vec(const_cast<VECTOR_T*>(&vec)),
80  m_parent(const_cast<self_t*>(&parent)),
81  m_idx_outer(idx_outer),
82  m_idx_inner(idx_inner)
83  {
84  }
85  const_iterator& operator=(const const_iterator& o)
86  {
87  m_vec = o.m_vec;
88  m_idx_outer = o.m_idx_outer;
89  m_idx_inner = o.m_idx_inner;
90  return *this;
91  }
92  bool operator==(const const_iterator& o) const
93  {
94  return m_vec == o.m_vec && m_idx_outer == o.m_idx_outer &&
95  m_idx_inner == o.m_idx_inner;
96  }
97  bool operator!=(const const_iterator& o) const { return !(*this == o); }
98  const value_type& operator*() const
99  {
100  return (*m_vec)[m_idx_outer][m_idx_inner];
101  }
102  const value_type* operator->() const
103  {
104  return &(*m_vec)[m_idx_outer][m_idx_inner];
105  }
106  inline const_iterator operator++(int)
107  { /* Post: it++ */
108  const_iterator aux = *this;
109  ++(*this);
110  return aux;
111  }
112  inline const_iterator& operator++()
113  { /* pre: ++it */
114  incr();
115  return *this;
116  }
117 
118  protected:
119  VECTOR_T* m_vec;
120  self_t* m_parent;
121  int m_idx_outer{0}, m_idx_inner{0};
122  void incr()
123  {
124  // This loop ends with the first used entry in the nested arrays, or
125  // an iterator pointing to "end()".
126  do
127  {
128  if (++m_idx_inner >=
129  static_cast<int>(NUM_HAS_TABLE_COLLISIONS_ALLOWED))
130  {
131  m_idx_inner = 0;
132  m_idx_outer++;
133  }
134  } while (m_idx_outer < static_cast<int>(m_parent->m_vec.size()) &&
135  !(*m_vec)[m_idx_outer][m_idx_inner].used);
136  }
137  };
138 
139  struct iterator : public const_iterator
140  {
141  public:
142  iterator() : const_iterator() {}
143  iterator(VECTOR_T& vec, self_t& parent, int idx_outer, int idx_inner)
144  : const_iterator(vec, parent, idx_outer, idx_inner)
145  {
146  }
147  value_type& operator*()
148  {
149  return (*const_iterator::m_vec)[const_iterator::m_idx_outer]
150  [const_iterator::m_idx_inner];
151  }
152  value_type* operator->()
153  {
154  return &(*const_iterator::m_vec)[const_iterator::m_idx_outer]
155  [const_iterator::m_idx_inner];
156  }
157  inline iterator operator++(int)
158  { /* Post: it++ */
159  iterator aux = *this;
160  ++(*this);
161  return aux;
162  }
163  inline iterator& operator++()
164  { /* pre: ++it */
165  const_iterator::incr();
166  return *this;
167  }
168  };
169  /** @} */
170  private:
171  /** The actual container */
172  vec_t m_vec;
173  /** Number of elements accessed with write access so far */
174  size_t m_size{0};
175 
176  public:
177  /** @name Constructors, read/write access and other operations
178  @{ */
179  //!< Default constructor */
180  ts_hash_map() = default;
181  /** Clear the contents of this container */
182  void clear()
183  {
184  m_size = 0;
185  for (size_t oi = 0; oi < m_vec.size(); oi++)
186  for (size_t ii = 0; ii < NUM_HAS_TABLE_COLLISIONS_ALLOWED; ii++)
187  m_vec[oi][ii] = value_type();
188  }
189 
190  bool empty() const { return m_size == 0; }
191  /** Write/read via [i] operator, that creates an element if it didn't exist
192  * already. */
193  VALUE& operator[](const KEY& key)
194  {
196  hash;
197  reduced_hash(key, hash);
198  std::array<ts_map_entry<KEY, VALUE>, NUM_HAS_TABLE_COLLISIONS_ALLOWED>&
199  match_arr = m_vec[hash];
200  for (unsigned int i = 0; i < NUM_HAS_TABLE_COLLISIONS_ALLOWED; i++)
201  {
202  if (!match_arr[i].used)
203  {
204  m_size++;
205  match_arr[i].used = true;
206  match_arr[i].first = key;
207  return match_arr[i].second;
208  }
209  if (match_arr[i].first == key) return match_arr[i].second;
210  }
211  throw std::runtime_error("ts_hash_map: too many hash collisions!");
212  }
213  const_iterator find(const KEY& key) const
214  {
216  hash;
217  reduced_hash(key, hash);
218  const std::array<
219  ts_map_entry<KEY, VALUE>, NUM_HAS_TABLE_COLLISIONS_ALLOWED>&
220  match_arr = m_vec[hash];
221  for (unsigned int i = 0; i < NUM_HAS_TABLE_COLLISIONS_ALLOWED; i++)
222  {
223  if (match_arr[i].used && match_arr[i].first == key)
224  return const_iterator(m_vec, *this, hash, i);
225  }
226  return this->end();
227  }
228 
229  const_iterator begin() const
230  {
231  const_iterator it(m_vec, *this, 0, -1);
232  ++it;
233  return it;
234  }
235  const_iterator end() const
236  {
237  return const_iterator(m_vec, *this, m_vec.size(), 0);
238  }
239  iterator begin()
240  {
241  iterator it(m_vec, *this, 0, -1);
242  ++it;
243  return it;
244  }
245  iterator end() { return iterator(m_vec, *this, m_vec.size(), 0); }
246  /** @} */
247 
248 }; // end class ts_hash_map
249 
250 } // namespace mrpt::containers
unsigned __int16 uint16_t
Definition: rptypes.h:47
const_iterator find(const KEY &key) const
Definition: ts_hash_map.h:213
GLint * first
Definition: glext.h:3833
VALUE second
Definition: ts_hash_map.h:24
ts_map_entry()=default
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:193
Usage: uint_select_by_bytecount<N>type var; allows defining var as a unsigned integer with...
unsigned char uint8_t
Definition: rptypes.h:44
void reduced_hash(const std::string_view &value, uint8_t &hash)
hash function used by ts_hash_map.
Definition: ts_hash_map.cpp:25
KEY first
Definition: ts_hash_map.h:23
ts_hash_map()=default
< Default constructor */
bool empty() const
Definition: ts_hash_map.h:190
bool operator==(const mrpt::img::TCamera &a, const mrpt::img::TCamera &b)
Definition: TCamera.cpp:202
unsigned __int64 uint64_t
Definition: rptypes.h:53
const_iterator end() const
Definition: ts_hash_map.h:235
const_iterator begin() const
Definition: ts_hash_map.h:229
bool used
Definition: ts_hash_map.h:22
vec_t m_vec
The actual container.
Definition: ts_hash_map.h:168
GLsizei const GLfloat * value
Definition: glext.h:4134
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:157
unsigned __int32 uint32_t
Definition: rptypes.h:50
bool operator!=(const mrpt::img::TCamera &a, const mrpt::img::TCamera &b)
Definition: TCamera.cpp:209
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:182
size_t m_size
Number of elements accessed with write access so far.
Definition: ts_hash_map.h:174
Definition: ts_hash_map.h:20
std::vector< T1 > operator*(const std::vector< T1 > &a, const std::vector< T2 > &b)
a*b (element-wise multiplication)
Definition: ops_vectors.h:50



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019