00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #include <pose_graph/graph_search.h>
00040 #include <pose_graph/exception.h>
00041 #include <graph_mapping_utils/general.h>
00042 #include <graph_mapping_utils/geometry.h>
00043 #include <boost/graph/connected_components.hpp>
00044 #include <boost/graph/dijkstra_shortest_paths.hpp>
00045 #include <list>
00046 #include <iostream>
00047
00048 namespace pose_graph
00049 {
00050
00051 namespace util=graph_mapping_utils;
00052 namespace msg=graph_mapping_msgs;
00053 using std::map;
00054 using std::pair;
00055 using std::list;
00056 using std::cout;
00057
00058 std::vector<NodeSet> connectedComponents (const ConstraintGraph& g)
00059 {
00060
00061 typedef std::map<GraphVertex, boost::default_color_type> ColorMap;
00062 ColorMap cmap;
00063 boost::associative_property_map<ColorMap> color_pmap(cmap);
00064
00065
00066 typedef std::map<GraphVertex, unsigned> ComponentMap;
00067 ComponentMap comp_map;
00068 boost::associative_property_map<ComponentMap> comp_pmap(comp_map);
00069
00070
00071 const Graph& graph = g.graph();
00072 const unsigned num_comps = connected_components(graph, comp_pmap, color_map(color_pmap));
00073
00074
00075 std::vector<NodeSet> comps(num_comps);
00076 BOOST_FOREACH (const ComponentMap::value_type& e, comp_map) {
00077 comps[e.second].insert(graph[e.first].id);
00078 }
00079 return comps;
00080 }
00081
00082 struct AllNodes
00083 {
00084 inline bool operator() (const GraphVertex v) const
00085 {
00086 return true;
00087 }
00088 };
00089
00090 NodeSet componentContaining (const ConstraintGraph& g, const unsigned n)
00091 {
00092 return filterNearbyNodes(g, n, AllNodes());
00093 }
00094
00095
00096
00097
00098
00099
00100
00101 typedef map<GraphVertex, double> DistanceMap;
00102 typedef map<GraphVertex, GraphVertex> PredecessorMap;
00103 typedef pair<DistanceMap, PredecessorMap> DijkstraResult;
00104
00105 DijkstraResult dijkstra (const Graph& g, const GraphVertex& src)
00106 {
00107
00108
00109 typedef map<GraphEdge, double> WeightMap;
00110 typedef map<GraphVertex, unsigned> IndexMap;
00111
00112
00113
00114 typedef boost::associative_property_map<DistanceMap> DistancePMap;
00115 typedef boost::associative_property_map<PredecessorMap> PredecessorPMap;
00116 typedef boost::associative_property_map<WeightMap> WeightPMap;
00117 typedef boost::associative_property_map<IndexMap> IndexPMap;
00118
00119
00120 IndexMap imap;
00121 IndexPMap index_pmap(imap);
00122 {
00123 unsigned ind=0;
00124 BOOST_FOREACH (const GraphVertex& v, vertices(g))
00125 imap[v] = ind++;
00126 }
00127
00128
00129 WeightMap wmap;
00130 WeightPMap weight_pmap(wmap);
00131 BOOST_FOREACH (const GraphEdge& e, edges(g))
00132 {
00133 const double l = util::length(g[e].constraint.constraint.pose.position);
00134 wmap[e] = l;
00135 }
00136
00137
00138 DistanceMap dmap;
00139 DistancePMap distance_pmap(dmap);
00140 PredecessorMap pmap;
00141 PredecessorPMap predecessor_pmap(pmap);
00142
00143
00144 boost::dijkstra_shortest_paths(g, src, weight_map(weight_pmap).vertex_index_map(index_pmap).
00145 distance_map(distance_pmap).predecessor_map(predecessor_pmap));
00146
00147
00148 return DijkstraResult(dmap, pmap);
00149 }
00150
00151
00152
00153
00154
00155
00156 ShortestPath shortestPath (const ConstraintGraph& g,
00157 const unsigned src, const unsigned dest)
00158 {
00159 typedef Graph::out_edge_iterator EdgeIter;
00160 const Graph& graph = g.graph();
00161
00162
00163 const GraphVertex v = g.idVertex(src);
00164 const GraphVertex w = g.idVertex(dest);
00165 const DijkstraResult res = dijkstra(graph, v);
00166
00167
00168 if (dest!=src && util::keyValue(res.second, w)==w)
00169 throw NoPathException(src, dest);
00170
00171
00172 list<unsigned> path;
00173 for (GraphVertex x=w; x!=util::keyValue(res.second, x);
00174 x=util::keyValue(res.second, x))
00175 path.push_front(graph[x].id);
00176 path.push_front(src);
00177 ShortestPath ret;
00178 copy(path.begin(), path.end(), back_inserter(ret.first));
00179
00180
00181
00182 for (unsigned i=0; i<ret.first.size()-1; i++)
00183 {
00184 const unsigned from = ret.first[i];
00185 const unsigned to = ret.first[i+1];
00186 pair<GraphEdge, bool> e = edge(g.idVertex(from), g.idVertex(to), graph);
00187 ROS_ASSERT(e.second);
00188 ret.second.push_back(graph[e.first].id);
00189 }
00190
00191 return ret;
00192 }
00193
00194
00195 tf::Pose relativePose (const ConstraintGraph& g, const unsigned n1,
00196 const unsigned n2)
00197 {
00198 const Graph& graph = g.graph();
00199 ShortestPath path = shortestPath(g, n1, n2);
00200 tf::Pose p;
00201 p.setIdentity();
00202 BOOST_FOREACH (const unsigned e, path.second)
00203 p *= util::toPose(graph[g.idEdge(e)].constraint.constraint.pose);
00204 return p;
00205 }
00206
00207
00208
00209 }