00001
00038 #include <yaml-cpp/yaml.h>
00039 #include <fstream>
00040 #include <boost/graph/dijkstra_shortest_paths.hpp>
00041 #include <boost/foreach.hpp>
00042
00043 #include <bwi_mapper/graph.h>
00044 #include <bwi_mapper/map_utils.h>
00045 #include <bwi_mapper/point_utils.h>
00046
00047 #include <opencv2/opencv_modules.hpp>
00048 #ifdef HAVE_OPENCV_IMGCODECS
00049
00050 #include <opencv2/imgcodecs.hpp>
00051 #endif
00052 #ifdef HAVE_OPENCV_IMGPROC
00053
00054 #include <opencv2/imgproc/imgproc.hpp>
00055 #endif
00056
00057
00058 #ifdef HAVE_NEW_YAMLCPP
00059 namespace YAML {
00060
00061
00062 template<typename T>
00063 void operator >> (const YAML::Node& node, T& i)
00064 {
00065 i = node.as<T>();
00066 }
00067 }
00068 #endif
00069
00070 namespace bwi_mapper {
00071
00076 void drawGraph(cv::Mat &image, const Graph& graph,
00077 uint32_t orig_x, uint32_t orig_y, bool put_text, bool put_all_edges,
00078 std::vector<std::pair<size_t, size_t> > specific_edges) {
00079
00080 Graph::vertex_iterator vi, vend;
00081 size_t count = 0;
00082 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend;
00083 ++vi, ++count) {
00084 Point2f location = graph[*vi].location;
00085
00086 std::vector<size_t> adj_vertices;
00087 getAdjacentNodes(count, graph, adj_vertices);
00088 BOOST_FOREACH(size_t adj_vtx, adj_vertices) {
00089 if (adj_vtx > count) {
00090 bool allow_edge = put_all_edges;
00091 allow_edge = allow_edge ||
00092 std::find(specific_edges.begin(), specific_edges.end(),
00093 std::make_pair(count, adj_vtx)) != specific_edges.end();
00094 allow_edge = allow_edge ||
00095 std::find(specific_edges.begin(), specific_edges.end(),
00096 std::make_pair(adj_vtx, count)) != specific_edges.end();
00097 if (allow_edge) {
00098 Point2f location2 = getLocationFromGraphId(adj_vtx, graph);
00099 cv::Point start_pt =
00100 cv::Point(orig_x + location.x, orig_y + location.y);
00101 cv::Point end_pt =
00102 cv::Point(orig_x + location2.x, orig_y + location2.y);
00103 float shift_ratio = 15.0f / cv::norm(start_pt - end_pt);
00104 cv::Point start_shift = start_pt + shift_ratio * (end_pt - start_pt);
00105 cv::Point end_shift = end_pt + shift_ratio * (start_pt - end_pt);
00106 cv::line(image, start_shift, end_shift,
00107 cv::Scalar(160, 160, 255),
00108 4, CV_AA);
00109 }
00110 }
00111 }
00112 }
00113
00114 count = 0;
00115 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend; ++vi) {
00116 Point2f location = graph[*vi].location;
00117
00118 cv::Point vertex_loc(orig_x + (uint32_t)location.x,
00119 orig_y + (uint32_t)location.y);
00120 if (put_text) {
00121 cv::Point text_loc = vertex_loc + cv::Point(-7,7);
00122 if (count >= 10) {
00123 text_loc = text_loc + cv::Point(-7,0);
00124 }
00125 cv::putText(image, boost::lexical_cast<std::string>(count), text_loc,
00126 cv::FONT_HERSHEY_SIMPLEX, 0.7, cvScalar(0,0,255), 2, CV_AA);
00127 } else {
00128 size_t vertex_size = 13;
00129 cv::circle(image, vertex_loc, vertex_size, cv::Scalar(0,0,255), -1, CV_AA);
00130 }
00131 count++;
00132 }
00133 }
00134
00135 void drawArrowOnImage(cv::Mat &image, const cv::Point2f &arrow_center, float orientation,
00136 const cv::Scalar &color, int size, int thickness) {
00137
00138 cv::Point arrow_start = arrow_center +
00139 cv::Point2f(size * cosf(orientation + M_PI/2),
00140 size * sinf(orientation + M_PI/2));
00141 cv::Point arrow_end = arrow_center -
00142 cv::Point2f(size * cosf(orientation + M_PI/2),
00143 size * sinf(orientation + M_PI/2));
00144
00145 cv::line(image, arrow_start, arrow_end, color, thickness, CV_AA);
00146
00147
00148 cv::Point p(arrow_start), q(arrow_end);
00149
00150
00151 float angle = atan2f(p.y - q.y, p.x - q.x);
00152 p.x = (int) (q.x + (size/2 - 1) * cos(angle + M_PI/4));
00153 p.y = (int) (q.y + (size/2 - 1) * sin(angle + M_PI/4));
00154 cv::line(image, p, q, color, thickness, CV_AA);
00155
00156
00157 p.x = (int) (q.x + (size/2 + 1) * cos(angle - M_PI/4));
00158 p.y = (int) (q.y + (size/2 + 1) * sin(angle - M_PI/4));
00159 cv::line(image, p, q, color, thickness, CV_AA);
00160
00161 }
00162
00163 void drawArrowOnGraph(cv::Mat &image, const Graph& graph,
00164 std::pair<size_t, float> arrow, uint32_t map_width, uint32_t map_height,
00165 cv::Scalar color, uint32_t orig_x, uint32_t orig_y) {
00166
00167 float orientation = arrow.second;
00168 Point2f loc = getLocationFromGraphId(arrow.first, graph);
00169 cv::Point node_loc(loc.x + orig_x, loc.y + orig_y);
00170 cv::Point map_center(orig_x + map_width / 2, orig_y + map_height / 2);
00171
00172 cv::Point arrow_center_1 = node_loc +
00173 cv::Point(25 * cosf(orientation), 25 * sinf(orientation));
00174 cv::Point arrow_center_2 = node_loc -
00175 cv::Point(25 * cosf(orientation), 25 * sinf(orientation));
00176 cv::Point arrow_center = (cv::norm(arrow_center_2 - map_center) <
00177 cv::norm(arrow_center_1 - map_center)) ? arrow_center_2 :
00178 arrow_center_1;
00179
00180 drawArrowOnImage(image, arrow_center, orientation, color, 20, 3);
00181
00182 }
00183
00184 void drawCircleOnGraph(cv::Mat &image, const Graph& graph,
00185 size_t node, cv::Scalar color,
00186 uint32_t orig_x, uint32_t orig_y) {
00187 Point2f loc = getLocationFromGraphId(node, graph);
00188 cv::Point circle_loc(loc.x + orig_x, loc.y + orig_y);
00189 cv::circle(image, circle_loc, 15, color, 2, CV_AA);
00190 }
00191
00192 void drawSquareOnGraph(cv::Mat &image, const Graph& graph,
00193 size_t node, cv::Scalar color,
00194 uint32_t orig_x, uint32_t orig_y, int size, int thickness) {
00195 Point2f loc = getLocationFromGraphId(node, graph);
00196 cv::Point square_loc(loc.x + orig_x, loc.y + orig_y);
00197 cv::Rect rect(square_loc.x - size/2, square_loc.y - size/2, size, size);
00198 cv::rectangle(image, rect, color, thickness, CV_AA);
00199 }
00200
00201 void writeGraphToFile(const std::string &filename,
00202 const Graph& graph, const nav_msgs::MapMetaData& info) {
00203
00204 std::map<Graph::vertex_descriptor, size_t> vertex_map;
00205 size_t count = 0;
00206 Graph::vertex_iterator vi, vend;
00207 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend; ++vi) {
00208 vertex_map[*vi] = count;
00209 count++;
00210 }
00211
00212 count = 0;
00213 YAML::Emitter out;
00214 out << YAML::BeginSeq;
00215 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend; ++vi) {
00216 out << YAML::BeginMap;
00217 Point2f pxl_loc = graph[*vi].location;
00218 Point2f real_loc = toMap(pxl_loc, info);
00219 out << YAML::Key << "id" << YAML::Value << count;
00220 out << YAML::Key << "x" << YAML::Value << real_loc.x;
00221 out << YAML::Key << "y" << YAML::Value << real_loc.y;
00222 out << YAML::Key << "edges" << YAML::Value << YAML::BeginSeq;
00223 Graph::adjacency_iterator ai, aend;
00224 for (boost::tie(ai, aend) = boost::adjacent_vertices(
00225 (Graph::vertex_descriptor)*vi, graph);
00226 ai != aend; ++ai) {
00227 out << vertex_map[*ai];
00228 }
00229 out << YAML::EndSeq;
00230 out << YAML::EndMap;
00231 count++;
00232 }
00233 out << YAML::EndSeq;
00234
00235 std::ofstream fout(filename.c_str());
00236 fout << out.c_str();
00237 fout.close();
00238 }
00239
00240 void readGraphFromFile(const std::string &filename,
00241 const nav_msgs::MapMetaData& info, Graph& graph) {
00242
00243 std::vector<std::pair<float, float> > vertices;
00244 std::vector<std::vector<size_t> > edges;
00245
00246 std::ifstream fin(filename.c_str());
00247 YAML::Node doc;
00248 #ifdef HAVE_NEW_YAMLCPP
00249 doc = YAML::Load(fin);
00250 #else
00251 YAML::Parser parser(fin);
00252 parser.GetNextDocument(doc);
00253 #endif
00254 for (size_t i = 0; i < doc.size(); ++i) {
00255 float x, y;
00256 doc[i]["x"] >> x;
00257 doc[i]["y"] >> y;
00258 vertices.push_back(std::make_pair(x, y));
00259 std::vector<size_t> v_edges;
00260 const YAML::Node& edges_node = doc[i]["edges"];
00261 for (size_t j = 0; j < edges_node.size(); ++j) {
00262 size_t t;
00263 edges_node[j] >> t;
00264 if (t > i) {
00265 v_edges.push_back(t);
00266
00267 }
00268 }
00269 edges.push_back(v_edges);
00270 }
00271 fin.close();
00272
00273
00274 for (size_t i = 0; i < vertices.size(); ++i) {
00275 Graph::vertex_descriptor vi = boost::add_vertex(graph);
00276 Point2f real_loc (vertices[i].first, vertices[i].second);
00277 Point2f pxl_loc (toGrid(real_loc, info));
00278 graph[vi].location = pxl_loc;
00279 graph[vi].pixels = 0;
00280 }
00281
00282 for (size_t i = 0; i < edges.size(); ++i) {
00283 for (size_t j = 0; j < edges[i].size(); ++j) {
00284 Graph::vertex_descriptor vi,vj;
00285 vi = boost::vertex(i, graph);
00286 vj = boost::vertex(edges[i][j], graph);
00287 Graph::edge_descriptor e; bool b;
00288 boost::tie(e,b) = boost::add_edge(vi, vj, graph);
00289 graph[e].weight =
00290 bwi_mapper::getMagnitude(graph[vi].location - graph[vj].location);
00291 }
00292 }
00293
00294 std::cout << "Read graph with " << vertices.size() << " vertices." << std::endl;
00295 }
00296
00297 Point2f getLocationFromGraphId(int idx, const Graph& graph) {
00298 Graph::vertex_descriptor i = boost::vertex(idx, graph);
00299 return graph[i].location;
00300 }
00301
00302 size_t getClosestIdOnGraph(const Point2f &point,
00303 const Graph &graph, double threshold) {
00304 Graph::vertex_iterator vi, vend;
00305 size_t count = 0, min_idx = -1;
00306 float min_distance = std::numeric_limits<float>::max();
00307 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend; ++vi) {
00308 Point2f location = graph[*vi].location;
00309 if (bwi_mapper::getMagnitude(point - location) <= min_distance) {
00310 min_distance =
00311 bwi_mapper::getMagnitude(point - location);
00312 min_idx = count;
00313 }
00314 count++;
00315 }
00316 if (min_distance < threshold || threshold == 0.0) {
00317 return min_idx;
00318 } else {
00319 return -1;
00320 }
00321 }
00322
00323 size_t getClosestIdOnGraphFromEdge(const Point2f& point,
00324 const Graph &graph, size_t prev_graph_id) {
00325
00326 Point2f location = getLocationFromGraphId(prev_graph_id, graph);
00327
00328 size_t other_graph_id = getClosestEdgeOnGraphGivenId(point, graph, prev_graph_id);
00329 Point2f other_location = getLocationFromGraphId(other_graph_id, graph);
00330
00331 if (getMagnitude(point - location) < getMagnitude(point - other_location)) {
00332 return prev_graph_id;
00333 } else {
00334 return other_graph_id;
00335 }
00336
00337 }
00338
00339 size_t getClosestEdgeOnGraphGivenId(const Point2f& point, const Graph &graph, size_t one_graph_id) {
00340
00341 boost::property_map<Graph, boost::vertex_index_t>::type
00342 indexmap = boost::get(boost::vertex_index, graph);
00343
00344 Graph::vertex_descriptor prev_vertex = boost::vertex(one_graph_id, graph);
00345 Point2f location = graph[prev_vertex].location;
00346
00347 size_t min_idx = -1;
00348 float min_distance = std::numeric_limits<float>::max();
00349
00350 Graph::adjacency_iterator ai, aend;
00351 for (boost::tie(ai, aend) = boost::adjacent_vertices(prev_vertex, graph);
00352 ai != aend; ++ai) {
00353 Point2f location2 = graph[*ai].location;
00354
00355 float distance = bwi_mapper::minimumDistanceToLineSegment(location, location2, point);
00356 if (distance < min_distance) {
00357 min_distance = distance;
00358 min_idx = indexmap[*ai];
00359 }
00360 }
00361
00362 return min_idx;
00363 }
00364
00365 bool isVisible(size_t u, size_t v, const Graph &graph,
00366 const nav_msgs::OccupancyGrid& map) {
00367 Point2f loc_u = getLocationFromGraphId(u, graph);
00368 Point2f loc_v = getLocationFromGraphId(v, graph);
00369 return locationsInDirectLineOfSight(loc_u, loc_v, map);
00370 }
00371
00372 float getNodeAngle(size_t u, size_t v, const Graph & graph) {
00373 Graph::vertex_descriptor vd_u = boost::vertex(u, graph);
00374 Graph::vertex_descriptor vd_v = boost::vertex(v, graph);
00375 return atan2f(graph[vd_v].location.y - graph[vd_u].location.y,
00376 graph[vd_v].location.x - graph[vd_u].location.x);
00377 }
00378
00379 float getEuclideanDistance(size_t u, size_t v, const Graph& graph) {
00380 Graph::vertex_descriptor vd_u = boost::vertex(u, graph);
00381 Graph::vertex_descriptor vd_v = boost::vertex(v, graph);
00382 return getMagnitude(graph[vd_v].location - graph[vd_u].location);
00383 }
00384
00385 float getShortestPathWithDistance(size_t start_idx, size_t goal_idx,
00386 std::vector<size_t> &path_from_goal, const Graph &graph) {
00387
00388 bwi_mapper::Graph graph_copy(graph);
00389
00390 std::vector<Graph::vertex_descriptor>
00391 p(boost::num_vertices(graph_copy));
00392 std::vector<double> d(boost::num_vertices(graph_copy));
00393 Graph::vertex_descriptor s =
00394 boost::vertex(start_idx, graph_copy);
00395
00396 boost::property_map<Graph, boost::vertex_index_t>::type
00397 indexmap = boost::get(boost::vertex_index, graph_copy);
00398 boost::property_map<
00399 Graph,
00400 double Edge::*
00401 >::type weightmap = boost::get(&Edge::weight, graph_copy);
00402 boost::dijkstra_shortest_paths(graph_copy, s, &p[0], &d[0], weightmap,
00403 indexmap, std::less<double>(), boost::closed_plus<double>(),
00404 (std::numeric_limits<double>::max)(), 0,
00405 boost::default_dijkstra_visitor());
00406
00407
00408 path_from_goal.clear();
00409
00410
00411 Graph::vertex_descriptor g = boost::vertex(goal_idx, graph_copy);
00412
00413 while (indexmap[p[g]] != start_idx) {
00414
00415 path_from_goal.push_back(indexmap[p[g]]);
00416 g = p[g];
00417 }
00418 path_from_goal.push_back(start_idx);
00419
00420
00421 return d[goal_idx];
00422
00423 }
00424
00425 float getShortestPathDistance(size_t start_idx, size_t goal_idx,
00426 const Graph &graph) {
00427 std::vector<size_t> temp_path;
00428 return getShortestPathWithDistance(start_idx, goal_idx, temp_path, graph);
00429 }
00430
00431 void getAdjacentNodes(size_t graph_id, const Graph& graph,
00432 std::vector<size_t>& adjacent_vertices) {
00433
00434 adjacent_vertices.clear();
00435
00436 boost::property_map<Graph, boost::vertex_index_t>::type
00437 indexmap = boost::get(boost::vertex_index, graph);
00438
00439 Graph::vertex_descriptor vertex = boost::vertex(graph_id, graph);
00440 Graph::adjacency_iterator ai, aend;
00441 for (boost::tie(ai, aend) = boost::adjacent_vertices(vertex, graph);
00442 ai != aend; ++ai) {
00443 adjacent_vertices.push_back(indexmap[*ai]);
00444 }
00445
00446 }
00447
00448 void getVisibleNodes(size_t v, const Graph& graph,
00449 const nav_msgs::OccupancyGrid& grid,
00450 std::vector<size_t>& visible_vertices, float visibility_range) {
00451
00452 visible_vertices.clear();
00453
00454 Point2f loc_v = getLocationFromGraphId(v, graph);
00455 size_t count = 0;
00456 Graph::vertex_iterator vi, vend;
00457 for (boost::tie(vi, vend) = boost::vertices(graph); vi != vend;
00458 ++vi, ++count) {
00459 bool is_visible = isVisible(v, count, graph, grid);
00460 if (is_visible && visibility_range != 0.0f) {
00461 is_visible = is_visible &&
00462 (getEuclideanDistance(v, count, graph) < visibility_range);
00463 }
00464 if (is_visible) {
00465 visible_vertices.push_back(count);
00466 }
00467 }
00468 }
00469
00470 }