line_iterator.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
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 Willow Garage, Inc. 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 OWNER 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 
00036 #ifndef __PCL_LINE_ITERATOR__
00037 #define __PCL_LINE_ITERATOR__
00038 #include "organized_index_iterator.h"
00039 
00040 namespace pcl
00041 {
00048 class LineIterator : public OrganizedIndexIterator
00049 {
00050   public:
00052     typedef enum {Neighbor4 = 4, Neighbor8 = 8} Neighborhood;
00053   public:
00062     LineIterator (unsigned x_start, unsigned y_start, unsigned x_end, unsigned y_end, unsigned width, const Neighborhood& neighborhood = Neighbor8);
00063     
00065     virtual ~LineIterator ();
00066     
00067     virtual void operator ++ ();
00068     virtual unsigned getRowIndex () const;
00069     virtual unsigned getColumnIndex () const;
00070     virtual bool isValid () const;
00071     virtual void reset ();
00072   protected:
00076     void init (const Neighborhood& neighborhood);
00077     
00079     unsigned x_;
00080     
00082     unsigned y_;
00083     
00085     unsigned x_start_;
00086     
00088     unsigned y_start_;
00089     
00091     unsigned x_end_;
00092     
00094     unsigned y_end_;
00095     
00096     // calculated values
00098     int error_;
00099     
00101     int error_max_;
00102     
00104     int error_minus_;
00105     
00107     int error_plus_;
00108     
00110     int x_plus_;
00111 
00113     int y_plus_;
00114     
00116     int x_minus_;
00117 
00119     int y_minus_;
00120     
00122     int index_plus_;
00123 
00125     int index_minus_;
00126 };
00127 
00131 
00132 
00134 inline LineIterator::LineIterator (unsigned x_start, unsigned y_start, unsigned x_end, unsigned y_end, unsigned width, const Neighborhood& neighborhood)
00135 : OrganizedIndexIterator (width)
00136 , x_start_ (x_start)
00137 , y_start_ (y_start)
00138 , x_end_ (x_end)
00139 , y_end_ (y_end)
00140 {
00141   init (neighborhood);
00142 }
00143 
00145 inline LineIterator::~LineIterator ()
00146 {  
00147 }
00148 
00150 inline void
00151 LineIterator::init (const Neighborhood& neighborhood)
00152 {
00153   x_ = x_start_;
00154   y_ = y_start_;
00155   index_ = x_ * width_ + y_;
00156   error_ = 0;
00157 
00158   int delta_x = x_end_ - x_start_;
00159   int delta_y = y_end_ - y_start_;
00160   
00161   int x_dir = ( (delta_x > 0) ? 1 : -1 ) ;
00162   int y_dir = ( (delta_y > 0) ? 1 : -1 ) ;
00163 
00164   delta_x *= x_dir;
00165   delta_y *= y_dir;
00166   
00167   if(delta_x >= delta_y)
00168   {
00169     if( neighborhood == Neighbor4 )
00170     {
00171       error_max_ = delta_x - delta_y;
00172       x_minus_ = 0;
00173       y_minus_ = y_dir;
00174       x_plus_  = x_dir;
00175       y_plus_  = 0;
00176 
00177       error_minus_ = -(delta_x * 2);
00178       error_plus_  = (delta_y * 2);
00179     }
00180     else
00181     {
00182       error_max_ = delta_x - (delta_y * 2);
00183       x_minus_ = x_dir;
00184       y_minus_ = y_dir;
00185       x_plus_  = x_dir;
00186       y_plus_  = 0;
00187         
00188       error_minus_ = (delta_y - delta_x) * 2;
00189       error_plus_  = (delta_y * 2);
00190     }
00191   }
00192   else
00193   {
00194     if( neighborhood == Neighbor4 )
00195     {
00196       error_max_ = delta_y - delta_x;
00197       x_minus_ = x_dir;
00198       y_minus_ = 0;
00199       x_plus_  = 0;
00200       y_plus_  = y_dir;
00201 
00202       error_minus_ = -(delta_y * 2);
00203       error_plus_  = (delta_x * 2);
00204     }
00205     else
00206     {
00207       error_max_ = delta_y - (delta_x * 2);
00208       x_minus_ = x_dir;
00209       y_minus_ = y_dir;
00210       x_plus_  = 0;
00211       y_plus_  = y_dir;
00212 
00213       error_minus_ = (delta_x - delta_y) * 2;
00214       error_plus_  = (delta_x * 2);
00215     }
00216   }
00217 
00218   index_minus_ = x_minus_ + y_minus_ * width_;
00219   index_plus_ = x_plus_ + y_plus_ * width_;  
00220 }
00221 
00223 inline void
00224 LineIterator::operator ++ ()
00225 {
00226   if (error_ >= error_max_ )
00227   {
00228     x_ += x_minus_;
00229     y_ += y_minus_;
00230     error_ += error_minus_;
00231     index_ += index_minus_;
00232   }
00233   else
00234   {
00235     x_ += x_plus_;
00236     y_ += y_plus_;
00237     error_ += error_plus_;
00238     index_ += index_plus_;
00239   }  
00240 }
00241 
00243 inline unsigned
00244 LineIterator::getRowIndex () const
00245 {
00246   return y_;
00247 }
00248 
00250 inline unsigned
00251 LineIterator::getColumnIndex () const
00252 {
00253   return x_;
00254 }
00255 
00257 inline bool
00258 LineIterator::isValid () const
00259 {
00260   return (x_ != x_end_ || y_ != y_end_);
00261 }
00262 
00264 inline void
00265 LineIterator::reset ()
00266 {
00267   x_ = x_start_;
00268   y_ = y_start_;
00269   error_ = 0;
00270   index_ = x_ * width_ + y_;
00271 }
00272 
00273 } // namespace pcl
00274 
00275 #endif // __PCL_LINE_ITERATOR__


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:13