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_PERPENDICULARPLANE_H_
00041 #define PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_
00042
00043 #include <pcl/sample_consensus/sac_model_plane.h>
00044 #include <pcl/common/common.h>
00045
00046 namespace pcl
00047 {
00069 template <typename PointT>
00070 class SampleConsensusModelPerpendicularPlane : public SampleConsensusModelPlane<PointT>
00071 {
00072 public:
00073 typedef typename SampleConsensusModelPlane<PointT>::PointCloud PointCloud;
00074 typedef typename SampleConsensusModelPlane<PointT>::PointCloudPtr PointCloudPtr;
00075 typedef typename SampleConsensusModelPlane<PointT>::PointCloudConstPtr PointCloudConstPtr;
00076
00077 typedef boost::shared_ptr<SampleConsensusModelPerpendicularPlane> Ptr;
00078
00082 SampleConsensusModelPerpendicularPlane (const PointCloudConstPtr &cloud) :
00083 SampleConsensusModelPlane<PointT> (cloud),
00084 axis_ (Eigen::Vector3f::Zero ()),
00085 eps_angle_ (0.0)
00086 {
00087 }
00088
00093 SampleConsensusModelPerpendicularPlane (const PointCloudConstPtr &cloud,
00094 const std::vector<int> &indices) :
00095 SampleConsensusModelPlane<PointT> (cloud, indices),
00096 axis_ (Eigen::Vector3f::Zero ()),
00097 eps_angle_ (0.0)
00098 {
00099 }
00100
00104 inline void
00105 setAxis (const Eigen::Vector3f &ax) { axis_ = ax; }
00106
00108 inline Eigen::Vector3f
00109 getAxis () { return (axis_); }
00110
00115 inline void
00116 setEpsAngle (const double ea) { eps_angle_ = ea; }
00117
00119 inline double
00120 getEpsAngle () { return (eps_angle_); }
00121
00127 void
00128 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00129 const double threshold,
00130 std::vector<int> &inliers);
00131
00138 virtual int
00139 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00140 const double threshold);
00141
00146 void
00147 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00148 std::vector<double> &distances);
00149
00151 inline pcl::SacModel
00152 getModelType () const { return (SACMODEL_PERPENDICULAR_PLANE); }
00153
00154 protected:
00158 bool
00159 isModelValid (const Eigen::VectorXf &model_coefficients);
00160
00162 Eigen::Vector3f axis_;
00163
00165 double eps_angle_;
00166 };
00167 }
00168
00169 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PERPENDICULARPLANE_H_