topological_mapper.cpp
Go to the documentation of this file.
00001 
00038 #include <bwi_mapper/topological_mapper.h>
00039 #include <bwi_mapper/connected_components.h>
00040 #include <bwi_mapper/map_utils.h>
00041 #include <bwi_mapper/point_utils.h>
00042 
00043 #include <boost/foreach.hpp>
00044 
00045 #include <opencv/highgui.h>
00046 #include <opencv2/opencv_modules.hpp>
00047 #ifdef HAVE_OPENCV_IMGCODECS
00048 // this is OpenCV 3 and we need extra includes
00049 #include <opencv2/imgcodecs.hpp>
00050 #endif
00051 #ifdef HAVE_OPENCV_IMGPROC
00052 // this is OpenCV 3 and we need extra includes
00053 #include <opencv2/imgproc/imgproc.hpp>
00054 #endif
00055 
00056 namespace bwi_mapper {
00057 
00068   void TopologicalMapper::computeTopologicalGraph(double threshold, 
00069       double critical_epsilon, double merge_threshold) {
00070 
00071     std::cout << "computeTopologicalGraph(): find voronoi points" << std::endl;
00072     findVoronoiPoints(threshold);
00073     std::cout << "computeTopologicalGraph(): compute critical regions" << std::endl;
00074     computeCriticalRegions(critical_epsilon);
00075     std::cout << "computeTopologicalGraph(): compute ze graph" << std::endl;
00076     computeGraph(merge_threshold);
00077   }
00078 
00083   void TopologicalMapper::drawCriticalPoints(cv::Mat &image, 
00084       uint32_t orig_x, uint32_t orig_y) {
00085 
00086     for (size_t i = 0; i < critical_points_.size(); ++i) {
00087       VoronoiPoint &vp = critical_points_[i];
00088       cv::circle(image, 
00089           cv::Point(vp.x + orig_x, vp.y + orig_y), 8, cv::Scalar(0,0,255), -1);
00090     }
00091 
00092     drawCriticalLines(image, orig_x, orig_y, false, true);
00093   }
00094 
00099   void TopologicalMapper::drawConnectedComponents(cv::Mat &image,
00100       uint32_t orig_x, uint32_t orig_y) {
00101 
00102     // Figure out different colors - 1st color should always be black
00103     size_t num_colors = num_components_;
00104     component_colors_.resize(num_colors);
00105     for (size_t i = 0; i < num_colors; ++i) {
00106       component_colors_[i] = 
00107         cv::Vec3b(160 + rand() % 64, 160 + rand() % 64, 160 + rand() % 64);
00108     }
00109 
00110     // component 0 is obstacles + background. don't draw?
00111 
00112     // Now paint!
00113     for (uint32_t j = 1; j < map_resp_.map.info.height; ++j) {
00114       cv::Vec3b* image_row_j = image.ptr<cv::Vec3b>(j + orig_y);
00115       for (uint32_t i = 0; i < map_resp_.map.info.width; ++i) {
00116         size_t map_idx = MAP_IDX(map_resp_.map.info.width, i, j);
00117         if (component_map_[map_idx] == -1)
00118           continue;
00119         cv::Vec3b& pixel = image_row_j[i + orig_x];
00120         pixel[0] = component_colors_[component_map_[map_idx]][0];
00121         pixel[1] = component_colors_[component_map_[map_idx]][1];
00122         pixel[2] = component_colors_[component_map_[map_idx]][2];
00123 
00124       }
00125     }
00126   }
00127 
00128 
00129   void TopologicalMapper::drawRegionGraph(cv::Mat &image,
00130       uint32_t orig_x, uint32_t orig_y) {
00131     drawGraph(image, region_graph_, orig_x, orig_y);
00132   }
00133 
00134   void TopologicalMapper::drawPointGraph(cv::Mat &image,
00135       uint32_t orig_x, uint32_t orig_y) {
00136     drawGraph(image, point_graph_, orig_x, orig_y);
00137   }
00138 
00139   void TopologicalMapper::writeRegionGraphToFile(std::string &filename) {
00140     writeGraphToFile(filename, region_graph_, map_resp_.map.info);
00141   }
00142 
00143   void TopologicalMapper::writePointGraphToFile(std::string &filename) {
00144     writeGraphToFile(filename, point_graph_, map_resp_.map.info);
00145   }
00146 
00151   void TopologicalMapper::printCriticalPoints() {
00152     for (size_t i = 0; i < critical_points_.size(); ++i) {
00153       VoronoiPoint &vp = critical_points_[i];
00154       std::cout << " (" << vp.x << "," << vp.y << "): ";
00155       for (size_t j = 0; j < vp.basis_points.size(); ++j) {
00156         std::cout << " (" << vp.basis_points[j].x << "," 
00157                   << vp.basis_points[j].y << "," 
00158                   << vp.basis_points[j].distance_from_ref << "), ";
00159       }
00160       std::cout << std::endl;
00161     }
00162   }
00163 
00170   void TopologicalMapper::drawOutput(cv::Mat &image) {
00171     VoronoiApproximator::drawOutput(image);
00172     drawMap(image, 2 * map_resp_.map.info.width);
00173     drawConnectedComponents(image, 2 * map_resp_.map.info.width);
00174     drawCriticalPoints(image, 2 * map_resp_.map.info.width);
00175     drawMap(image, 3 * map_resp_.map.info.width);
00176     drawRegionGraph(image, 3 * map_resp_.map.info.width);
00177     drawMap(image, 4 * map_resp_.map.info.width);
00178     drawPointGraph(image, 4 * map_resp_.map.info.width);
00179   }
00180 
00181   void TopologicalMapper::saveOutput() {
00182     cv::Mat image;
00183     drawMap(image);
00184     drawVoronoiPoints(image);
00185     cv::imwrite("graphvoronoi.png", image);
00186     drawMap(image);
00187     drawConnectedComponents(image);
00188     drawCriticalPoints(image);
00189     cv::imwrite("graphcritical.png", image);
00190     drawMap(image);
00191     drawGraph(image, region_graph_);
00192     cv::imwrite("graphoriginal.png", image);
00193     drawMap(image);
00194     drawGraph(image, pass_1_graph_);
00195     cv::imwrite("graphpass1.png", image);
00196     drawMap(image);
00197     drawGraph(image, pass_2_graph_);
00198     cv::imwrite("graphpass2.png", image);
00199     drawMap(image);
00200     drawGraph(image, pass_3_graph_);
00201     cv::imwrite("graphpass3.png", image);
00202     drawMap(image);
00203     drawGraph(image, pass_4_graph_);
00204     cv::imwrite("graphpass4.png", image);
00205     drawMap(image);
00206     drawGraph(image, point_graph_);
00207     cv::imwrite("graphfinal.png", image);
00208   }
00209 
00215   void TopologicalMapper::computeCriticalRegions (double critical_epsilon) {
00216 
00217     // Compute critical points
00218     size_t pixel_critical_epsilon = 
00219       critical_epsilon / map_resp_.map.info.resolution;
00220 
00221     for (size_t i = 0; i < voronoi_points_.size(); ++i) {
00222       VoronoiPoint &vpi = voronoi_points_[i];
00223       float average_neighbourhood_clearance = 0;
00224       size_t neighbour_count = 0;
00225       bool is_clearance_minima = true;
00226       // Get all voronoi points in a region around this voronoi point
00227       for (size_t j = 0; j < voronoi_points_.size(); ++j) {
00228         // Don't check if it is the same point
00229         if (j == i) {
00230           continue;
00231         }
00232 
00233         // Compute distance of jth point to ith point - 
00234         // don't compare if too far away
00235         VoronoiPoint &vpj = voronoi_points_[j];
00236         float distance = bwi_mapper::getMagnitude(vpj - vpi); 
00237         if (distance > pixel_critical_epsilon) {
00238           continue;
00239         }
00240 
00241         average_neighbourhood_clearance += vpj.average_clearance;
00242         ++neighbour_count;
00243 
00244         // See if the jth point has lower clearance than the ith
00245         if (vpj.average_clearance < vpi.average_clearance) {
00246           is_clearance_minima = false;
00247           break;
00248         }
00249       }
00250 
00251       // If no neighbours, then this cannot be a critical point
00252       if (neighbour_count == 0) {
00253         continue;
00254       }
00255 
00256       // Check if the point is indeed better than the neighbourhood
00257       // This can happen is any 2 walls of the map are too straight
00258       average_neighbourhood_clearance /= neighbour_count;
00259       if (vpi.average_clearance >= 0.999 * average_neighbourhood_clearance) {
00260         continue;
00261       }
00262 
00263       /* std::cout << "Check1: VP at " << vpi << " with clearance " << vpi.average_clearance << " and avg neighbourhood clearance " << average_neighbourhood_clearance << std::endl; */
00264 
00265       vpi.critical_clearance_diff = 
00266         average_neighbourhood_clearance - vpi.average_clearance;
00267 
00268       std::vector<size_t> mark_for_removal;
00269       // This removal is not perfect, but ensures you don't have critical 
00270       // points too close.
00271       for (size_t j = 0; j < critical_points_.size(); ++j) {
00272 
00273         // Check if in same neighbourhood
00274         VoronoiPoint &vpj = critical_points_[j];
00275         float distance = norm(vpj - vpi); 
00276         if (distance > pixel_critical_epsilon) {
00277           continue;
00278         }
00279 
00280         // If in same neighbourhood, retain better point
00281         if (vpj.critical_clearance_diff >= vpi.critical_clearance_diff) {
00282           is_clearance_minima = false;
00283           break;
00284         } else {
00285           mark_for_removal.push_back(j);
00286         }
00287       }
00288 
00289       if (is_clearance_minima) {
00290         // Let's remove any points marked for removal
00291         for (size_t j = mark_for_removal.size() - 1; 
00292             j < mark_for_removal.size(); --j) { //unsigned
00293           critical_points_.erase(
00294               critical_points_.begin() + mark_for_removal[j]);
00295         }
00296 
00297         // And then add this critical point
00298         critical_points_.push_back(vpi);
00299       }
00300     }
00301 
00302     // Remove any critical points where the point itself does not lie on the line
00303     std::vector<size_t> mark_for_removal;
00304     for (size_t i = 0; i < critical_points_.size(); ++i) {
00305       VoronoiPoint &cp = critical_points_[i];
00306       float theta0 = 
00307         atan2((cp.basis_points[0] - cp).y,
00308               (cp.basis_points[0] - cp).x);
00309       float theta1 = 
00310         atan2((cp.basis_points[1] - cp).y,
00311               (cp.basis_points[1] - cp).x);
00312       float thetadiff = fabs(theta1 - theta0);
00313 
00314       // We don't need to worry about wrapping here due known range of atan2
00315       if (thetadiff > M_PI + M_PI/12 || thetadiff < M_PI - M_PI/12) {
00316         mark_for_removal.push_back(i);
00317       }
00318     }
00319 
00320     // Remove bad critical points
00321     for (size_t j = mark_for_removal.size() - 1; 
00322         j < mark_for_removal.size(); --j) { //unsigned
00323       critical_points_.erase(
00324           critical_points_.begin() + mark_for_removal[j]);
00325     }
00326 
00327     // Once you have critical lines, produce connected regions (4-connected)
00328     // draw the critical lines on to a copy of the map so that we can find
00329     // connected regions
00330     cv::Mat component_map_color;
00331     drawMap(component_map_color, inflated_map_);
00332     cvtColor(component_map_color, component_image_, CV_RGB2GRAY);
00333     drawCriticalLines(component_image_);
00334 
00335     component_map_.resize(
00336         component_image_.rows * component_image_.cols);
00337     ConnectedComponents cc(component_image_, component_map_);
00338     num_components_ = cc.getNumberComponents();
00339 
00340   }
00341 
00342   void TopologicalMapper::computeGraph(double merge_threshold) {
00343 
00344     // First for each critical point, find out the neigbouring regions
00345     std::vector<std::set<uint32_t> > point_neighbour_sets;
00346     point_neighbour_sets.resize(critical_points_.size());
00347 
00348     // Draw the critical lines as their indexes on the map
00349     cv::Mat lines(map_resp_.map.info.height, map_resp_.map.info.width, CV_16UC1,
00350         cv::Scalar((uint16_t)-1));
00351     drawCriticalLines(lines, 0, 0, true);
00352 
00353     // Go over all the pixels in the lines image and find neighbouring critical
00354     // regions
00355     for (int j = 0; j < lines.rows; ++j) {
00356       uint16_t* image_row_j = lines.ptr<uint16_t>(j);
00357       for (int i = 0; i < lines.cols; ++i) {
00358         uint16_t pixel = image_row_j[i];
00359         if (pixel == (uint16_t)-1) {
00360           continue;
00361         }
00362         int x_offset[] = {0, -1, 1, 0};
00363         int y_offset[] = {-1, 0, 0, 1};
00364         size_t num_neighbours = 4;
00365         for (size_t count = 0; count < num_neighbours; ++count) {
00366           uint32_t x_n = i + x_offset[count];
00367           uint32_t y_n = j + y_offset[count];
00368           if (x_n >= (uint16_t) lines.cols || y_n >= (uint16_t) lines.rows) {
00369             continue;
00370           }
00371           size_t map_idx = MAP_IDX(lines.cols, x_n, y_n);
00372           if (component_map_[map_idx] >= 0 && 
00373               component_map_[map_idx] < (int32_t) num_components_) {
00374             point_neighbour_sets[pixel].insert(component_map_[map_idx]);
00375           }
00376         }
00377       }
00378     }
00379 
00380     // Throw out any critical points that do not have 2 adjoining regions.
00381     // This can happen if the regions are too small
00382     std::vector<std::vector<uint32_t> > point_neighbours;
00383     point_neighbours.resize(critical_points_.size());
00384     std::vector<int> remove_crit_points;
00385     for (size_t i = 0; i < critical_points_.size(); ++i) {
00386       if (point_neighbour_sets[i].size() == 2) {
00387         point_neighbours[i] = 
00388           std::vector<uint32_t>(point_neighbour_sets[i].begin(),
00389               point_neighbour_sets[i].end());
00390       } else {
00391         remove_crit_points.push_back(i);
00392       }
00393     }
00394 
00395     for (int i = remove_crit_points.size() - 1; i >=0 ; --i) {
00396       critical_points_.erase(critical_points_.begin() + i);
00397       point_neighbour_sets.erase(point_neighbour_sets.begin() + i);
00398       point_neighbours.erase(point_neighbours.begin() + i);
00399     }
00400 
00401     // Find connectivity to remove any isolated sub-graphs
00402     std::vector<bool> checked_region(critical_points_.size(), false);
00403     std::vector<std::set<int> > graph_sets;
00404     for (size_t i = 0; i < num_components_; ++i) {
00405       if (checked_region[i]) {
00406         continue;
00407       }
00408       std::set<int> open_set, closed_set;
00409       open_set.insert(i);
00410       while (open_set.size() != 0) {
00411         int current_region = *(open_set.begin());
00412         open_set.erase(open_set.begin());
00413         closed_set.insert(current_region);
00414         checked_region[current_region] = true;
00415         for (int j = 0; j < critical_points_.size(); ++j) {
00416           for (int k = 0; k < 2; ++k) {
00417             if (point_neighbours[j][k] == current_region && 
00418                 std::find(closed_set.begin(), closed_set.end(), 
00419                   point_neighbours[j][1-k]) == 
00420                 closed_set.end()) {
00421               open_set.insert(point_neighbours[j][1-k]);
00422             }
00423           }
00424         }
00425       }
00426       graph_sets.push_back(closed_set);
00427     }
00428 
00429     std::set<int> master_region_set;
00430     if (graph_sets.size() != 1) {
00431       std::cout << "WARNING: Master graph is fragmented into " <<
00432         graph_sets.size() << " sub-graphs!!!" << std::endl;
00433       int max_idx = 0;
00434       int max_size = graph_sets[0].size();
00435       for (size_t i = 1; i < graph_sets.size(); ++i) {
00436         if (graph_sets[i].size() > max_size) {
00437           max_idx = i;
00438           max_size = graph_sets[i].size();
00439         }
00440       }
00441       master_region_set = graph_sets[max_idx];
00442     } else {
00443       master_region_set = graph_sets[0];
00444     }
00445     
00446     // Create the region graph next
00447     std::map<int, int> region_to_vertex_map;
00448     int vertex_count = 0;
00449     for (size_t r = 0; r < num_components_; ++r) { 
00450       if (std::find(master_region_set.begin(), master_region_set.end(), r) ==
00451           master_region_set.end()) {
00452         region_to_vertex_map[r] = -1;
00453         continue;
00454       }
00455 
00456       Graph::vertex_descriptor vi = boost::add_vertex(region_graph_);
00457 
00458       // Calculate the centroid
00459       uint32_t avg_i = 0, avg_j = 0, pixel_count = 0;
00460       for (size_t j = 0; j < map_resp_.map.info.height; ++j) {
00461         for (size_t i = 0; i < map_resp_.map.info.width; ++i) {
00462           size_t map_idx = MAP_IDX(map_resp_.map.info.width, i, j);
00463           if (component_map_[map_idx] == (int)r) {
00464             avg_j += j;
00465             avg_i += i;
00466             pixel_count++;
00467           }
00468         }
00469       }
00470 
00471       region_graph_[vi].location.x = ((float) avg_i) / pixel_count;
00472       region_graph_[vi].location.y = ((float) avg_j) / pixel_count;
00473       region_graph_[vi].pixels = floor(sqrt(pixel_count));
00474 
00475       // This map is only required till the point we form edges on this graph 
00476       region_to_vertex_map[r] = vertex_count;
00477 
00478       ++vertex_count;
00479     }
00480 
00481     // Now that region_to_vertex_map is complete, 
00482     // forward critical points to next graph
00483     std::map<int, std::map<int, VoronoiPoint> > 
00484       region_vertex_crit_points;
00485     for (size_t r = 0; r < num_components_; ++r) { 
00486       if (std::find(master_region_set.begin(), master_region_set.end(), r) ==
00487           master_region_set.end()) {
00488         region_to_vertex_map[r] = -1;
00489         continue;
00490       }
00491       // Store the critical points corresponding to this vertex
00492       for (int j = 0; j < critical_points_.size(); ++j) {
00493         for (int k = 0; k < 2; ++k) {
00494           if (point_neighbours[j][k] == r) {
00495             int region_vertex = region_to_vertex_map[r];
00496             int other_region_vertex = region_to_vertex_map[point_neighbours[j][1-k]];
00497             if (region_vertex == 192 && other_region_vertex == 202) {
00498               std::cout << "192-202: " << r << " " << point_neighbours[j][1-k] << " " << critical_points_[j] << std::endl;
00499             }
00500             if (region_vertex == 202 && other_region_vertex == 192) {
00501               std::cout << "192-202: " << r << " " << point_neighbours[j][1-k] << " " << critical_points_[j] << std::endl;
00502             }
00503             region_vertex_crit_points[region_vertex]
00504               [region_to_vertex_map[point_neighbours[j][1-k]]] =  
00505                 critical_points_[j];
00506           }
00507         }
00508       }
00509     }
00510 
00511     // Create 1 edge per critical point
00512     for (size_t i = 0; i < critical_points_.size(); ++i) {
00513       int region1 = region_to_vertex_map[point_neighbours[i][0]];
00514       int region2 = region_to_vertex_map[point_neighbours[i][1]];
00515       if (region1 == -1) {
00516         // part of one of the sub-graphs that was discarded
00517         continue;
00518       }
00519       int count = 0;
00520       Graph::vertex_descriptor vi,vj;
00521       vi = boost::vertex(region1, region_graph_);
00522       vj = boost::vertex(region2, region_graph_);
00523       Graph::edge_descriptor e; bool b;
00524       boost::tie(e,b) = boost::edge(vi, vj, region_graph_);
00525       if (!b) {
00526         boost::tie(e,b) = boost::add_edge(vi, vj, region_graph_);
00527       }
00528       /* boost::tie(e,b) = boost::add_edge(vi, vj, region_graph_); */
00529       // region_graph_[e].weight = bwi_mapper::getMagnitude(
00530       //     region_graph_[vi].location - region_graph_[vj].location);
00531     }
00532 
00533     // Refine the region graph into the point graph:
00534     int pixel_threshold = merge_threshold / map_resp_.map.info.resolution;
00535 
00536     enum {
00537       PRESENT = 0,
00538       REMOVED_REGION_VERTEX = 1,
00539       CONVERT_TO_CRITICAL_POINT = 2,
00540       MERGE_VERTEX = 3
00541     };
00542     Graph::vertex_iterator vi, vend;
00543 
00544     // PASS 1 - resolve all vertices that are too big and have more than 2 
00545     // critical points to their underlying critical points
00546     std::cout << std::endl << "==============================" << std::endl;
00547     std::cout << "PASS 1" << std::endl;
00548     std::cout << "==============================" << std::endl << std::endl;
00549     Graph pass_0_graph = region_graph_;
00550     Graph pass_1_graph;
00551     int pass_0_count = 0;
00552     int pass_1_count = 0;
00553     std::vector<int> pass_0_vertex_status(
00554         boost::num_vertices(pass_0_graph), PRESENT);
00555     std::map<int, int> pass_0_vertex_to_pass_1_map;
00556     for (boost::tie(vi, vend) = boost::vertices(pass_0_graph); vi != vend;
00557         ++vi, ++pass_0_count) {
00558 
00559       std::cout << "Analyzing pass 0 graph vertex: " << pass_0_count << std::endl;
00560 
00561       std::vector<size_t> adj_vertices;
00562       getAdjacentNodes(pass_0_count, pass_0_graph, adj_vertices);
00563       // See if the area of this region is too big to be directly pushed into 
00564       // the pass 3 graph
00565       if (pass_0_graph[*vi].pixels >= pixel_threshold &&
00566           adj_vertices.size() > 2) {
00567         pass_0_vertex_status[pass_0_count] = CONVERT_TO_CRITICAL_POINT;
00568         std::cout << " - throwing it out (needs to be resolved to CPs)" <<
00569           std::endl;
00570         continue;
00571       }
00572 
00573       // Otherwise insert this as is into the point graph
00574       Graph::vertex_descriptor point_vi = boost::add_vertex(pass_1_graph);
00575       pass_1_graph[point_vi] = pass_0_graph[*vi];
00576       pass_0_vertex_to_pass_1_map[pass_0_count] = pass_1_count;
00577 
00578       ++pass_1_count;
00579     }
00580 
00581     // Now for each vertex that needs to be resolved into critical points, 
00582     // check neighbours recursively to convert these vertices into critical
00583     // points
00584     std::map<int, std::map<int, int> > pass_0_vertex_to_cp_map;
00585     pass_0_count = 0;
00586     for (boost::tie(vi, vend) = boost::vertices(pass_0_graph); vi != vend;
00587         ++vi, ++pass_0_count) {
00588 
00589       if (pass_0_vertex_status[pass_0_count] != CONVERT_TO_CRITICAL_POINT) {
00590         continue;
00591       }
00592       std::cout << "Converting pass1 vtx to CPs: " << pass_0_count << std::endl;
00593 
00594       std::vector<size_t> adj_vertices;
00595       getAdjacentNodes(pass_0_count, pass_0_graph, adj_vertices);
00596       std::vector<int> connect_edges;
00597       BOOST_FOREACH(size_t vtx, adj_vertices) {
00598         if (pass_0_vertex_status[vtx] == PRESENT) {
00599           Graph::vertex_descriptor point_vi = boost::add_vertex(pass_1_graph);
00600           pass_1_graph[point_vi].location =
00601             region_vertex_crit_points[pass_0_count][vtx];
00602           std::cout << " - added vtx at " << pass_1_graph[point_vi].location 
00603             << std::endl;
00604           int pass_1_vertex = pass_0_vertex_to_pass_1_map[vtx];
00605           std::cout << " - connecting vtx to pass_1_vertex: " << pass_1_vertex
00606             << " (pass0 = " << vtx << ")" << std::endl;
00607           Graph::vertex_descriptor vj;
00608           vj = boost::vertex(pass_1_vertex, pass_1_graph);
00609           Graph::edge_descriptor e; bool b;
00610           boost::tie(e,b) = boost::add_edge(point_vi, vj, pass_1_graph);
00611           connect_edges.push_back(pass_1_count);
00612           ++pass_1_count;
00613         } else if (vtx > pass_0_count) {
00614           // The CP is shared, but has not been added
00615           Graph::vertex_descriptor point_vi = boost::add_vertex(pass_1_graph);
00616           pass_1_graph[point_vi].location =
00617             region_vertex_crit_points[pass_0_count][vtx];
00618           std::cout << " - added shared cp with " << vtx << " at " 
00619             << pass_1_graph[point_vi].location << std::endl;
00620           pass_0_vertex_to_cp_map[pass_0_count][vtx] = pass_1_count;
00621           connect_edges.push_back(pass_1_count);
00622           ++pass_1_count;
00623         } else {
00624           // Retrieve existing CP
00625           int cp_vtx = pass_0_vertex_to_cp_map[vtx][pass_0_count];
00626           connect_edges.push_back(cp_vtx);
00627         }
00628       }
00629 
00630       /* Connect all the edges */
00631       for (int i = 0; i < connect_edges.size(); ++i) {
00632         for (int j = 0; j < i; ++j) {
00633           Graph::vertex_descriptor vi, vj;
00634           vi = boost::vertex(connect_edges[i], pass_1_graph);
00635           vj = boost::vertex(connect_edges[j], pass_1_graph);
00636           Graph::edge_descriptor e; bool b;
00637           boost::tie(e,b) = boost::add_edge(vi, vj, pass_1_graph);
00638         }
00639       }
00640 
00641     }
00642 
00643     // Connect all the edges as is from pass 1
00644     pass_0_count = 0;
00645     for (boost::tie(vi, vend) = boost::vertices(pass_0_graph); vi != vend;
00646         ++vi, ++pass_0_count) {
00647 
00648       if (pass_0_vertex_status[pass_0_count] != PRESENT) {
00649         continue;
00650       }
00651       std::cout << "Adding pass 1 edges for: " << pass_0_count << std::endl;
00652 
00653       std::vector<size_t> adj_vertices;
00654       getAdjacentNodes(pass_0_count, pass_0_graph, adj_vertices);
00655       BOOST_FOREACH(size_t vtx, adj_vertices) {
00656         if (pass_0_vertex_status[vtx] == PRESENT && vtx < pass_0_count) {
00657           Graph::vertex_descriptor vi, vj;
00658           vi = boost::vertex(
00659               pass_0_vertex_to_pass_1_map[pass_0_count], pass_1_graph);
00660           vj = boost::vertex(
00661               pass_0_vertex_to_pass_1_map[vtx], pass_1_graph);
00662           Graph::edge_descriptor e; bool b;
00663           boost::tie(e,b) = boost::add_edge(vi, vj, pass_1_graph);
00664         }
00665       }
00666     }
00667 
00668     pass_1_graph_ = pass_1_graph;
00669 
00670     // PASS 2 - remove any vertices that are adjacent to only 2 other vertices,
00671     // where both those vertices are visible to each other
00672     std::cout << std::endl << "==============================" << std::endl;
00673     std::cout << "PASS 2" << std::endl;
00674     std::cout << "==============================" << std::endl << std::endl;
00675 
00676     Graph pass_2_graph;
00677 
00678     std::vector<int> pass_1_vertex_status(boost::num_vertices(pass_1_graph), PRESENT);
00679     std::map<int, int> pass_1_vertex_to_pass_2_vertex_map;
00680     std::vector<std::pair<int, int> > rr_extra_edges;
00681     std::map<int, std::pair<int, int> > removed_vertex_map;
00682 
00683     pass_1_count = 0;
00684     int pass_2_count = 0;
00685     for (boost::tie(vi, vend) = boost::vertices(pass_1_graph); vi != vend;
00686         ++vi, ++pass_1_count) {
00687 
00688       std::cout << "Analyzing pass_1 graph vertex: " << pass_1_count << std::endl;
00689 
00690       if (pass_1_vertex_status[pass_1_count] != PRESENT) {
00691         std::cout << " - the vertex has been thrown out already " << std::endl;
00692         continue;
00693       }
00694       
00695       // See if this only has 2 neighbours, and the 2 neighbours are visible to
00696       // each other
00697       std::vector<size_t> open_vertices;
00698       int current_vertex = pass_1_count;
00699       getAdjacentNodes(current_vertex, pass_1_graph, open_vertices);
00700       std::vector<int> removed_vertices;
00701       std::pair<int, int> edge;
00702       if (open_vertices.size() == 2 &&
00703           pass_1_vertex_status[open_vertices[0]] == PRESENT &&
00704           pass_1_vertex_status[open_vertices[1]] == PRESENT) {
00705         while(true) {
00706           std::cout << " - has 2 adjacent vertices " << open_vertices[0] << ", " 
00707             << open_vertices[1] << std::endl;
00708           // Check if the 2 adjacent vertices are visible
00709           Point2f location1 = 
00710             getLocationFromGraphId(open_vertices[0], pass_1_graph);
00711           Point2f location2 = 
00712             getLocationFromGraphId(open_vertices[1], pass_1_graph);
00713           bool locations_visible = 
00714             locationsInDirectLineOfSight(location1, location2, map_resp_.map);
00715           if (locations_visible) {
00716             std::cout << " - the 2 adjacent vertices are visible " 
00717               << "- removing vertex." << std::endl; 
00718             pass_1_vertex_status[current_vertex] = REMOVED_REGION_VERTEX;
00719             removed_vertices.push_back(current_vertex);
00720             edge = std::make_pair(open_vertices[0], open_vertices[1]);
00721             bool replacement_found = false;
00722             for (int i = 0; i < 2; ++i) {
00723               std::vector<size_t> adj_vertices;
00724               getAdjacentNodes(open_vertices[i], pass_1_graph, 
00725                   adj_vertices);
00726               if (adj_vertices.size() == 2) {
00727                 size_t new_vertex = (adj_vertices[0] == current_vertex) ? 
00728                   adj_vertices[1] : adj_vertices[0];
00729                 if (pass_1_vertex_status[new_vertex] == PRESENT) {
00730                   current_vertex = open_vertices[i];
00731                   std::cout << " - neighbours may suffer from the same problem"
00732                     << ". checking vertex " << current_vertex << std::endl;
00733                   open_vertices[i] = new_vertex;
00734                   replacement_found = true;
00735                   break;
00736                 }
00737               }
00738             }
00739             if (!replacement_found) {
00740               // Both neighbours on either side had 1 or more than 2 adjacent 
00741               // vertices
00742               break;
00743             }
00744           } else {
00745             // left and right vertices not visible
00746             break;
00747           }
00748         }
00749       }
00750 
00751       BOOST_FOREACH(int removed_vertex, removed_vertices) {
00752         removed_vertex_map[removed_vertex] = edge;
00753       }
00754 
00755       if (removed_vertices.size() != 0) {
00756         // Add the extra edge
00757         std::cout << " - adding extra edge between " << edge.first <<
00758           " " << edge.second << std::endl;
00759         rr_extra_edges.push_back(edge);
00760         continue;
00761       }
00762 
00763       // Otherwise insert this as is into the point graph
00764       Graph::vertex_descriptor point_vi = boost::add_vertex(pass_2_graph);
00765       pass_2_graph[point_vi] = pass_1_graph[*vi];
00766       pass_1_vertex_to_pass_2_vertex_map[pass_1_count] = 
00767         pass_2_count;
00768 
00769       ++pass_2_count;
00770     }
00771 
00772     // Insert all edges that can be inserted
00773     
00774     // Add edges from the pass_1 graph that can be placed as is
00775     pass_1_count = 0;
00776     for (boost::tie(vi, vend) = boost::vertices(pass_1_graph); vi != vend;
00777         ++vi, ++pass_1_count) {
00778       if (pass_1_vertex_status[pass_1_count] == PRESENT) {
00779         std::vector<size_t> adj_vertices;
00780         getAdjacentNodes(pass_1_count, pass_1_graph, adj_vertices);
00781         BOOST_FOREACH(size_t adj_vertex, adj_vertices) {
00782           if (pass_1_vertex_status[adj_vertex] == PRESENT &&
00783               adj_vertex > pass_1_count) {
00784             Graph::vertex_descriptor vi,vj;
00785             int vertex1 = 
00786               pass_1_vertex_to_pass_2_vertex_map[pass_1_count];
00787             int vertex2 = pass_1_vertex_to_pass_2_vertex_map[adj_vertex];
00788             vi = boost::vertex(vertex1, pass_2_graph);
00789             vj = boost::vertex(vertex2, pass_2_graph);
00790             Graph::edge_descriptor e; bool b;
00791             boost::tie(e,b) = boost::add_edge(vi, vj, pass_2_graph);
00792           }
00793         }
00794       }
00795     }
00796 
00797     // Add all the extra edges
00798     typedef std::pair<int, int> int2pair;
00799     BOOST_FOREACH(const int2pair& edge, rr_extra_edges) {
00800       Graph::vertex_descriptor vi,vj;
00801       int vertex1 = 
00802         pass_1_vertex_to_pass_2_vertex_map[edge.first];
00803       int vertex2 = pass_1_vertex_to_pass_2_vertex_map[edge.second];
00804       vi = boost::vertex(vertex1, pass_2_graph);
00805       vj = boost::vertex(vertex2, pass_2_graph);
00806       Graph::edge_descriptor e; bool b;
00807       boost::tie(e,b) = boost::add_edge(vi, vj, pass_2_graph);
00808     }
00809 
00810     pass_2_graph_ = pass_2_graph;
00811 
00812     // Pass 3 - Merge all close vertices and remove any edges that can be
00813     // replaced by 2 edges of marginally longer length
00814     int vertex_merge_threshold = 2.0f / map_resp_.map.info.resolution;
00815     std::cout << std::endl << "==============================" << std::endl;
00816     std::cout << "PASS 3" << std::endl;
00817     std::cout << "==============================" << std::endl << std::endl;
00818     Graph pass_3_graph;
00819     pass_2_count = 0;
00820     int pass_3_count = 0;
00821     std::map<int, int> pass_2_vertex_to_pass_3_vertex_map;
00822     std::vector<int> pass_2_vertex_status(
00823         boost::num_vertices(pass_2_graph), PRESENT);
00824     for (boost::tie(vi, vend) = boost::vertices(pass_2_graph); vi != vend;
00825         ++vi, ++pass_2_count) {
00826 
00827       std::cout << "Analyzing pass 2 graph vtx: " << pass_2_count << std::endl;
00828       if (pass_2_vertex_status[pass_2_count] != PRESENT) {
00829         std::cout << " - vtx already thrown out " << std::endl;
00830         continue;
00831       }
00832 
00833       std::set<int> open_set;
00834       std::set<int> closed_set;
00835       open_set.insert(pass_2_count);
00836       while(open_set.size() != 0) {
00837         int current_vertex = *open_set.begin();
00838         open_set.erase(open_set.begin());
00839         closed_set.insert(current_vertex);
00840         std::vector<size_t> adj_vertices;
00841         getAdjacentNodes(current_vertex, pass_2_graph, adj_vertices);
00842         BOOST_FOREACH(size_t vtx, adj_vertices) {
00843           if (closed_set.count(vtx) || open_set.count(vtx)) {
00844             continue;
00845           }
00846           std::cout << " - checking " << current_vertex << ", " << vtx;
00847           Point2f l1 = getLocationFromGraphId(current_vertex, pass_2_graph);
00848           Point2f l2 = getLocationFromGraphId(vtx, pass_2_graph);
00849           float distance = getMagnitude(l1-l2);
00850           std::cout << " - " << distance;
00851           if (distance < vertex_merge_threshold) {
00852             open_set.insert(vtx);
00853             std::cout << " - WILL MERGE";
00854           }
00855           std::cout << std::endl;
00856         }
00857       }
00858 
00859       Point2f vertex_location = pass_2_graph[*vi].location;
00860       if (closed_set.size() != 1) {
00861         Point2f sum(0,0);
00862         BOOST_FOREACH(int vtx, closed_set) {
00863           pass_2_vertex_status[vtx] = MERGE_VERTEX;
00864           pass_2_vertex_to_pass_3_vertex_map[vtx] = pass_3_count;
00865           sum += getLocationFromGraphId(vtx, pass_2_graph); 
00866         }
00867         vertex_location = (1.0f / closed_set.size()) * sum;
00868       } else {
00869         pass_2_vertex_to_pass_3_vertex_map[pass_2_count] = pass_3_count;
00870       }
00871         
00872       Graph::vertex_descriptor point_vi = boost::add_vertex(pass_3_graph);
00873       pass_3_graph[point_vi].location = vertex_location;
00874       ++pass_3_count;
00875     }
00876 
00877     // Add edges from the pass_1 graph that can be placed as is
00878     pass_2_count = 0;
00879     for (boost::tie(vi, vend) = boost::vertices(pass_2_graph); vi != vend;
00880         ++vi, ++pass_2_count) {
00881       std::cout << "Gen edges pass 2 graph vtx: " << pass_2_count << std::endl;
00882       std::vector<size_t> adj_vertices;
00883       getAdjacentNodes(pass_2_count, pass_2_graph, adj_vertices);
00884       BOOST_FOREACH(size_t adj_vertex, adj_vertices) {
00885         if (adj_vertex > pass_2_count) {
00886           Graph::vertex_descriptor vi,vj;
00887           int vertex1 = pass_2_vertex_to_pass_3_vertex_map[pass_2_count];
00888           int vertex2 = pass_2_vertex_to_pass_3_vertex_map[adj_vertex];
00889           if (vertex1 != vertex2) {
00890             vi = boost::vertex(vertex1, pass_3_graph);
00891             vj = boost::vertex(vertex2, pass_3_graph);
00892             Graph::edge_descriptor e; bool b;
00893             boost::tie(e,b) = boost::edge(vi, vj, pass_3_graph);
00894             if (!b) {
00895               boost::tie(e,b) = boost::add_edge(vi, vj, pass_3_graph);
00896               pass_3_graph[e].weight = getMagnitude(
00897                   getLocationFromGraphId(vertex1, pass_3_graph) - 
00898                   getLocationFromGraphId(vertex2, pass_3_graph));
00899               std::cout << " - gen edge " << vertex1 << " " << vertex2 << std::endl;
00900             }
00901           }
00902         }
00903       }
00904     }
00905 
00906     pass_3_graph_ = pass_3_graph;
00907 
00908     // Now, nudge all vertices to see if you can increase visibility.
00909     pass_3_count = 0;
00910     int neighbourhood = 0.5 / map_resp_.map.info.resolution;
00911     int num_vertices_pass_3 = boost::num_vertices(pass_3_graph);
00912     for (boost::tie(vi, vend) = boost::vertices(pass_3_graph); vi != vend;
00913         ++vi, ++pass_3_count) {
00914       std::cout << "Attempting nudge on vtx: " << pass_3_count << std::endl;
00915       Point2f vtx_loc = getLocationFromGraphId(pass_3_count, pass_3_graph);
00916       int max_visibility = 0, best_i = vtx_loc.x, best_j = vtx_loc.y; 
00917       for (int k = 0; k < num_vertices_pass_3; ++k) {
00918         Point2f k_loc = getLocationFromGraphId(k, pass_3_graph);
00919         if (locationsInDirectLineOfSight(vtx_loc, k_loc, map_resp_.map)) {
00920           ++max_visibility;
00921         }
00922       }
00923       for (int j = vtx_loc.y - neighbourhood / 2; 
00924           j <= vtx_loc.y + neighbourhood / 2; ++j) {
00925         for (int i = vtx_loc.x - neighbourhood / 2; 
00926             i <= vtx_loc.x + neighbourhood / 2; ++i) {
00927           Point2f point_loc(i, j); 
00928           int visibility = 0;
00929           for (int k = 0; k < num_vertices_pass_3; ++k) {
00930             Point2f k_loc = getLocationFromGraphId(k, pass_3_graph);
00931             if (locationsInDirectLineOfSight(point_loc, k_loc, map_resp_.map)) {
00932               ++visibility;
00933             }
00934           }
00935           if (visibility > max_visibility) {
00936             max_visibility = visibility;
00937             best_i = i;
00938             best_j = j;
00939           }
00940         }
00941       }
00942       pass_3_graph[*vi].location = Point2f(best_i, best_j);
00943     }
00944 
00945     // Recompute edge weights
00946     pass_3_count = 0;
00947     for (boost::tie(vi, vend) = boost::vertices(pass_3_graph); vi != vend;
00948         ++vi, ++pass_3_count) {
00949       Point2f vtx1 = getLocationFromGraphId(pass_3_count, pass_3_graph);
00950       std::vector<size_t> adj_vertices;
00951       getAdjacentNodes(pass_3_count, pass_3_graph, adj_vertices);
00952       BOOST_FOREACH(size_t adj_vertex, adj_vertices) {
00953         if (adj_vertex > pass_3_count) {
00954           Point2f vtx2 = getLocationFromGraphId(adj_vertex, pass_3_graph);
00955           Graph::vertex_descriptor vi,vj;
00956           vi = boost::vertex(pass_3_count, pass_3_graph);
00957           vj = boost::vertex(adj_vertex, pass_3_graph);
00958           Graph::edge_descriptor e; bool b;
00959           boost::tie(e,b) = boost::edge(vi, vj, pass_3_graph);
00960           if (b) {
00961             pass_3_graph[e].weight = getMagnitude(vtx1 - vtx2);
00962           }
00963         }
00964       }
00965     }
00966 
00967     pass_4_graph_ = pass_3_graph;
00968 
00969     // Once all the edges have been added, remove edges that fail triangle inequality
00970     pass_3_count = 0;
00971     for (boost::tie(vi, vend) = boost::vertices(pass_3_graph); vi != vend;
00972         ++vi, ++pass_3_count) {
00973       std::cout << "Analyzing edges on vtx " << pass_3_count << std::endl;
00974       std::vector<size_t> adj_vertices;
00975       getAdjacentNodes(pass_3_count, pass_3_graph, adj_vertices);
00976       Point2f vtx1 = getLocationFromGraphId(pass_3_count, pass_3_graph);
00977       BOOST_FOREACH(size_t adj_vertex, adj_vertices) {
00978         if (adj_vertex < pass_3_count)
00979           continue;
00980         std::cout << " - analyzing edge between " << pass_3_count << " and " <<
00981           adj_vertex << std::endl;
00982         Point2f vtx2 = getLocationFromGraphId(adj_vertex, pass_3_graph);
00983         float edge_length = getMagnitude(vtx1 - vtx2);
00984         Graph::vertex_descriptor vi,vj;
00985         vi = boost::vertex(pass_3_count, pass_3_graph);
00986         vj = boost::vertex(adj_vertex, pass_3_graph);
00987         boost::remove_edge(vi, vj, pass_3_graph);
00988         std::vector<size_t> replacement_path;
00989         float path_cost = 
00990           getShortestPathWithDistance(pass_3_count, adj_vertex, replacement_path, pass_3_graph);
00991         if (replacement_path.size() >= 2) {
00992           std::cout << " - fount alternate path cost: " << path_cost << std::endl;
00993         }
00994         if (replacement_path.size() < 2 || path_cost  > 1.05 * edge_length) {
00995           // re-add edge to graph
00996           Graph::edge_descriptor e; bool b;
00997           boost::tie(e,b) = boost::add_edge(vi, vj, pass_3_graph);
00998           pass_3_graph[e].weight = getMagnitude(
00999               getLocationFromGraphId(pass_3_count, pass_3_graph) - 
01000               getLocationFromGraphId(adj_vertex, pass_3_graph));
01001         } else {
01002           std::cout << " - removing edge between " << pass_3_count << " and " <<
01003             adj_vertex << std::endl;
01004         }
01005       }
01006     }
01007 
01008     point_graph_ = pass_3_graph;
01009     
01010   }
01011 
01016   void TopologicalMapper::drawCriticalLines(cv::Mat &image, 
01017       uint32_t orig_x, uint32_t orig_y, bool draw_idx, 
01018       bool visualization_image) {
01019 
01020     for (size_t i = 0; i < critical_points_.size(); ++i) {
01021       cv::Scalar color = cv::Scalar(0);
01022       if (draw_idx) {
01023         color = cv::Scalar((uint16_t)i);
01024       }
01025       VoronoiPoint &vp = critical_points_[i];
01026       if (vp.basis_points.size() != 2) {
01027         std::cerr << "ERROR: Found a critical point with more than 2 basis" 
01028           << "points. This should not have happened" << std::endl;
01029       } else {
01030         Point2d &p1(vp.basis_points[0]);
01031         Point2d &p2(vp.basis_points[1]);
01032         if (!visualization_image) {
01033           cv::line(image, 
01034               cv::Point(orig_x + p1.x, orig_y + p1.y),
01035               cv::Point(orig_x + p2.x, orig_y + p2.y), 
01036               color,
01037               1, 4); // draw a 4 connected line
01038         } else {
01039           color = cv::Scalar(0, 0, 255);
01040           cv::line(image, 
01041               cv::Point(orig_x + p1.x, orig_y + p1.y),
01042               cv::Point(orig_x + p2.x, orig_y + p2.y), 
01043               color,
01044               2, CV_AA); // draw a 4 connected line
01045         }
01046       }
01047     }
01048   }
01049 
01050 } /* bwi_mapper */
01051 


bwi_mapper
Author(s): Piyush Khandelwal
autogenerated on Thu Jun 6 2019 17:57:21