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_PARALLELLINE_H_
00042 #define PCL_SAMPLE_CONSENSUS_MODEL_PARALLELLINE_H_
00043
00044 #include <pcl/sample_consensus/sac_model_line.h>
00045 #include <pcl/sample_consensus/sac_model_perpendicular_plane.h>
00046
00047 namespace pcl
00048 {
00062 template <typename PointT>
00063 class SampleConsensusModelParallelLine : public SampleConsensusModelLine<PointT>
00064 {
00065 public:
00066 typedef typename SampleConsensusModelLine<PointT>::PointCloud PointCloud;
00067 typedef typename SampleConsensusModelLine<PointT>::PointCloudPtr PointCloudPtr;
00068 typedef typename SampleConsensusModelLine<PointT>::PointCloudConstPtr PointCloudConstPtr;
00069
00070 typedef boost::shared_ptr<SampleConsensusModelParallelLine> Ptr;
00071
00076 SampleConsensusModelParallelLine (const PointCloudConstPtr &cloud,
00077 bool random = false)
00078 : SampleConsensusModelLine<PointT> (cloud, random)
00079 , axis_ (Eigen::Vector3f::Zero ())
00080 , eps_angle_ (0.0)
00081 {
00082 }
00083
00089 SampleConsensusModelParallelLine (const PointCloudConstPtr &cloud,
00090 const std::vector<int> &indices,
00091 bool random = false)
00092 : SampleConsensusModelLine<PointT> (cloud, indices, random)
00093 , axis_ (Eigen::Vector3f::Zero ())
00094 , eps_angle_ (0.0)
00095 {
00096 }
00097
00099 virtual ~SampleConsensusModelParallelLine () {}
00100
00104 inline void
00105 setAxis (const Eigen::Vector3f &ax) { axis_ = ax; axis_.normalize (); }
00106
00108 inline Eigen::Vector3f
00109 getAxis () { return (axis_); }
00110
00114 inline void
00115 setEpsAngle (const double ea) { eps_angle_ = ea; }
00116
00118 inline double getEpsAngle () { return (eps_angle_); }
00119
00125 void
00126 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00127 const double threshold,
00128 std::vector<int> &inliers);
00129
00136 virtual int
00137 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00138 const double threshold);
00139
00144 void
00145 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00146 std::vector<double> &distances);
00147
00149 inline pcl::SacModel
00150 getModelType () const { return (SACMODEL_PARALLEL_LINE); }
00151
00152 protected:
00156 bool
00157 isModelValid (const Eigen::VectorXf &model_coefficients);
00158
00159 protected:
00161 Eigen::Vector3f axis_;
00162
00164 double eps_angle_;
00165 };
00166 }
00167
00168 #ifdef PCL_NO_PRECOMPILE
00169 #include <pcl/sample_consensus/impl/sac_model_parallel_line.hpp>
00170 #endif
00171
00172 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PARALLELLINE_H_