pose_graph.h
Go to the documentation of this file.
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 
00031 
00042 #ifndef POSE_GRAPH_POSE_GRAPH_H
00043 #define POSE_GRAPH_POSE_GRAPH_H
00044 
00045 #include "geometry.h"
00046 #include "ids.h"
00047 #include <occupancy_grid_utils/LocalizedCloud.h>
00048 #include <boost/scoped_ptr.hpp>
00049 #include <boost/optional.hpp>
00050 #include <set>
00051 #include <vector>
00052 
00053 namespace pose_graph {
00054 
00055 /************************************************************ 
00056  * Externally used defs (see also geometry.h and ids.h)
00057  ************************************************************/
00058 
00060 struct ShortestPathResult
00061 {
00063   bool path_found;
00064   
00066   std::vector<NodeId> nodes;
00067 
00069   std::vector<EdgeId> edges;
00070 
00072   double cost;
00073 };
00074 
00076 typedef std::map<NodeId, geometry_msgs::Pose> NodePoseMap;
00077 
00079 const std::string OPTIMIZED_FRAME("graph_optimization");
00080 
00081 
00082 
00083 /************************************************************
00084  * Main pose graph data structure
00085  ************************************************************/
00086 
00087 class PoseGraphImpl;
00088 
00089 class PoseGraph
00090 {
00091 public:
00092 
00093 
00094   /****************************************
00095    * Creation
00096    ****************************************/
00097   
00099   PoseGraph ();
00100 
00102   PoseGraph (const PoseGraph& g);
00103 
00105   PoseGraph& operator= (const PoseGraph& g);
00106 
00108   ~PoseGraph();
00109   
00110   
00111   /****************************************
00112    * Basic graph modification ops
00113    ****************************************/
00114 
00118   NodeId addNode ();
00119 
00123   void addNode (NodeId id);
00124 
00131   EdgeId addEdge (NodeId from, NodeId to, const PoseConstraint& constraint);
00132 
00140   void addEdge (NodeId from, NodeId to, const PoseConstraint& constraint, EdgeId id);
00141 
00144   void setInitialPoseEstimate (NodeId n, const geometry_msgs::Pose& pose);
00145 
00149   const geometry_msgs::Pose& getInitialPoseEstimate (NodeId n) const;
00150 
00151 
00152   /****************************************
00153    * Basic const ops
00154    ****************************************/
00155 
00157   std::set<NodeId> allNodes() const;
00158 
00160   std::set<EdgeId> allEdges() const;
00161 
00165   const PoseConstraint& getConstraint (EdgeId id) const;
00166 
00169   double edgeLength (EdgeId id) const;
00170 
00173   std::set<EdgeId> incidentEdges (NodeId n) const;
00174 
00177   std::pair<NodeId, NodeId> incidentNodes (EdgeId e) const;
00178 
00181   std::set<NodeId> neighbors (NodeId n) const;
00182 
00184   bool nodeIdExists (NodeId id) const;
00185 
00187   bool edgeIdExists (EdgeId id) const;
00188 
00194   PoseGraph subgraph (const std::set<NodeId>& nodes) const;
00195 
00201   geometry_msgs::Pose relativePose (NodeId n, NodeId ref) const;
00202 
00205   NodeId otherNode (const NodeId n, const EdgeId e) const;
00206 
00207 
00208   /****************************************
00209    * Graph search
00210    ****************************************/
00211 
00216   ShortestPathResult shortestPath(NodeId src, NodeId dest) const;
00217 
00223   std::set<NodeId> nearbyNodes (NodeId src, double radius) const;
00224 
00225 
00226   /****************************************
00227    * Sensor data attached to nodes
00228    ****************************************/
00229 
00233   void attachCloud (NodeId id, occupancy_grid_utils::LocalizedCloud::ConstPtr cloud);
00234 
00239   occupancy_grid_utils::LocalizedCloud::ConstPtr getCloud (NodeId id) const;
00240 
00243   bool hasCloud (NodeId id) const;
00244 
00253   void attachScan (NodeId id, sensor_msgs::LaserScan::ConstPtr cloud);
00254 
00261   sensor_msgs::LaserScan::ConstPtr getScan (NodeId id) const;
00262 
00265   bool hasScan (NodeId id) const;
00266 
00268   static std::string nodeFrameName (const NodeId id);
00269   
00270 private:
00271   
00272   boost::scoped_ptr<PoseGraphImpl> impl_;
00273 
00274 };
00275 
00276 
00277 } //namespace pose_graph
00278 
00279 
00280 #endif // POSE_GRAPH_POSE_GRAPH_H


pose_graph
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:15