graph.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 <map>
22 
23 #define BOOST_NO_HASH // to pacify the warnings about depricated headers in boost.graph
24 
25 #include <boost/graph/graph_traits.hpp>
26 #include <boost/graph/adjacency_list.hpp>
27 #include <boost/shared_ptr.hpp>
28 #include <gtsam/nonlinear/Values.h>
29 
30 namespace gtsam {
31 
32  // type definitions :
33 
37  template<class KEY>
38  class SDGraph: public boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS,
39  boost::property<boost::vertex_name_t, KEY>, boost::property<
40  boost::edge_weight_t, double> > {
41  public:
42  typedef typename boost::graph_traits<SDGraph<KEY> >::vertex_descriptor Vertex;
43  };
44 
45  template<class KEY>
46  class SGraph : public boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS,
47  boost::property<boost::vertex_name_t, KEY> > {
48  public:
49  typedef typename boost::graph_traits<SGraph<KEY> >::vertex_descriptor Vertex;
50  };
51 
52  //typedef boost::graph_traits<SGraph>::vertex_descriptor SVertex;
53 
57  template<class KEY>
58  class PredecessorMap: public std::map<KEY, KEY> {
59  public:
61  inline void insert(const KEY& key, const KEY& parent) {
62  std::map<KEY, KEY>::insert(std::make_pair(key, parent));
63  }
64  };
65 
69  template<class KEY>
70  std::list<KEY> predecessorMap2Keys(const PredecessorMap<KEY>& p_map);
71 
78  template<class G, class F, class KEY> SDGraph<KEY> toBoostGraph(const G& graph);
79 
85  template<class G, class V, class KEY>
86  boost::tuple<G, V, std::map<KEY,V> > predecessorMap2Graph(const PredecessorMap<KEY>& p_map);
87 
91  template<class G, class Factor, class POSE, class KEY>
92  boost::shared_ptr<Values>
93  composePoses(const G& graph, const PredecessorMap<KEY>& tree, const POSE& rootPose);
94 
95 
99  template<class G, class KEY, class FACTOR2>
101 
106  template<class G, class KEY, class FACTOR2>
107  void split(const G& g, const PredecessorMap<KEY>& tree, G& Ab1, G& Ab2) ;
108 
109 
110 } // namespace gtsam
111 
void insert(const KEY &key, const KEY &parent)
Definition: graph.h:61
A insert(1, 2)=0
A non-templated config holding any types of Manifold-group elements.
JacobiRotation< float > G
boost::shared_ptr< Values > composePoses(const G &graph, const PredecessorMap< KEY > &tree, const POSE &rootPose)
Definition: graph-inl.h:174
NonlinearFactorGraph graph
void g(const string &key, int i)
Definition: testBTree.cpp:43
void split(const G &g, const PredecessorMap< KEY > &tree, G &Ab1, G &Ab2)
Definition: graph-inl.h:255
boost::graph_traits< SDGraph< KEY > >::vertex_descriptor Vertex
Definition: graph.h:42
SDGraph< KEY > toBoostGraph(const G &graph)
Definition: graph-inl.h:68
traits
Definition: chartTesting.h:28
boost::tuple< G, V, std::map< KEY, V > > predecessorMap2Graph(const PredecessorMap< KEY > &p_map)
Definition: graph-inl.h:118
boost::graph_traits< SGraph< KEY > >::vertex_descriptor Vertex
Definition: graph.h:49
PredecessorMap< KEY > findMinimumSpanningTree(const G &fg)
Definition: graph-inl.h:232
std::list< KEY > predecessorMap2Keys(const PredecessorMap< KEY > &p_map)
Definition: graph-inl.h:50


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:09