Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #ifndef PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP
00036 #define PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP
00037 
00038 #include <pcl/filters/plane_clipper3D.h>
00039 
00040 template<typename PointT>
00041 pcl::PlaneClipper3D<PointT>::PlaneClipper3D (const Eigen::Vector4f& plane_params)
00042 : plane_params_ (plane_params)
00043 {
00044 }
00045 
00046 template<typename PointT>
00047 pcl::PlaneClipper3D<PointT>::~PlaneClipper3D () throw ()
00048 {
00049 }
00050 
00051 template<typename PointT> void
00052 pcl::PlaneClipper3D<PointT>::setPlaneParameters (const Eigen::Vector4f& plane_params)
00053 {
00054   plane_params_ = plane_params;
00055 }
00056 
00057 template<typename PointT> const Eigen::Vector4f&
00058 pcl::PlaneClipper3D<PointT>::getPlaneParameters () const
00059 {
00060   return plane_params_;
00061 }
00062 
00063 template<typename PointT> pcl::Clipper3D<PointT>*
00064 pcl::PlaneClipper3D<PointT>::clone () const
00065 {
00066   return new PlaneClipper3D<PointT> (plane_params_);
00067 }
00068 
00069 template<typename PointT> float
00070 pcl::PlaneClipper3D<PointT>::getDistance (const PointT& point) const
00071 {
00072   return (plane_params_[0] * point.x + plane_params_[1] * point.y + plane_params_[2] * point.z + plane_params_[3]);
00073 }
00074 
00075 template<typename PointT> bool
00076 pcl::PlaneClipper3D<PointT>::clipPoint3D (const PointT& point) const
00077 {
00078   return ((plane_params_[0] * point.x + plane_params_[1] * point.y + plane_params_[2] * point.z ) >= -plane_params_[3]);
00079 }
00080 
00084 template<typename PointT> bool
00085 pcl::PlaneClipper3D<PointT>::clipLineSegment3D (PointT& point1, PointT& point2) const
00086 {
00087   float dist1 = getDistance (point1);
00088   float dist2 = getDistance (point2);
00089 
00090   if (dist1 * dist2 > 0) 
00091     return (dist1 > 0); 
00092 
00093   float lambda = dist2 / (dist2 - dist1);
00094 
00095   
00096   PointT intersection;
00097   intersection.x = (point1.x - point2.x) * lambda + point2.x;
00098   intersection.y = (point1.y - point2.y) * lambda + point2.y;
00099   intersection.z = (point1.z - point2.z) * lambda + point2.z;
00100 
00101   
00102   if (dist1 >= 0)
00103     point2 = intersection;
00104   else
00105     point1 = intersection;
00106 
00107   return false;
00108 }
00109 
00113 template<typename PointT> void
00114 pcl::PlaneClipper3D<PointT>::clipPlanarPolygon3D (const std::vector<PointT>& polygon, std::vector<PointT>& clipped_polygon) const
00115 {
00116   clipped_polygon.clear ();
00117   clipped_polygon.reserve (polygon.size ());
00118 
00119   
00120   if (polygon.size () < 3)
00121   {
00122     if (polygon.size () == 1)
00123     {
00124       
00125       if (clipPoint3D (polygon [0]))
00126         clipped_polygon.push_back (polygon [0]);
00127     }
00128     else if (polygon.size () == 2)
00129     {
00130       clipped_polygon.push_back (polygon [0]);
00131       clipped_polygon.push_back (polygon [1]);
00132       if (!clipLineSegment3D (clipped_polygon [0], clipped_polygon [1]))
00133         clipped_polygon.clear ();
00134     }
00135     return;
00136   }
00137 
00138   float previous_distance = getDistance (polygon [0]);
00139 
00140   if (previous_distance > 0)
00141     clipped_polygon.push_back (polygon [0]);
00142 
00143   typename std::vector<PointT>::const_iterator prev_it = polygon.begin ();
00144 
00145   for (typename std::vector<PointT>::const_iterator pIt = prev_it + 1; pIt != polygon.end (); prev_it = pIt++)
00146   {
00147     
00148     float distance = getDistance (*pIt);
00149     if (distance * previous_distance < 0)
00150     {
00151       float lambda = distance / (distance - previous_distance);
00152 
00153       PointT intersection;
00154       intersection.x = (prev_it->x - pIt->x) * lambda + pIt->x;
00155       intersection.y = (prev_it->y - pIt->y) * lambda + pIt->y;
00156       intersection.z = (prev_it->z - pIt->z) * lambda + pIt->z;
00157 
00158       clipped_polygon.push_back (intersection);
00159     }
00160     if (distance > 0)
00161       clipped_polygon.push_back (*pIt);
00162 
00163     previous_distance = distance;
00164   }
00165 }
00166 
00170 template<typename PointT> void
00171 pcl::PlaneClipper3D<PointT>::clipPlanarPolygon3D (std::vector<PointT>& polygon) const
00172 {
00173   std::vector<PointT> clipped;
00174   clipPlanarPolygon3D (polygon, clipped);
00175   polygon = clipped;
00176 }
00177 
00178 
00179 template<typename PointT> void
00180 pcl::PlaneClipper3D<PointT>::clipPointCloud3D (const pcl::PointCloud<PointT>& cloud_in, std::vector<int>& clipped, const std::vector<int>& indices) const
00181 {
00182   if (indices.empty ())
00183   {
00184     clipped.reserve (cloud_in.size ());
00185     
00186 
00187 
00188 
00189 
00190 
00191 
00192 
00193 
00194 
00195 
00196 
00197 
00198 
00199 
00200 
00201 
00202 
00203 
00204 
00205 
00206 
00207 
00208 
00209 
00210 
00211 
00212 
00213 
00214 
00215 
00216 
00217 
00218 
00219 
00220   }
00221   else
00222   {
00223     for (std::vector<int>::const_iterator iIt = indices.begin (); iIt != indices.end (); ++iIt)
00224       if (clipPoint3D (cloud_in[*iIt]))
00225         clipped.push_back (*iIt);
00226   }
00227 }
00228 #endif //PCL_FILTERS_IMPL_PLANE_CLIPPER3D_HPP