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
00041 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_
00042 #define PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_
00043
00044 #include <pcl/sample_consensus/sac_model.h>
00045 #include <pcl/sample_consensus/sac_model_plane.h>
00046 #include <pcl/sample_consensus/sac_model_perpendicular_plane.h>
00047 #include <pcl/sample_consensus/model_types.h>
00048
00049 namespace pcl
00050 {
00085 template <typename PointT, typename PointNT>
00086 class SampleConsensusModelNormalParallelPlane : public SampleConsensusModelPlane<PointT>, public SampleConsensusModelFromNormals<PointT, PointNT>
00087 {
00088 public:
00089 using SampleConsensusModel<PointT>::input_;
00090 using SampleConsensusModel<PointT>::indices_;
00091 using SampleConsensusModelFromNormals<PointT, PointNT>::normals_;
00092 using SampleConsensusModelFromNormals<PointT, PointNT>::normal_distance_weight_;
00093 using SampleConsensusModel<PointT>::error_sqr_dists_;
00094
00095 typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00096 typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00097 typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00098
00099 typedef typename SampleConsensusModelFromNormals<PointT, PointNT>::PointCloudNPtr PointCloudNPtr;
00100 typedef typename SampleConsensusModelFromNormals<PointT, PointNT>::PointCloudNConstPtr PointCloudNConstPtr;
00101
00102 typedef boost::shared_ptr<SampleConsensusModelNormalParallelPlane> Ptr;
00103
00108 SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud,
00109 bool random = false)
00110 : SampleConsensusModelPlane<PointT> (cloud, random)
00111 , SampleConsensusModelFromNormals<PointT, PointNT> ()
00112 , axis_ (Eigen::Vector4f::Zero ())
00113 , distance_from_origin_ (0)
00114 , eps_angle_ (-1.0)
00115 , cos_angle_ (-1.0)
00116 , eps_dist_ (0.0)
00117 {
00118 }
00119
00125 SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud,
00126 const std::vector<int> &indices,
00127 bool random = false)
00128 : SampleConsensusModelPlane<PointT> (cloud, indices, random)
00129 , SampleConsensusModelFromNormals<PointT, PointNT> ()
00130 , axis_ (Eigen::Vector4f::Zero ())
00131 , distance_from_origin_ (0)
00132 , eps_angle_ (-1.0)
00133 , cos_angle_ (-1.0)
00134 , eps_dist_ (0.0)
00135 {
00136 }
00137
00139 virtual ~SampleConsensusModelNormalParallelPlane () {}
00140
00144 inline void
00145 setAxis (const Eigen::Vector3f &ax) { axis_.head<3> () = ax; axis_.normalize ();}
00146
00148 inline Eigen::Vector3f
00149 getAxis () { return (axis_.head<3> ()); }
00150
00155 inline void
00156 setEpsAngle (const double ea) { eps_angle_ = ea; cos_angle_ = fabs (cos (ea));}
00157
00159 inline double
00160 getEpsAngle () { return (eps_angle_); }
00161
00165 inline void
00166 setDistanceFromOrigin (const double d) { distance_from_origin_ = d; }
00167
00169 inline double
00170 getDistanceFromOrigin () { return (distance_from_origin_); }
00171
00175 inline void
00176 setEpsDist (const double delta) { eps_dist_ = delta; }
00177
00179 inline double
00180 getEpsDist () { return (eps_dist_); }
00181
00187 void
00188 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00189 const double threshold,
00190 std::vector<int> &inliers);
00191
00198 virtual int
00199 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00200 const double threshold);
00201
00206 void
00207 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00208 std::vector<double> &distances);
00209
00211 inline pcl::SacModel
00212 getModelType () const { return (SACMODEL_NORMAL_PARALLEL_PLANE); }
00213
00214 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00215
00216 protected:
00220 bool
00221 isModelValid (const Eigen::VectorXf &model_coefficients);
00222
00223 private:
00225 Eigen::Vector4f axis_;
00226
00228 double distance_from_origin_;
00229
00231 double eps_angle_;
00232
00234 double cos_angle_;
00236 double eps_dist_;
00237 };
00238 }
00239
00240 #ifdef PCL_NO_PRECOMPILE
00241 #include <pcl/sample_consensus/impl/sac_model_normal_parallel_plane.hpp>
00242 #endif
00243
00244 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_NORMALPARALLELPLANE_H_