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_PLANE_H_
00042 #define PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_
00043
00044 #include <pcl/sample_consensus/sac_model.h>
00045 #include <pcl/sample_consensus/model_types.h>
00046
00047 namespace pcl
00048 {
00049
00055 template <typename Point> inline void
00056 projectPoint (const Point &p, const Eigen::Vector4f &model_coefficients, Point &q)
00057 {
00058
00059 Eigen::Vector4f pp (p.x, p.y, p.z, 1);
00060
00061 float distance_to_plane = pp.dot(model_coefficients);
00062
00063
00064
00065
00066
00067
00068 Eigen::Vector4f q_e = pp - distance_to_plane * model_coefficients;
00069 q.x = q_e[0];
00070 q.y = q_e[1];
00071 q.z = q_e[2];
00072 }
00073
00082 template <typename Point> inline double
00083 pointToPlaneDistanceSigned (const Point &p, double a, double b, double c, double d)
00084 {
00085 return (a * p.x + b * p.y + c * p.z + d);
00086 }
00087
00093 template <typename Point> inline double
00094 pointToPlaneDistanceSigned (const Point &p, const Eigen::Vector4f &plane_coefficients)
00095 {
00096 return ( plane_coefficients[0] * p.x + plane_coefficients[1] * p.y + plane_coefficients[2] * p.z + plane_coefficients[3] );
00097 }
00098
00107 template <typename Point> inline double
00108 pointToPlaneDistance (const Point &p, double a, double b, double c, double d)
00109 {
00110 return (fabs (pointToPlaneDistanceSigned (p, a, b, c, d)) );
00111 }
00112
00118 template <typename Point> inline double
00119 pointToPlaneDistance (const Point &p, const Eigen::Vector4f &plane_coefficients)
00120 {
00121 return ( fabs (pointToPlaneDistanceSigned (p, plane_coefficients)) );
00122 }
00123
00125
00135 template <typename PointT>
00136 class SampleConsensusModelPlane : public SampleConsensusModel<PointT>
00137 {
00138 public:
00139 using SampleConsensusModel<PointT>::input_;
00140 using SampleConsensusModel<PointT>::indices_;
00141 using SampleConsensusModel<PointT>::error_sqr_dists_;
00142
00143 typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00144 typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00145 typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00146
00147 typedef boost::shared_ptr<SampleConsensusModelPlane> Ptr;
00148
00153 SampleConsensusModelPlane (const PointCloudConstPtr &cloud, bool random = false)
00154 : SampleConsensusModel<PointT> (cloud, random) {};
00155
00161 SampleConsensusModelPlane (const PointCloudConstPtr &cloud,
00162 const std::vector<int> &indices,
00163 bool random = false)
00164 : SampleConsensusModel<PointT> (cloud, indices, random) {};
00165
00167 virtual ~SampleConsensusModelPlane () {}
00168
00175 bool
00176 computeModelCoefficients (const std::vector<int> &samples,
00177 Eigen::VectorXf &model_coefficients);
00178
00183 void
00184 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00185 std::vector<double> &distances);
00186
00192 void
00193 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00194 const double threshold,
00195 std::vector<int> &inliers);
00196
00203 virtual int
00204 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00205 const double threshold);
00206
00213 void
00214 optimizeModelCoefficients (const std::vector<int> &inliers,
00215 const Eigen::VectorXf &model_coefficients,
00216 Eigen::VectorXf &optimized_coefficients);
00217
00224 void
00225 projectPoints (const std::vector<int> &inliers,
00226 const Eigen::VectorXf &model_coefficients,
00227 PointCloud &projected_points,
00228 bool copy_data_fields = true);
00229
00235 bool
00236 doSamplesVerifyModel (const std::set<int> &indices,
00237 const Eigen::VectorXf &model_coefficients,
00238 const double threshold);
00239
00241 inline pcl::SacModel
00242 getModelType () const { return (SACMODEL_PLANE); }
00243
00244 protected:
00248 inline bool
00249 isModelValid (const Eigen::VectorXf &model_coefficients)
00250 {
00251
00252 if (model_coefficients.size () != 4)
00253 {
00254 PCL_ERROR ("[pcl::SampleConsensusModelPlane::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00255 return (false);
00256 }
00257 return (true);
00258 }
00259
00260 private:
00265 virtual bool
00266 isSampleGood (const std::vector<int> &samples) const;
00267 };
00268 }
00269
00270 #ifdef PCL_NO_PRECOMPILE
00271 #include <pcl/sample_consensus/impl/sac_model_plane.hpp>
00272 #endif
00273
00274 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_PLANE_H_