voronoi_approximator.cpp
Go to the documentation of this file.
00001 
00038 #include <algorithm>
00039 #include <cmath>
00040 #include <cstdlib>
00041 
00042 #include <bwi_mapper/voronoi_approximator.h>
00043 #include <bwi_mapper/map_utils.h>
00044 #include <bwi_mapper/point_utils.h>
00045 
00046 #include <opencv2/opencv_modules.hpp>
00047 #ifdef HAVE_OPENCV_IMGPROC
00048 // this is OpenCV 3 and we need extra includes
00049 #include <opencv2/imgproc/imgproc.hpp>
00050 #endif
00051 
00052 namespace bwi_mapper {
00053 
00063   void VoronoiApproximator::findVoronoiPoints(double threshold, 
00064       bool is_naive, int sub_pixel_sampling) {
00065 
00066     // Get the inflated cost map
00067     inflateMap(threshold, map_resp_.map, inflated_map_);
00068 
00069     // Compute the voronoi points
00070     double pixel_threshold = 
00071       ceil(threshold / map_resp_.map.info.resolution);
00072 
00073     uint32_t max_dimension = 
00074       std::max(inflated_map_.info.height, inflated_map_.info.width);
00075 
00076     for (int j = 0; j < sub_pixel_sampling * (inflated_map_.info.height - 1); ++j) {
00077       if (j % sub_pixel_sampling == 0) {
00078         std::cout << "findVoronoiPoints(): On row : " << j / sub_pixel_sampling << std::endl;
00079       }
00080       for (int i = 0; i < sub_pixel_sampling * (inflated_map_.info.width - 1); 
00081           ++i) {
00082 
00083         Point2f center_pt((i + ((float)sub_pixel_sampling / 2)) / ((float)sub_pixel_sampling) + 0.001,
00084             (j + ((float)sub_pixel_sampling / 2)) / ((float)sub_pixel_sampling) + 0.001);
00085 
00086         // if (center_pt.x < inflated_map_.info.width / 2 ||
00087         //     i >= inflated_map_.info.width / 2 + 1)
00088         //   continue;
00089         // if (j < inflated_map_.info.height / 2 ||
00090         //     j >= inflated_map_.info.height / 2 + 1)
00091         //   continue;
00092 
00093         VoronoiPoint vp(lrint(center_pt.x), lrint(center_pt.y));
00094 
00095         // Check if this location is too close to a given obstacle
00096         uint32_t map_idx = MAP_IDX(inflated_map_.info.width, vp.x, vp.y);
00097         if (inflated_map_.data[map_idx] != 0) {
00098           continue;
00099         }
00100 
00101         /* std::cout << "Checking " << center_pt << ", will mark " << vp << std::endl; */
00102 
00103         // Use the boxes to find obstacles
00104         for (int box = pixel_threshold; box < max_dimension; ++box) {
00105 
00106           // Early termination crit - no more hope of finding more obstacles
00107           // at the same distance as the one found already
00108           if (vp.basis_points.size() != 0 &&
00109               box > vp.basis_distance + 1) {
00110             break;
00111           }
00112 
00113           // Get obstacles at this box size
00114           std::vector<Point2d> obstacles;
00115           int low_j = lrint(center_pt.y - box - 1);
00116           int high_j = lrint(center_pt.y + box);
00117           int low_i = lrint(center_pt.x - box - 1);
00118           int high_i = lrint(center_pt.x + box);
00119 
00120           /* std::cout << " - box " << box << " [" << low_i << "," << low_j << "," << high_i << "," << high_j << "]" << std::endl;  */
00121 
00122           // If we hit the side of the images + 1, we've seen all possible
00123           // sites
00124           if (low_i < 0 || low_j < 0 || 
00125               high_i >= inflated_map_.info.width 
00126               || high_j >= inflated_map_.info.height) {
00127             break;
00128           }
00129 
00130           // Corners of the box + vertical edges
00131           for (int j_box = low_j; j_box <= high_j; ++j_box) {
00132             for (int i_box = low_i; i_box <= high_i; 
00133                 i_box += high_i - low_i) {
00134               uint32_t map_idx_box = 
00135                 MAP_IDX(inflated_map_.info.width, i_box, j_box);
00136               bool occupied = map_resp_.map.data[map_idx_box];
00137               if (occupied) {
00138                 Point2d p(i_box, j_box);
00139                 Point2f f(i_box + 0.5, j_box + 0.5);
00140                 p.distance_from_ref = bwi_mapper::getMagnitude(f - center_pt);
00141                 obstacles.push_back(p);
00142               }
00143             }
00144           }
00145 
00146           // horizontal edges
00147           for (int j_box = low_j; j_box <= high_j;
00148               j_box += high_j - low_j) {
00149             for (int i_box = low_i + 1; i_box < high_i + 1; ++i_box) {
00150               uint32_t map_idx_box = 
00151                 MAP_IDX(inflated_map_.info.width, i_box, j_box);
00152               bool occupied = map_resp_.map.data[map_idx_box];
00153               if (occupied) {
00154                 Point2d p(i_box, j_box);
00155                 Point2f f(i_box + 0.5, j_box + 0.5);
00156                 p.distance_from_ref = bwi_mapper::getMagnitude(f - center_pt);
00157                 obstacles.push_back(p);
00158               }
00159             }
00160           }
00161 
00162           // Check if any obstacles are found
00163           if (obstacles.size() == 0) {
00164             continue;
00165           }
00166 
00167           // Now that obstacles are available, sort and add to the vp as
00168           // necessary
00169           if (!is_naive) {
00170             std::sort(obstacles.begin(), obstacles.end(), 
00171                 Point2dDistanceComp());
00172           }
00173           for (size_t q = 0; q < obstacles.size(); q++) {
00174             vp.addBasisCandidate(obstacles[q], pixel_threshold, 
00175                 inflated_map_, is_naive);
00176           }
00177         }
00178 
00179         if (vp.basis_points.size() >= 2) {
00180           voronoi_points_.push_back(vp);
00181         }
00182         
00183       }
00184     }
00185 
00186     // Compute average basis distance for each voronoi point
00187     for (size_t i = 0; i < voronoi_points_.size(); ++i) {
00188       VoronoiPoint &vp = voronoi_points_[i];
00189       float basis_distance_sum = 0;
00190       for (size_t j = 0; j < vp.basis_points.size(); ++j) {
00191         basis_distance_sum += vp.basis_points[j].distance_from_ref;
00192       }
00193       vp.average_clearance = basis_distance_sum / vp.basis_points.size();
00194       std::cout << "Found VP at " << vp << " with clearance " << vp.average_clearance << std::endl;
00195     }
00196 
00197     // Label the voronoi diagram as being available
00198     initialized_ = true;
00199   }
00200 
00206   void VoronoiApproximator::drawOutput(cv::Mat &image) {
00207     if (!initialized_) {
00208       throw std::runtime_error("drawOutput(): voronoi diagram not "
00209           "initialized, call findVoronoiPoints first");
00210     }
00211     drawMap(image);
00212     drawMap(image, map_resp_.map.info.width);
00213     drawVoronoiPoints(image, map_resp_.map.info.width);
00214   }
00215 
00220   void VoronoiApproximator::printVoronoiPoints() {
00221     for (size_t i = 0; i < voronoi_points_.size(); ++i) {
00222       VoronoiPoint &vp = voronoi_points_[i];
00223       std::cout << " (" << vp.x << "," << vp.y << "): ";
00224       for (size_t j = 0; j < vp.basis_points.size(); ++j) {
00225         std::cout << " (" << vp.basis_points[j].x << "," 
00226           << vp.basis_points[j].y << "," 
00227           << vp.basis_points[j].distance_from_ref << "), ";
00228       }
00229       std::cout << std::endl;
00230     }
00231   }
00232 
00237   void VoronoiApproximator::drawVoronoiPoints(cv::Mat &image, 
00238       uint32_t orig_x, uint32_t orig_y) {
00239     for (size_t i = 0; i < voronoi_points_.size(); ++i) {
00240       VoronoiPoint &vp = voronoi_points_[i];
00241       cv::Point p(vp.x + orig_x, orig_y + vp.y);
00242       cv::circle(image, p, 1, cv::Scalar(255,0,0), -1, CV_AA);
00243       // image.at<cv::Vec3b>
00244       //   (orig_y + vp.y, vp.x + orig_x) = 
00245       //   cv::Vec3b(255,0,0);
00246     }
00247   }
00248 
00249 } /* bwi_mapper */


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