circle_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/circle_fill.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 
00038 namespace nav_grid_iterators
00039 {
00040 CircleFill::CircleFill(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius)
00041   : BaseIterator(info), center_x_(center_x), center_y_(center_y), start_index_(0, 0)
00042 {
00043   radius_sq_ = radius * radius;
00044 
00045   double min_x = center_x_ - radius;
00046   double max_x = center_x_ + radius;
00047   double min_y = center_y_ - radius;
00048   double max_y = center_y_ + radius;
00049 
00050   // Calculate and save the minimum coordinates
00051   worldToGridBounded(*info_, min_x, min_y, min_x_, min_y_);
00052 
00053   // Calculate the max coordinates, and save the width/height
00054   unsigned int max_x_grid, max_y_grid;
00055   worldToGridBounded(*info_, max_x, max_y, max_x_grid, max_y_grid);
00056 
00057   width_ = max_x_grid - min_x_ + 1;
00058   height_ = max_y_grid - min_y_ + 1;
00059 
00060   // Initialize internal iterator
00061   internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_));
00062   index_.x = min_x_;
00063   index_.y = min_y_;
00064 
00065   // Iterate to first valid index
00066   if (!isInside(min_x_, min_y_)) ++(*this);
00067   start_index_ = **internal_iterator_;
00068   index_ = start_index_;
00069 }
00070 
00071 CircleFill::CircleFill(const nav_grid_iterators::CircleFill& other)
00072   : CircleFill(other.info_, other.index_, other.center_x_, other.center_y_, other.radius_sq_,
00073                other.min_x_, other.min_y_, other.width_, other.height_, other.start_index_)
00074 {
00075 }
00076 
00077 CircleFill::CircleFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x,
00078                double center_y, double radius_sq, unsigned int min_x, unsigned int min_y, unsigned int width,
00079                unsigned int height, const nav_grid::Index& start_index)
00080   : BaseIterator(info, index), center_x_(center_x), center_y_(center_y), radius_sq_(radius_sq),
00081     min_x_(min_x), min_y_(min_y), width_(width), height_(height), start_index_(start_index)
00082 {
00083   internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_));
00084 }
00085 
00086 CircleFill& CircleFill::operator=(const CircleFill& other)
00087 {
00088   info_ = other.info_;
00089   index_ = other.index_;
00090   center_x_ = other.center_x_;
00091   center_y_ = other.center_y_;
00092   radius_sq_ = other.radius_sq_;
00093   min_x_ = other.min_x_;
00094   min_y_ = other.min_y_;
00095   width_ = other.width_;
00096   height_ = other.height_;
00097   start_index_ = other.start_index_;
00098   internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_));
00099   return *this;
00100 }
00101 
00102 bool CircleFill::isInside(unsigned int x, unsigned int y) const
00103 {
00104   double wx, wy;
00105   gridToWorld(*info_, x, y, wx, wy);
00106   double dx = wx - center_x_;
00107   double dy = wy - center_y_;
00108   return (dx * dx + dy * dy) < radius_sq_;
00109 }
00110 
00111 CircleFill CircleFill::begin() const
00112 {
00113   return CircleFill(info_, start_index_, center_x_, center_y_, radius_sq_, min_x_, min_y_, width_, height_,
00114                     start_index_);
00115 }
00116 
00117 CircleFill CircleFill::end() const
00118 {
00119   return CircleFill(info_, *internal_iterator_->end(), center_x_, center_y_, radius_sq_, min_x_, min_y_,
00120                     width_, height_, start_index_);
00121 }
00122 
00123 void CircleFill::increment()
00124 {
00125   ++(*internal_iterator_);
00126   index_ = **internal_iterator_;
00127   while (*internal_iterator_ != internal_iterator_->end())
00128   {
00129     if (isInside(index_.x, index_.y))
00130       break;
00131     ++(*internal_iterator_);
00132     index_ = **internal_iterator_;
00133   }
00134 }
00135 
00136 bool CircleFill::fieldsEqual(const CircleFill& other)
00137 {
00138   return center_x_ == other.center_x_ && center_y_ == other.center_y_ && radius_sq_ == other.radius_sq_;
00139 }
00140 
00141 }  // namespace nav_grid_iterators


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