roadmap.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 
00039 #ifndef TOPOLOGICAL_ROADMAP_ROADMAP_H
00040 #define TOPOLOGICAL_ROADMAP_ROADMAP_H
00041 
00042 #include <topological_map_2d/topological_map.h>
00043 #include <topological_nav_msgs/RoadmapNode.h>
00044 #include <topological_nav_msgs/RoadmapEdge.h>
00045 
00046 namespace topological_roadmap
00047 {
00048 
00049 namespace msg=topological_nav_msgs;
00050 
00051 /************************************************************
00052  * Underlying boost graph typedefs
00053  ***********************************************************/
00054 
00055 typedef boost::adjacency_list<boost::multisetS, boost::listS, boost::undirectedS,
00056                               msg::RoadmapNode, msg::RoadmapEdge> Graph;
00057 typedef boost::graph_traits<Graph>::edge_descriptor GraphEdge;
00058 typedef boost::graph_traits<Graph>::vertex_descriptor GraphVertex;
00059 
00060 /************************************************************
00061  * Class def
00062  ***********************************************************/
00063 
00077 class Roadmap : public Graph
00078 {
00079 public:
00080 
00081   typedef msg::RoadmapNode NodeInfo;
00082   typedef msg::RoadmapEdge EdgeInfo;
00083   typedef std::set<unsigned> Nodes;
00084 
00086   Roadmap ();
00087 
00089   Roadmap (const Roadmap& r);
00090 
00092   Roadmap& operator= (const Roadmap& r);
00093 
00096   GraphVertex node (unsigned id) const;
00097 
00100   GraphEdge edge (unsigned id) const;
00101 
00104   const NodeInfo& nodeInfo (unsigned id) const;
00105 
00108   const EdgeInfo& edgeInfo (unsigned id) const;
00109 
00113   unsigned addNode (const NodeInfo& info);
00114 
00120   unsigned addEdge (const EdgeInfo& info);
00121 
00125   void deleteEdge (unsigned id);
00126 
00130   Nodes gridNodes (const unsigned g) const;
00131 
00133   void recomputeIndexes ();
00134 
00135 private:
00136 
00137   std::map<unsigned, GraphVertex> vertex_map_;
00138   std::map<unsigned, GraphEdge> edge_map_;
00139   std::map<unsigned, Nodes> grid_nodes_;
00140 
00141   // Counter used to autogenerate node ids
00142   unsigned next_node_id_;
00143 
00144   // Counter used to autogenerate edge ids
00145   unsigned next_edge_id_;
00146 
00147 };
00148 
00149 
00150 /************************************************************
00151  * Utilities
00152  ***********************************************************/
00153 
00155 geometry_msgs::Point
00156 positionOnGrid (unsigned n, unsigned g, const Roadmap& r,
00157                 const topological_map_2d::TopologicalMap& t);
00158 
00159 
00161 std::pair<std::vector<unsigned>, std::vector<geometry_msgs::Point> >
00162 nodesOnGrid (const unsigned g, const Roadmap& r,
00163              const topological_map_2d::TopologicalMap& t);
00164 
00165 
00166 } // namespace
00167 
00168 #endif // include guard


topological_roadmap
Author(s): Bhaskara Marthi
autogenerated on Sun Jan 5 2014 11:39:33