ConcurrentMap.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #pragma once
20 
21 #include <gtsam/global_includes.h>
22 
23 // Change class depending on whether we are using TBB
24 #ifdef GTSAM_USE_TBB
25 
26 // Include TBB header
27 # include <tbb/concurrent_unordered_map.h>
28 # undef min // TBB seems to include Windows.h which defines these macros that cause problems
29 # undef max
30 # undef ERROR
31 
32 #include <functional> // std::hash()
33 
34 // Use TBB concurrent_unordered_map for ConcurrentMap
35 template <typename KEY, typename VALUE>
36 using ConcurrentMapBase = tbb::concurrent_unordered_map<
37  KEY,
38  VALUE,
39  std::hash<KEY>
40  >;
41 
42 #else
43 
44 // If we're not using TBB, use a FastMap for ConcurrentMap
45 #include <gtsam/base/FastMap.h>
46 template <typename KEY, typename VALUE>
48 
49 #endif
50 
51 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
52 #include <boost/serialization/nvp.hpp>
53 #include <boost/serialization/split_member.hpp>
54 #endif
55 
56 #include <gtsam/base/FastVector.h>
57 
58 namespace gtsam {
59 
68 template<typename KEY, typename VALUE>
69 class ConcurrentMap : public ConcurrentMapBase<KEY,VALUE> {
70 
71 public:
72 
74 
77 
79  template<typename INPUTITERATOR>
80  ConcurrentMap(INPUTITERATOR first, INPUTITERATOR last) : Base(first, last) {}
81 
84 
86  ConcurrentMap(const Base& x) : Base(x) {}
87 
89  bool exists(const KEY& e) const { return this->count(e); }
90 
91 #ifndef GTSAM_USE_TBB
92  // If we're not using TBB and this is actually a FastMap, we need to add these functions and hide
93  // the original erase functions.
94  void unsafe_erase(typename Base::iterator position) { ((Base*)this)->erase(position); }
95  typename Base::size_type unsafe_erase(const KEY& k) { return ((Base*)this)->erase(k); }
96  void unsafe_erase(typename Base::iterator first, typename Base::iterator last) {
97  return ((Base*)this)->erase(first, last); }
98 private:
99  void erase() {}
100 public:
101 #endif
102 
103 private:
104 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
105 
106  friend class boost::serialization::access;
107  template<class Archive>
108  void save(Archive& ar, const unsigned int /*version*/) const
109  {
110  // Copy to an STL container and serialize that
111  FastVector<std::pair<KEY, VALUE> > map(this->size());
112  std::copy(this->begin(), this->end(), map.begin());
113  ar & BOOST_SERIALIZATION_NVP(map);
114  }
115  template<class Archive>
116  void load(Archive& ar, const unsigned int /*version*/)
117  {
118  this->clear();
119  // Load into STL container and then fill our map
120  FastVector<std::pair<KEY, VALUE> > map;
121  ar & BOOST_SERIALIZATION_NVP(map);
122  this->insert(map.begin(), map.end());
123  }
124  BOOST_SERIALIZATION_SPLIT_MEMBER()
125 #endif
126 };
127 
128 }
gtsam::ConcurrentMap::Base
ConcurrentMapBase< KEY, VALUE > Base
Definition: ConcurrentMap.h:73
gtsam::ConcurrentMap
Definition: ConcurrentMap.h:69
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
global_includes.h
Included from all GTSAM files.
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::position
Point3_ position(const NavState_ &X)
Definition: navigation/expressions.h:37
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::FastMap
Definition: FastMap.h:39
Eigen::last
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
Definition: IndexedViewHelper.h:38
gtsam::ConcurrentMap::exists
bool exists(const KEY &e) const
Definition: ConcurrentMap.h:89
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
Eigen::internal::VALUE
@ VALUE
Definition: SpecialFunctionsImpl.h:729
gtsam::ConcurrentMap::ConcurrentMap
ConcurrentMap(INPUTITERATOR first, INPUTITERATOR last)
Definition: ConcurrentMap.h:80
gtsam::ConcurrentMap::unsafe_erase
void unsafe_erase(typename Base::iterator first, typename Base::iterator last)
Definition: ConcurrentMap.h:96
gtsam::ConcurrentMap::erase
void erase()
Definition: ConcurrentMap.h:99
gtsam::ConcurrentMap::ConcurrentMap
ConcurrentMap(const ConcurrentMap< KEY, VALUE > &x)
Definition: ConcurrentMap.h:83
gtsam::ConcurrentMap::unsafe_erase
void unsafe_erase(typename Base::iterator position)
Definition: ConcurrentMap.h:94
test_KarcherMeanFactor.KEY
int KEY
Definition: test_KarcherMeanFactor.py:22
gtsam::ConcurrentMap::ConcurrentMap
ConcurrentMap()
Definition: ConcurrentMap.h:76
gtsam::ConcurrentMap::ConcurrentMap
ConcurrentMap(const Base &x)
Definition: ConcurrentMap.h:86
gtsam::save
void save(const Matrix &A, const string &s, const string &filename)
Definition: Matrix.cpp:166
gtsam
traits
Definition: chartTesting.h:28
gtsam::ConcurrentMap::unsafe_erase
Base::size_type unsafe_erase(const KEY &k)
Definition: ConcurrentMap.h:95
Eigen::placeholders::end
static const EIGEN_DEPRECATED end_t end
Definition: IndexedViewHelper.h:181
Base
Definition: test_virtual_functions.cpp:156
insert
A insert(1, 2)=0
FastMap.h
A thin wrapper around std::map that uses boost's fast_pool_allocator.


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:01:20