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 #ifndef POSE_GRAPH_GRAPH_SEARCH_H
00040 #define POSE_GRAPH_GRAPH_SEARCH_H
00041
00042 #include <pose_graph/constraint_graph.h>
00043 #include <graph_mapping_utils/ros.h>
00044
00045 namespace pose_graph
00046 {
00047
00051 template <class Predicate>
00052 NodeSet filterNearbyNodes (const ConstraintGraph& g, const unsigned n, const Predicate& p);
00053
00058 template <class NodePredicate, class EdgePredicate>
00059 NodeSet filterNearbyNodes (const ConstraintGraph& g, const unsigned n, const NodePredicate& node_pred,
00060 const EdgePredicate& edge_pred);
00061
00062
00063
00066 struct OptimizedDistancePredicate
00067 {
00070 OptimizedDistancePredicate (const ConstraintGraph& g,
00071 const btVector3& p, const double window_size) :
00072 g(&g.graph()), p(&p), squared_window_size(window_size * window_size)
00073 {}
00074
00075 OptimizedDistancePredicate () : g(NULL), p(NULL) {}
00076
00077 bool operator() (const GraphVertex v) const
00078 {
00079 if ((*g)[v].optimized_pose.size()==1) {
00080 const geometry_msgs::Point& pt = (*g)[v].optimized_pose[0].position;
00081 const double dx = p->x() - pt.x;
00082 const double dy = p->y() - pt.y;
00083 const double dz = p->z() - pt.z;
00084 ROS_DEBUG_NAMED ("optimized_distance", "Checking optimized distance "
00085 "between node %u at (%.2f, %.2f) and (%.2f, %.2f)",
00086 (unsigned) (*g)[v].id, pt.x, pt.y, p->x(), p->y());
00087 return (dx*dx + dy*dy + dz*dz < squared_window_size);
00088 }
00089 else {
00090 ROS_DEBUG_NAMED ("optimized_distance",
00091 "Node %u did not have an optimized pose", (*g)[v].id);
00092 return false;
00093 }
00094 }
00095
00096 const Graph* g;
00097 const btVector3* p;
00098 double squared_window_size;
00099 };
00100
00101
00103 struct AllEdges
00104 {
00105 bool operator() (const GraphEdge&) const { return true; }
00106 };
00107
00108
00111 std::vector<NodeSet>
00112 connectedComponents (const ConstraintGraph& g);
00113
00115 NodeSet componentContaining (const ConstraintGraph& g, unsigned n);
00116
00117
00118 typedef std::pair<std::vector<unsigned>, std::vector<unsigned> > ShortestPath;
00119
00124 ShortestPath shortestPath (const ConstraintGraph& g,
00125 const unsigned src, const unsigned dest);
00126
00130 tf::Pose relativePose (const ConstraintGraph& g,
00131 const unsigned n1, const unsigned n2);
00132
00133
00134
00135 }
00136
00137 #include "../../src/graph_search_impl.h"
00138
00139 #endif // include guard