00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00040 #ifndef POSE_GRAPH_CONSTRAINT_GRAPH_H 00041 #define POSE_GRAPH_CONSTRAINT_GRAPH_H 00042 00043 #include <graph_mapping_msgs/Node.h> 00044 #include <graph_mapping_msgs/Edge.h> 00045 00046 #include <tf/transform_datatypes.h> 00047 00048 #define BOOST_NO_HASH 00049 #include <boost/graph/adjacency_list.hpp> 00050 #include <boost/graph/graph_traits.hpp> 00051 00052 namespace pose_graph 00053 { 00054 00055 namespace msg=graph_mapping_msgs; 00056 using msg::PoseWithPrecision; 00057 00058 00059 /************************************************************ 00060 * Definition of underlying boost graph 00061 ***********************************************************/ 00062 00063 typedef boost::adjacency_list<boost::multisetS, boost::listS, boost::undirectedS, msg::Node, msg::Edge> Graph; 00064 typedef boost::graph_traits<Graph>::edge_descriptor GraphEdge; 00065 typedef boost::graph_traits<Graph>::vertex_descriptor GraphVertex; 00066 00067 00068 /************************************************************ 00069 * Other useful definitions 00070 ***********************************************************/ 00071 00072 typedef std::map<unsigned, tf::Pose> NodePoseMap; 00073 typedef std::set<unsigned> NodeSet; 00074 typedef std::set<unsigned> EdgeSet; 00075 00076 /*********************************************************//* 00077 * Represents a graph where nodes represent poses, 00078 * edges represent constraints between them. Nodes and edges 00079 * have (independent) ids which are unsigned integers, and 00080 * edges have associated constraints, which consist of a 00081 * relative pose (of the destination w.r.t the source), and 00082 * precision matrix. 00083 * 00084 * Represents the actual graph using a boost graph library 00085 * adjacency_list. You can use (non-modifying) algorithms from 00086 * the BGL on the underlying graph. Get the graph using the 00087 * graph method, and convert node/edge ids to BGL descriptors 00088 * using idVertex and idEdge. 00089 ***********************************************************/ 00090 class ConstraintGraph 00091 { 00092 public: 00093 00094 /**************************************** 00095 * Construction 00096 ****************************************/ 00097 00099 ConstraintGraph (); 00100 00102 ConstraintGraph (const ConstraintGraph& g); 00103 00105 virtual ConstraintGraph& operator= (const ConstraintGraph& g); 00106 00108 virtual ~ConstraintGraph (); 00109 00110 /**************************************** 00111 * Basic modification 00112 ****************************************/ 00113 00115 unsigned addNode (); 00116 00119 void addNode (unsigned id); 00120 00122 unsigned addEdge (unsigned from, unsigned t, const PoseWithPrecision& constraint); 00123 00126 void addEdge (unsigned id, unsigned from, unsigned t, const PoseWithPrecision& constraint); 00127 00128 00129 /**************************************** 00130 * Basic const ops 00131 ****************************************/ 00132 00134 NodeSet allNodes() const; 00135 00137 EdgeSet allEdges() const; 00138 00141 EdgeSet incidentEdges (unsigned n) const; 00142 00145 std::pair<unsigned, unsigned> incidentNodes (unsigned e) const; 00146 00149 const PoseWithPrecision& getConstraint (unsigned e) const; 00150 00152 bool nodeIdExists (unsigned n) const; 00153 00155 bool edgeIdExists (unsigned e) const; 00156 00157 00158 /**************************************** 00159 * Ops on underlying graph 00160 ****************************************/ 00161 00166 const Graph& graph () const; 00167 00170 GraphVertex idVertex (unsigned n) const; 00171 00173 GraphEdge idEdge (unsigned e) const; 00174 00175 /**************************************** 00176 * Optimized poses 00177 ****************************************/ 00178 00182 tf::Pose getOptimizedPose (unsigned n) const; 00183 00186 bool hasOptimizedPose (unsigned n) const; 00187 00192 void setOptimizedPose (unsigned n, const tf::Pose& pose); 00193 00196 void setOptimizedPoses (const NodePoseMap& poses); 00197 00198 private: 00199 00200 /**************************************** 00201 * Modifying utilities 00202 ****************************************/ 00203 00204 void initializeFrom (const ConstraintGraph& other); 00205 00206 unsigned next_node_id_; 00207 unsigned next_edge_id_; 00208 std::map<unsigned, GraphVertex> vertex_map_; 00209 std::map<unsigned, GraphEdge> edge_map_; 00210 Graph graph_; 00211 }; 00212 00213 } // namespace 00214 00215 #endif // include guard