spiral.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/spiral.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 
00038 namespace nav_grid_iterators
00039 {
00040 Spiral::Spiral(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius)
00041   : BaseIterator(info), center_x_(center_x), center_y_(center_y), distance_(0), start_index_(0, 0)
00042 {
00043   radius_sq_ = radius * radius;
00044   max_distance_ = ceil(radius / info->resolution);
00045   loadRing();
00046   index_ = **internal_iterator_;
00047   start_index_ = index_;
00048 }
00049 
00050 Spiral::Spiral(const Spiral& other)
00051   : Spiral(other.info_, other.index_, other.center_x_, other.center_y_, other.radius_sq_,
00052            other.distance_, other.max_distance_, other.start_index_)
00053 {
00054 }
00055 
00056 Spiral::Spiral(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x, double center_y,
00057                double radius_sq, unsigned int distance, unsigned int max_distance,
00058                const nav_grid::Index& start_index)
00059   : BaseIterator(info, index), center_x_(center_x), center_y_(center_y), radius_sq_(radius_sq),
00060     distance_(distance), max_distance_(max_distance), start_index_(start_index)
00061 {
00062   loadRing();
00063   if (distance_ < max_distance_)
00064   {
00065     index_ = **internal_iterator_;
00066     start_index_ = index_;
00067   }
00068 }
00069 
00070 Spiral& Spiral::operator=(const Spiral& other)
00071 {
00072   info_ = other.info_;
00073   index_ = other.index_;
00074   center_x_ = other.center_x_;
00075   center_y_ = other.center_y_;
00076   radius_sq_ = other.radius_sq_;
00077   distance_ = other.distance_;
00078   max_distance_ = other.max_distance_;
00079   start_index_ = other.start_index_;
00080   loadRing();
00081   if (distance_ < max_distance_)
00082   {
00083     index_ = **internal_iterator_;
00084     start_index_ = index_;
00085   }
00086   return *this;
00087 }
00088 
00089 Spiral Spiral::begin() const
00090 {
00091   return Spiral(info_, start_index_, center_x_, center_y_, radius_sq_, 0, max_distance_, start_index_);
00092 }
00093 
00094 Spiral Spiral::end() const
00095 {
00096   return Spiral(info_, start_index_, center_x_, center_y_, radius_sq_, max_distance_ + 1, max_distance_,
00097                 start_index_);
00098 }
00099 
00100 void Spiral::increment()
00101 {
00102   while (distance_ <= max_distance_)
00103   {
00104     ++(*internal_iterator_);
00105     if (*internal_iterator_ == internal_iterator_->end())
00106     {
00107       ++distance_;
00108       if (distance_ > max_distance_)
00109       {
00110         index_ = start_index_;
00111         return;
00112       }
00113       loadRing();
00114     }
00115     index_ = **internal_iterator_;
00116     if (isInside(index_.x, index_.y))
00117     {
00118       break;
00119     }
00120   }
00121   if (distance_ > max_distance_)
00122   {
00123     index_ = start_index_;
00124   }
00125 }
00126 
00127 bool Spiral::fieldsEqual(const Spiral& other)
00128 {
00129   return center_x_ == other.center_x_ && center_y_ == other.center_y_ &&
00130          radius_sq_ == other.radius_sq_ && distance_ == other.distance_;
00131 }
00132 
00133 void Spiral::loadRing()
00134 {
00135   while (distance_ <= max_distance_)
00136   {
00137     internal_iterator_.reset(new CircleOutline(info_, center_x_, center_y_, distance_));
00138 
00139     if (*internal_iterator_ != internal_iterator_->end())
00140       break;
00141     ++distance_;
00142   }
00143 }
00144 
00145 bool Spiral::isInside(unsigned int x, unsigned int y) const
00146 {
00147   double wx, wy;
00148   gridToWorld(*info_, x, y, wx, wy);
00149   double dx = wx - center_x_;
00150   double dy = wy - center_y_;
00151   return (dx * dx + dy * dy) < radius_sq_;
00152 }
00153 
00154 }  // namespace nav_grid_iterators


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