GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Ordering.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 
21 #pragma once
22 
23 #include <gtsam/inference/Key.h>
26 #include <gtsam/base/FastSet.h>
27 
28 #ifdef GTSAM_USE_BOOST_FEATURES
29 #include <boost/assign/list_inserter.hpp>
30 #endif
31 
32 #include <algorithm>
33 #include <vector>
34 
35 namespace gtsam {
36 
37 class Ordering: public KeyVector {
38 protected:
39  typedef KeyVector Base;
40 
41 public:
42 
44  enum OrderingType {
45  COLAMD, METIS, NATURAL, CUSTOM
46  };
47 
48  typedef Ordering This;
49  typedef std::shared_ptr<This> shared_ptr;
50 
52  GTSAM_EXPORT
54  }
55 
56  using KeyVector::KeyVector; // Inherit the KeyVector's constructors
57 
59  template<typename KEYS>
60  explicit Ordering(const KEYS& keys) :
61  Base(keys.begin(), keys.end()) {
62  }
63 
64 #ifdef GTSAM_USE_BOOST_FEATURES
65  boost::assign::list_inserter<boost::assign_detail::call_push_back<This> > operator+=(
68  Key key) {
69  return boost::assign::make_list_inserter(
70  boost::assign_detail::call_push_back<This>(*this))(key);
71  }
72 #endif
73 
80  This& operator+=(KeyVector& keys);
81 
83  bool contains(const Key& key) const;
84 
92 
95 
99  template<class FACTOR_GRAPH>
100  static Ordering Colamd(const FACTOR_GRAPH& graph) {
101  if (graph.empty())
102  return Ordering();
103  else
104  return Colamd(VariableIndex(graph));
105  }
106 
108  static GTSAM_EXPORT Ordering Colamd(const VariableIndex& variableIndex);
109 
118  template<class FACTOR_GRAPH>
119  static Ordering ColamdConstrainedLast(const FACTOR_GRAPH& graph,
120  const KeyVector& constrainLast, bool forceOrder = false) {
121  if (graph.empty())
122  return Ordering();
123  else
124  return ColamdConstrainedLast(VariableIndex(graph), constrainLast, forceOrder);
125  }
126 
133  static GTSAM_EXPORT Ordering ColamdConstrainedLast(
134  const VariableIndex& variableIndex, const KeyVector& constrainLast,
135  bool forceOrder = false);
136 
145  template<class FACTOR_GRAPH>
146  static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH& graph,
147  const KeyVector& constrainFirst, bool forceOrder = false) {
148  if (graph.empty())
149  return Ordering();
150  else
151  return ColamdConstrainedFirst(VariableIndex(graph), constrainFirst, forceOrder);
152  }
153 
161  static GTSAM_EXPORT Ordering ColamdConstrainedFirst(
162  const VariableIndex& variableIndex,
163  const KeyVector& constrainFirst, bool forceOrder = false);
164 
174  template<class FACTOR_GRAPH>
175  static Ordering ColamdConstrained(const FACTOR_GRAPH& graph,
176  const FastMap<Key, int>& groups) {
177  if (graph.empty())
178  return Ordering();
179  else
180  return ColamdConstrained(VariableIndex(graph), groups);
181  }
182 
190  static GTSAM_EXPORT Ordering ColamdConstrained(
191  const VariableIndex& variableIndex, const FastMap<Key, int>& groups);
192 
194  template<class FACTOR_GRAPH>
195  static Ordering Natural(const FACTOR_GRAPH &fg) {
196  KeySet src = fg.keys();
197  KeyVector keys(src.begin(), src.end());
198  std::stable_sort(keys.begin(), keys.end());
199  return Ordering(keys.begin(), keys.end());
200  }
201 
203  template<class FACTOR_GRAPH>
204  static GTSAM_EXPORT void CSRFormat(std::vector<int>& xadj,
205  std::vector<int>& adj, const FACTOR_GRAPH& graph);
206 
208  static GTSAM_EXPORT Ordering Metis(const MetisIndex& met);
209 
210  template<class FACTOR_GRAPH>
211  static Ordering Metis(const FACTOR_GRAPH& graph) {
212  if (graph.empty())
213  return Ordering();
214  else
215  return Metis(MetisIndex(graph));
216  }
217 
219 
222 
223  template<class FACTOR_GRAPH>
224  static Ordering Create(OrderingType orderingType,
225  const FACTOR_GRAPH& graph) {
226  if (graph.empty())
227  return Ordering();
228 
229  switch (orderingType) {
230  case COLAMD:
231  return Colamd(graph);
232  case METIS:
233  return Metis(graph);
234  case NATURAL:
235  return Natural(graph);
236  case CUSTOM:
237  throw std::runtime_error(
238  "Ordering::Create error: called with CUSTOM ordering type.");
239  default:
240  throw std::runtime_error(
241  "Ordering::Create error: called with unknown ordering type.");
242  }
243  }
244 
246 
249 
250  GTSAM_EXPORT
251  void print(const std::string& str = "", const KeyFormatter& keyFormatter =
252  DefaultKeyFormatter) const;
253 
254  GTSAM_EXPORT
255  bool equals(const Ordering& other, double tol = 1e-9) const;
256 
258 
259 private:
261  static GTSAM_EXPORT Ordering ColamdConstrained(
262  const VariableIndex& variableIndex, std::vector<int>& cmember);
263 
264 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
265 
266  friend class boost::serialization::access;
267  template<class ARCHIVE>
268  void serialize(ARCHIVE & ar, const unsigned int version) {
269  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
270  }
271 #endif
272 };
273 
275 template<> struct traits<Ordering> : public Testable<Ordering> {
276 };
277 
278 }
279 
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: Testable.h:152
Definition: Group.h:43
Ordering(const KEYS &keys)
Create from a container.
Definition: Ordering.h:60
Definition: Ordering.h:37
static GTSAM_EXPORT void CSRFormat(std::vector< int > &xadj, std::vector< int > &adj, const FACTOR_GRAPH &graph)
METIS Formatting function.
GTSAM_EXPORT Ordering()
Create an empty ordering.
Definition: Ordering.h:53
static GTSAM_EXPORT Ordering Metis(const MetisIndex &met)
Compute an ordering determined by METIS from a VariableIndex.
static Ordering Colamd(const FACTOR_GRAPH &graph)
Definition: Ordering.h:100
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: Ordering.h:49
Definition: Testable.h:112
static Ordering ColamdConstrainedFirst(const FACTOR_GRAPH &graph, const KeyVector &constrainFirst, bool forceOrder=false)
Definition: Ordering.h:146
OrderingType
Type of ordering to use.
Definition: Ordering.h:44
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
Definition: MetisIndex.h:37
static Ordering ColamdConstrained(const FACTOR_GRAPH &graph, const FastMap< Key, int > &groups)
Definition: Ordering.h:175
Definition: chartTesting.h:28
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Definition: VariableIndex.h:41
bool contains(const Key &key) const
Check if key exists in ordering.
This & operator+=(KeyVector &keys)
Append new keys to the ordering as ordering += keys.
FastMap< Key, size_t > invert() const
Invert (not reverse) the ordering - returns a map from key to order position.
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH &graph, const KeyVector &constrainLast, bool forceOrder=false)
Definition: Ordering.h:119
A thin wrapper around std::set that uses boost&#39;s fast_pool_allocator.
static Ordering Natural(const FACTOR_GRAPH &fg)
Return a natural Ordering. Typically used by iterative solvers.
Definition: Ordering.h:195
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Ordering This
Typedef to this class.
Definition: Ordering.h:48