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
00036
00037
00038
00039
00040 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_
00041 #define PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_
00042
00043 #include <pcl/sample_consensus/sac_model_plane.h>
00044 #include <pcl/common/common.h>
00045
00046 namespace pcl
00047 {
00064 template <typename PointT>
00065 class SampleConsensusModelParallelPlane : public SampleConsensusModelPlane<PointT>
00066 {
00067 public:
00068 typedef typename SampleConsensusModelPlane<PointT>::PointCloud PointCloud;
00069 typedef typename SampleConsensusModelPlane<PointT>::PointCloudPtr PointCloudPtr;
00070 typedef typename SampleConsensusModelPlane<PointT>::PointCloudConstPtr PointCloudConstPtr;
00071
00072 typedef boost::shared_ptr<SampleConsensusModelParallelPlane> Ptr;
00073
00077 SampleConsensusModelParallelPlane (const PointCloudConstPtr &cloud) :
00078 SampleConsensusModelPlane<PointT> (cloud),
00079 axis_ (Eigen::Vector3f::Zero ()),
00080 eps_angle_ (0.0), sin_angle_ (-1.0)
00081 {
00082 }
00083
00088 SampleConsensusModelParallelPlane (const PointCloudConstPtr &cloud, const std::vector<int> &indices) :
00089 SampleConsensusModelPlane<PointT> (cloud, indices),
00090 axis_ (Eigen::Vector3f::Zero ()),
00091 eps_angle_ (0.0), sin_angle_ (-1.0)
00092 {
00093 }
00094
00098 inline void
00099 setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00100
00102 inline Eigen::Vector3f
00103 getAxis () { return (axis_); }
00104
00109 inline void
00110 setEpsAngle (const double ea) { eps_angle_ = ea; sin_angle_ = fabs (sin (ea));}
00111
00113 inline double
00114 getEpsAngle () { return (eps_angle_); }
00115
00121 void
00122 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00123 const double threshold,
00124 std::vector<int> &inliers);
00125
00132 virtual int
00133 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00134 const double threshold);
00135
00140 void
00141 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00142 std::vector<double> &distances);
00143
00145 inline pcl::SacModel
00146 getModelType () const { return (SACMODEL_PARALLEL_PLANE); }
00147
00148 protected:
00152 bool
00153 isModelValid (const Eigen::VectorXf &model_coefficients);
00154
00156 Eigen::Vector3f axis_;
00157
00159 double eps_angle_;
00160
00162 double sin_angle_;
00163 };
00164 }
00165
00166 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELPLANE_H_