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_SPHERE_H_
00041 #define PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_
00042
00043 #include <pcl/sample_consensus/sac_model.h>
00044 #include <pcl/sample_consensus/model_types.h>
00045
00046 namespace pcl
00047 {
00058 template <typename PointT>
00059 class SampleConsensusModelSphere : public SampleConsensusModel<PointT>
00060 {
00061 public:
00062 using SampleConsensusModel<PointT>::input_;
00063 using SampleConsensusModel<PointT>::indices_;
00064 using SampleConsensusModel<PointT>::radius_min_;
00065 using SampleConsensusModel<PointT>::radius_max_;
00066
00067
00068 typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00069 typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00070 typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00071
00072 typedef boost::shared_ptr<SampleConsensusModelSphere> Ptr;
00073
00077 SampleConsensusModelSphere (const PointCloudConstPtr &cloud) :
00078 SampleConsensusModel<PointT> (cloud), tmp_inliers_ ()
00079 {}
00080
00085 SampleConsensusModelSphere (const PointCloudConstPtr &cloud, const std::vector<int> &indices) :
00086 SampleConsensusModel<PointT> (cloud, indices), tmp_inliers_ ()
00087 {}
00088
00092 SampleConsensusModelSphere (const SampleConsensusModelSphere &source) :
00093 SampleConsensusModel<PointT> (), tmp_inliers_ ()
00094 {
00095 *this = source;
00096 }
00097
00101 inline SampleConsensusModelSphere&
00102 operator = (const SampleConsensusModelSphere &source)
00103 {
00104 SampleConsensusModel<PointT>::operator=(source);
00105 tmp_inliers_ = source.tmp_inliers_;
00106 return (*this);
00107 }
00108
00115 bool
00116 computeModelCoefficients (const std::vector<int> &samples,
00117 Eigen::VectorXf &model_coefficients);
00118
00123 void
00124 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00125 std::vector<double> &distances);
00126
00132 void
00133 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00134 const double threshold,
00135 std::vector<int> &inliers);
00136
00143 virtual int
00144 countWithinDistance (const Eigen::VectorXf &model_coefficients,
00145 const double threshold);
00146
00153 void
00154 optimizeModelCoefficients (const std::vector<int> &inliers,
00155 const Eigen::VectorXf &model_coefficients,
00156 Eigen::VectorXf &optimized_coefficients);
00157
00165 void
00166 projectPoints (const std::vector<int> &inliers,
00167 const Eigen::VectorXf &model_coefficients,
00168 PointCloud &projected_points,
00169 bool copy_data_fields = true);
00170
00176 bool
00177 doSamplesVerifyModel (const std::set<int> &indices,
00178 const Eigen::VectorXf &model_coefficients,
00179 const double threshold);
00180
00182 inline pcl::SacModel getModelType () const { return (SACMODEL_SPHERE); }
00183
00184 protected:
00188 inline bool
00189 isModelValid (const Eigen::VectorXf &model_coefficients)
00190 {
00191
00192 if (model_coefficients.size () != 4)
00193 {
00194 PCL_ERROR ("[pcl::SampleConsensusModelSphere::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00195 return (false);
00196 }
00197
00198 if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[3] < radius_min_)
00199 return (false);
00200 if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[3] > radius_max_)
00201 return (false);
00202
00203 return (true);
00204 }
00205
00210 bool
00211 isSampleGood(const std::vector<int> &samples) const;
00212
00213 private:
00215 const std::vector<int> *tmp_inliers_;
00216
00217 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00218 #pragma GCC diagnostic ignored "-Weffc++"
00219 #endif
00220 struct OptimizationFunctor : pcl::Functor<float>
00221 {
00227 OptimizationFunctor (int m_data_points, pcl::SampleConsensusModelSphere<PointT> *model) :
00228 pcl::Functor<float>(m_data_points), model_ (model) {}
00229
00235 int
00236 operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const
00237 {
00238 Eigen::Vector4f cen_t;
00239 cen_t[3] = 0;
00240 for (int i = 0; i < values (); ++i)
00241 {
00242
00243 cen_t[0] = model_->input_->points[(*model_->tmp_inliers_)[i]].x - x[0];
00244 cen_t[1] = model_->input_->points[(*model_->tmp_inliers_)[i]].y - x[1];
00245 cen_t[2] = model_->input_->points[(*model_->tmp_inliers_)[i]].z - x[2];
00246
00247
00248 fvec[i] = sqrtf (cen_t.dot (cen_t)) - x[3];
00249 }
00250 return (0);
00251 }
00252
00253 pcl::SampleConsensusModelSphere<PointT> *model_;
00254 };
00255 #if defined BUILD_Maintainer && defined __GNUC__ && __GNUC__ == 4 && __GNUC_MINOR__ > 3
00256 #pragma GCC diagnostic warning "-Weffc++"
00257 #endif
00258 };
00259 }
00260
00261 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_SPHERE_H_