polygon_fill.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include <nav_grid_iterators/polygon_fill.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_2d_utils/polygons.h>
00038 #include <algorithm>
00039 
00040 namespace nav_grid_iterators
00041 {
00042 PolygonFill::PolygonFill(const nav_grid::NavGridInfo* info, nav_2d_msgs::Polygon2D polygon)
00043   : BaseIterator(info), polygon_(polygon), start_index_(0, 0)
00044 {
00045   if (polygon.points.size() == 0)
00046   {
00047     internal_iterator_.reset(new SubGrid(info_, 0, 0, 0, 0));
00048     start_index_ = **internal_iterator_;
00049     index_ = start_index_;
00050     return;
00051   }
00052 
00053   // Find the minimum and maximum coordinates of the vertices
00054   double min_x = polygon_.points[0].x;
00055   double max_x = min_x;
00056   double min_y = polygon_.points[0].y;
00057   double max_y = min_y;
00058   for (const auto& vertex : polygon_.points)
00059   {
00060     min_x = std::min(min_x, vertex.x);
00061     min_y = std::min(min_y, vertex.y);
00062     max_x = std::max(max_x, vertex.x);
00063     max_y = std::max(max_y, vertex.y);
00064   }
00065 
00066   // Save the minimum in grid coordinates
00067   worldToGridBounded(*info_, min_x, min_y, min_x_, min_y_);
00068 
00069   // Calculate the maximum in grid coordinates and then save the width/height
00070   unsigned int max_x_grid, max_y_grid;
00071   worldToGridBounded(*info_, max_x, max_y, max_x_grid, max_y_grid);
00072   width_ = max_x_grid - min_x_ + 1;
00073   height_ = max_y_grid - min_y_ + 1;
00074 
00075   // Initialize internal iterator
00076   internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_));
00077   index_.x = min_x_;
00078   index_.y = min_y_;
00079 
00080   // Iterate to first valid index
00081   if (!isInside(index_.x, index_.y)) ++(*this);
00082   start_index_ = **internal_iterator_;
00083   index_ = start_index_;
00084 }
00085 
00086 PolygonFill::PolygonFill(const PolygonFill& other)
00087   : PolygonFill(other.info_, other.index_, other.polygon_, other.min_x_, other.min_y_, other.width_, other.height_,
00088                 other.start_index_)
00089 {
00090 }
00091 
00092 PolygonFill::PolygonFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index,
00093                nav_2d_msgs::Polygon2D polygon,
00094                unsigned int min_x, unsigned int min_y, unsigned int width, unsigned int height,
00095                const nav_grid::Index& start_index)
00096   : BaseIterator(info, index), polygon_(polygon),
00097     min_x_(min_x), min_y_(min_y), width_(width), height_(height), start_index_(start_index)
00098 {
00099   internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_));
00100 }
00101 
00102 PolygonFill& PolygonFill::operator=(const PolygonFill& other)
00103 {
00104   info_ = other.info_;
00105   index_ = other.index_;
00106   polygon_ = other.polygon_;
00107   min_x_ = other.min_x_;
00108   min_y_ = other.min_y_;
00109   width_ = other.width_;
00110   height_ = other.height_;
00111   start_index_ = other.start_index_;
00112   internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_));
00113   return *this;
00114 }
00115 
00116 bool PolygonFill::isInside(unsigned int x, unsigned int y) const
00117 {
00118   // Determine if the current index is inside the polygon using the number of crossings method
00119   double wx, wy;
00120   gridToWorld(*info_, x, y, wx, wy);
00121   return nav_2d_utils::isInside(polygon_, wx, wy);
00122 }
00123 
00124 PolygonFill PolygonFill::begin() const
00125 {
00126   return PolygonFill(info_, start_index_, polygon_, min_x_, min_y_, width_, height_, start_index_);
00127 }
00128 
00129 PolygonFill PolygonFill::end() const
00130 {
00131   return PolygonFill(info_, *internal_iterator_->end(), polygon_, min_x_, min_y_, width_, height_,
00132                 start_index_);
00133 }
00134 
00135 void PolygonFill::increment()
00136 {
00137   ++(*internal_iterator_);
00138   index_ = **internal_iterator_;
00139   while (*internal_iterator_ != internal_iterator_->end())
00140   {
00141     if (isInside(index_.x, index_.y))
00142       break;
00143     ++(*internal_iterator_);
00144     index_ = **internal_iterator_;
00145   }
00146 }
00147 
00148 bool PolygonFill::fieldsEqual(const PolygonFill& other)
00149 {
00150   return nav_2d_utils::equals(polygon_, other.polygon_);
00151 }
00152 
00153 }  // namespace nav_grid_iterators


nav_grid_iterators
Author(s):
autogenerated on Wed Jun 26 2019 20:09:45