00001 
00038 #ifndef GRAPH_E8QGZKSM
00039 #define GRAPH_E8QGZKSM
00040 
00041 #include <boost/lexical_cast.hpp>
00042 #include <boost/graph/adjacency_list.hpp>
00043 #include <boost/graph/labeled_graph.hpp>
00044 #include <bwi_mapper/structures/point.h>
00045 
00046 #include <opencv/cv.h>
00047 #include <nav_msgs/MapMetaData.h>
00048 #include <nav_msgs/OccupancyGrid.h>
00049 
00050 namespace bwi_mapper {
00051 
00052   
00053   struct Vertex {
00054     Point2f location;
00055     double pixels;
00056   };
00057 
00058   
00059   struct Edge {
00060     double weight;
00061   };
00062 
00063   
00064   typedef boost::adjacency_list<
00065     boost::vecS, boost::vecS, boost::undirectedS, Vertex, Edge
00066   > Graph;
00067 
00072   void drawGraph(cv::Mat &image, const Graph& graph,
00073       uint32_t orig_x = 0, uint32_t orig_y = 0, 
00074       bool put_text = true, bool put_all_edges = true, 
00075       std::vector<std::pair<size_t, size_t> > specific_edges = 
00076       std::vector<std::pair<size_t, size_t> >());
00077 
00078   void drawArrowOnImage(cv::Mat &image, const cv::Point2f &arrow_center, float orientation, 
00079                         const cv::Scalar &color, int size, int thickness);
00080 
00081   void drawArrowOnGraph(cv::Mat &image, const Graph& graph, 
00082       std::pair<size_t, float> arrow, uint32_t map_width, uint32_t map_height,
00083       cv::Scalar color = cv::Scalar(0,0,255),
00084       uint32_t orig_x = 0, uint32_t orig_y = 0);
00085 
00086   void drawCircleOnGraph(cv::Mat &image, const Graph& graph, 
00087       size_t node, cv::Scalar color = cv::Scalar(0,0,255),
00088       uint32_t orig_x = 0, uint32_t orig_y = 0);
00089 
00090   void drawSquareOnGraph(cv::Mat &image, const Graph& graph, 
00091       size_t node, cv::Scalar color = cv::Scalar(0,0,255),
00092       uint32_t orig_x = 0, uint32_t orig_y = 0, int size = 30, 
00093       int thickness = 2);
00094 
00095   void writeGraphToFile(const std::string &filename, 
00096       const Graph& graph, const nav_msgs::MapMetaData& info); 
00097 
00098   void readGraphFromFile(const std::string &filename, 
00099       const nav_msgs::MapMetaData& info, Graph& graph); 
00100 
00101   Point2f getLocationFromGraphId(int idx, const Graph& graph);
00102 
00103   size_t getClosestIdOnGraph(const Point2f &point, 
00104       const Graph &graph, double threshold = 0.0);
00105 
00106   size_t getClosestIdOnGraphFromEdge(const Point2f &point, 
00107       const Graph &graph, size_t prev_graph_id);
00108 
00109   
00110 
00111   bool isVisible(size_t u, size_t v, const Graph &graph, 
00112       const nav_msgs::OccupancyGrid& map);
00113   
00114   float getNodeAngle(size_t u, size_t v, const Graph &graph);
00115 
00116   float getEuclideanDistance(size_t u, size_t v, const Graph &graph);
00117 
00118   float getShortestPathWithDistance(size_t start_idx, size_t goal_idx, 
00119       std::vector<size_t> &path_from_goal, const Graph &graph);
00120 
00121   float getShortestPathDistance(size_t start_idx, size_t goal_idx,
00122       const Graph &graph);
00123 
00124   void getAdjacentNodes(size_t v, const Graph& graph,
00125       std::vector<size_t>& adjacent_vertices);
00126 
00127   void getVisibleNodes(size_t v, const Graph& graph, 
00128       const nav_msgs::OccupancyGrid& grid,
00129       std::vector<size_t>& visible_vertices, float visibility_range = 0.0f);
00130 
00131 } 
00132 
00133 #endif