ray_trace.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/line/ray_trace.h>
00036 #include <cmath>
00037 #include <limits>
00038 
00039 namespace nav_grid_iterators
00040 {
00041 RayTrace::RayTrace(double x0, double y0, double x1, double y1, bool include_last_index)
00042   : AbstractLineIterator(), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index)
00043 {
00044   dx_ = std::abs(x1 - x0);
00045   dy_ = std::abs(y1 - y0);
00046   index_.x = static_cast<int>(floor(x0));
00047   index_.y = static_cast<int>(floor(y0));
00048 
00049   if (dx_ == 0)
00050   {
00051     loop_inc_x_ = 0;
00052     error_ = std::numeric_limits<double>::max();
00053   }
00054   else if (x1 > x0)
00055   {
00056     loop_inc_x_ = 1;
00057     error_ = (floor(x0) + 1 - x0) * dy_;
00058   }
00059   else
00060   {
00061     loop_inc_x_ = -1;
00062     error_ = (x0 - floor(x0)) * dy_;
00063   }
00064 
00065   if (dy_ == 0)
00066   {
00067     loop_inc_y_ = 0;
00068     error_ -= std::numeric_limits<double>::max();
00069   }
00070   else if (y1 > y0)
00071   {
00072     loop_inc_y_ = 1;
00073     error_ -= (floor(y0) + 1 - y0) * dx_;
00074   }
00075   else
00076   {
00077     loop_inc_y_ = -1;
00078     error_ -= (y0 - floor(y0)) * dx_;
00079   }
00080 
00081   /* Since we check if the index is equal to the second point in the line,
00082    * we have to check for this one edge case to ensure we don't get into a rounding
00083    * problem, resulting in an off-by-one error.
00084    */
00085   if (!include_last_index && x1 < x0 && y1 - floor(y1) == 0.0)
00086   {
00087     error_ += 1e-10;
00088   }
00089 
00090   initial_error_ = error_;
00091 
00092   // Special use case when start and end point are the same AND we want to include that point
00093   if (include_last_index && loop_inc_x_ == 0 && loop_inc_y_ == 0)
00094   {
00095     loop_inc_x_ = 1;
00096   }
00097 }
00098 
00099 RayTrace::RayTrace(const nav_grid::SignedIndex& index,
00100      double x0, double y0, double x1, double y1, bool include_last_index,
00101      double dx, double dy, double initial_error, int loop_inc_x, int loop_inc_y)
00102   : AbstractLineIterator(index), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index),
00103     dx_(dx), dy_(dy), error_(initial_error), initial_error_(initial_error),
00104     loop_inc_x_(loop_inc_x), loop_inc_y_(loop_inc_y)
00105 {
00106 }
00107 
00108 RayTrace RayTrace::begin() const
00109 {
00110   return RayTrace(nav_grid::SignedIndex(x0_, y0_), x0_, y0_, x1_, y1_, include_last_index_,
00111                   dx_, dy_, initial_error_, loop_inc_x_, loop_inc_y_);
00112 }
00113 
00114 RayTrace RayTrace::end() const
00115 {
00116   int x_diff = abs(static_cast<int>(x0_) - static_cast<int>(x1_));
00117   int y_diff = abs(static_cast<int>(y0_) - static_cast<int>(y1_));
00118   double final_error = initial_error_ - dx_ * y_diff + dy_ * x_diff;
00119   RayTrace end(nav_grid::SignedIndex(x1_, y1_), x0_, y0_, x1_, y1_, include_last_index_,
00120                dx_, dy_, final_error, loop_inc_x_, loop_inc_y_);
00121 
00122   // If we want the last_index, return an iterator that is whatever is one-past the end coordinates
00123   if (include_last_index_)
00124     end.increment();
00125   return end;
00126 }
00127 
00128 void RayTrace::increment()
00129 {
00130   if (error_ > 0.0)
00131   {
00132     index_.y += loop_inc_y_;
00133     error_ -= dx_;
00134   }
00135   else
00136   {
00137     index_.x += loop_inc_x_;
00138     error_ += dy_;
00139   }
00140 }
00141 
00142 nav_grid::SignedIndex RayTrace::getFinalIndex() const
00143 {
00144   return end().index_;
00145 }
00146 }  // namespace nav_grid_iterators


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