VariableIndex.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 
18 #pragma once
19 
20 #include <gtsam/inference/Factor.h>
21 #include <gtsam/inference/Key.h>
22 #include <gtsam/base/FastMap.h>
23 #include <gtsam/base/FastVector.h>
24 #include <gtsam/dllexport.h>
25 
26 #include <cassert>
27 #include <stdexcept>
28 #include <optional>
29 
30 namespace gtsam {
31 
41 class GTSAM_EXPORT VariableIndex {
42  public:
43  typedef std::shared_ptr<VariableIndex> shared_ptr;
44  typedef FactorIndices::iterator Factor_iterator;
45  typedef FactorIndices::const_iterator Factor_const_iterator;
46 
47  protected:
50  size_t nFactors_; // Number of factors in the original factor graph.
51  size_t nEntries_; // Sum of involved variable counts of each factor.
52 
53  public:
54  typedef KeyMap::const_iterator const_iterator;
55  typedef KeyMap::const_iterator iterator;
56  typedef KeyMap::value_type value_type;
57 
60 
62  VariableIndex() : nFactors_(0), nEntries_(0) {}
63 
68  template <class FG>
69  explicit VariableIndex(const FG& factorGraph) : nFactors_(0), nEntries_(0) {
70  augment(factorGraph);
71  }
72 
76 
78  size_t size() const { return index_.size(); }
79 
81  size_t nFactors() const { return nFactors_; }
82 
84  size_t nEntries() const { return nEntries_; }
85 
87  const FactorIndices& operator[](Key variable) const {
88  KeyMap::const_iterator item = index_.find(variable);
89  if(item == index_.end())
90  throw std::invalid_argument("Requested non-existent variable from VariableIndex");
91  else
92  return item->second;
93  }
94 
96  bool empty(Key variable) const {
97  return (*this)[variable].empty();
98  }
99 
103 
105  bool equals(const VariableIndex& other, double tol=0.0) const;
106 
108  void print(const std::string& str = "VariableIndex: ",
109  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
110 
115  void outputMetisFormat(std::ostream& os) const;
116 
117 
121 
126  template<class FG>
127  void augment(const FG& factors, const FactorIndices* newFactorIndices = nullptr);
128 
133  template<class FG>
134  void augment(const FG& factor, const FactorIndices& newFactorIndices) {
135  augment(factor, &newFactorIndices);
136  }
137 
143  void augmentExistingFactor(const FactorIndex factorIndex, const KeySet & newKeys);
144 
155  template<typename ITERATOR, class FG>
156  void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG& factors);
157 
159  template<typename ITERATOR>
160  void removeUnusedVariables(ITERATOR firstKey, ITERATOR lastKey);
161 
163  const_iterator begin() const { return index_.begin(); }
164 
166  const_iterator end() const { return index_.end(); }
167 
169  const_iterator find(Key key) const { return index_.find(key); }
170 
171 protected:
172  Factor_iterator factorsBegin(Key variable) { return internalAt(variable).begin(); }
173  Factor_iterator factorsEnd(Key variable) { return internalAt(variable).end(); }
174 
175  Factor_const_iterator factorsBegin(Key variable) const { return internalAt(variable).begin(); }
176  Factor_const_iterator factorsEnd(Key variable) const { return internalAt(variable).end(); }
177 
179  const FactorIndices& internalAt(Key variable) const {
180  const KeyMap::const_iterator item = index_.find(variable);
181  assert(item != index_.end());
182  return item->second;
183  }
184 
187  const KeyMap::iterator item = index_.find(variable);
188  assert(item != index_.end());
189  return item->second;
190  }
191 
192 private:
193 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
194 
195  friend class boost::serialization::access;
196  template<class ARCHIVE>
197  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
198  ar & BOOST_SERIALIZATION_NVP(index_);
199  ar & BOOST_SERIALIZATION_NVP(nFactors_);
200  ar & BOOST_SERIALIZATION_NVP(nEntries_);
201  }
202 #endif
203 
205 };
206 
208 template<>
209 struct traits<VariableIndex> : public Testable<VariableIndex> {
210 };
211 
212 } //\ namespace gtsam
213 
gtsam::VariableIndex::operator[]
const FactorIndices & operator[](Key variable) const
Access a list of factors by variable.
Definition: VariableIndex.h:87
gtsam::VariableIndex::find
const_iterator find(Key key) const
Find the iterator for the requested variable entry.
Definition: VariableIndex.h:169
gtsam::VariableIndex::const_iterator
KeyMap::const_iterator const_iterator
Definition: VariableIndex.h:54
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::FastMap< Key, FactorIndices >
gtsam::VariableIndex::factorsBegin
Factor_iterator factorsBegin(Key variable)
Definition: VariableIndex.h:172
gtsam::VariableIndex::factorsBegin
Factor_const_iterator factorsBegin(Key variable) const
Definition: VariableIndex.h:175
gtsam::VariableIndex::nEntries
size_t nEntries() const
The number of nonzero blocks, i.e. the number of variable-factor entries.
Definition: VariableIndex.h:84
gtsam::FastSet< Key >
gtsam::VariableIndex::iterator
KeyMap::const_iterator iterator
Definition: VariableIndex.h:55
gtsam::VariableIndex::Factor_const_iterator
FactorIndices::const_iterator Factor_const_iterator
Definition: VariableIndex.h:45
os
ofstream os("timeSchurFactors.csv")
Factor.h
The base class for all factors.
gtsam::VariableIndex::augment
void augment(const FG &factor, const FactorIndices &newFactorIndices)
Definition: VariableIndex.h:134
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
VariableIndex-inl.h
gtsam::VariableIndex::internalAt
const FactorIndices & internalAt(Key variable) const
Internal version of 'at' that asserts existence.
Definition: VariableIndex.h:179
gtsam::VariableIndex::internalAt
FactorIndices & internalAt(Key variable)
Internal version of 'at' that asserts existence.
Definition: VariableIndex.h:186
Key.h
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::VariableIndex::value_type
KeyMap::value_type value_type
Definition: VariableIndex.h:56
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::FactorIndex
std::uint64_t FactorIndex
Integer nonlinear factor index type.
Definition: types.h:100
gtsam::VariableIndex::factorsEnd
Factor_const_iterator factorsEnd(Key variable) const
Definition: VariableIndex.h:176
gtsam::VariableIndex::begin
const_iterator begin() const
Iterator to the first variable entry.
Definition: VariableIndex.h:163
gtsam::VariableIndex::VariableIndex
VariableIndex(const FG &factorGraph)
Definition: VariableIndex.h:69
gtsam::VariableIndex
Definition: VariableIndex.h:41
gtsam::VariableIndex::nFactors
size_t nFactors() const
The number of factors in the original factor graph.
Definition: VariableIndex.h:81
gtsam::equals
Definition: Testable.h:112
str
Definition: pytypes.h:1558
key
const gtsam::Symbol key('X', 0)
gtsam::VariableIndex::index_
KeyMap index_
Definition: VariableIndex.h:49
gtsam::VariableIndex::end
const_iterator end() const
Iterator to the first variable entry.
Definition: VariableIndex.h:166
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::VariableIndex::nFactors_
size_t nFactors_
Definition: VariableIndex.h:50
gtsam::VariableIndex::shared_ptr
std::shared_ptr< VariableIndex > shared_ptr
Definition: VariableIndex.h:43
gtsam::traits
Definition: Group.h:36
gtsam::VariableIndex::nEntries_
size_t nEntries_
Definition: VariableIndex.h:51
gtsam::VariableIndex::size
size_t size() const
The number of variable entries. This is equal to the number of unique variable Keys.
Definition: VariableIndex.h:78
gtsam::VariableIndex::VariableIndex
VariableIndex()
Default constructor, creates an empty VariableIndex.
Definition: VariableIndex.h:62
gtsam::VariableIndex::factorsEnd
Factor_iterator factorsEnd(Key variable)
Definition: VariableIndex.h:173
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::VariableIndex::KeyMap
FastMap< Key, FactorIndices > KeyMap
Definition: VariableIndex.h:48
gtsam::VariableIndex::empty
bool empty(Key variable) const
Return true if no factors associated with a variable.
Definition: VariableIndex.h:96
gtsam::VariableIndex::Factor_iterator
FactorIndices::iterator Factor_iterator
Definition: VariableIndex.h:44
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
FastMap.h
A thin wrapper around std::map that uses boost's fast_pool_allocator.
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:37


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:09:41