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 #ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_
00039 #define PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_
00040
00041 #include <pcl/sample_consensus/sac_model.h>
00042 #include <pcl/sample_consensus/model_types.h>
00043 #include <pcl/registration/registration.h>
00044 #include <pcl/features/feature.h>
00045
00046 namespace pcl
00047 {
00051 template <typename PointT>
00052 class SampleConsensusModelRegistration : public SampleConsensusModel<PointT>
00053 {
00054 using SampleConsensusModel<PointT>::input_;
00055 using SampleConsensusModel<PointT>::indices_;
00056
00057 public:
00058 typedef typename SampleConsensusModel<PointT>::PointCloud PointCloud;
00059 typedef typename SampleConsensusModel<PointT>::PointCloudPtr PointCloudPtr;
00060 typedef typename SampleConsensusModel<PointT>::PointCloudConstPtr PointCloudConstPtr;
00061
00062 typedef boost::shared_ptr<SampleConsensusModelRegistration> Ptr;
00063
00067 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud) : SampleConsensusModel<PointT> (cloud)
00068 {
00069 setInputCloud (cloud);
00070 }
00071
00076 SampleConsensusModelRegistration (const PointCloudConstPtr &cloud,
00077 const std::vector<int> &indices) :
00078 SampleConsensusModel<PointT> (cloud, indices)
00079 {
00080 input_ = cloud;
00081 computeSampleDistanceThreshold (cloud);
00082 }
00083
00087 inline virtual void
00088 setInputCloud (const PointCloudConstPtr &cloud)
00089 {
00090 SampleConsensusModel<PointT>::setInputCloud (cloud);
00091 computeSampleDistanceThreshold (cloud);
00092 }
00093
00098 inline void
00099 computeSampleDistanceThreshold (const PointCloudConstPtr &cloud)
00100 {
00101
00102 Eigen::Vector4f xyz_centroid;
00103 compute3DCentroid (*cloud, xyz_centroid);
00104 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00105 computeCovarianceMatrixNormalized (*cloud, xyz_centroid, covariance_matrix);
00106 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00107 EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00108 pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00109
00110
00111 sample_dist_thresh_ = eigen_values.array ().sqrt ().sum () / 3.0;
00112 sample_dist_thresh_ *= sample_dist_thresh_;
00113 ROS_DEBUG ("[pcl::SampleConsensusModelRegistration::setInputCloud] Estimated a sample selection distance threshold of: %f", sample_dist_thresh_);
00114 }
00115
00119 inline void
00120 setInputTarget (const PointCloudConstPtr &target)
00121 {
00122 target_ = target;
00123
00124 unsigned int target_size = target->size();
00125 indices_tgt_->resize(target_size);
00126 for (unsigned int i = 0; i < target_size; ++i)
00127 indices_tgt_->push_back(i);
00128 }
00129
00134 inline void
00135 setInputTarget (const PointCloudConstPtr &target, const std::vector<int> &indices_tgt)
00136 {
00137 target_ = target;
00138 indices_tgt_ = boost::make_shared <std::vector<int> > (indices_tgt);
00139 }
00140
00146 void
00147 getSamples (int &iterations,
00148 std::vector<int> &samples);
00149
00154 bool
00155 computeModelCoefficients (const std::vector<int> &samples,
00156 Eigen::VectorXf &model_coefficients);
00157
00162 void
00163 getDistancesToModel (const Eigen::VectorXf &model_coefficients,
00164 std::vector<double> &distances);
00165
00171 void
00172 selectWithinDistance (const Eigen::VectorXf &model_coefficients,
00173 double threshold, std::vector<int> &inliers);
00174
00180 void
00181 optimizeModelCoefficients (const std::vector<int> &inliers,
00182 const Eigen::VectorXf &model_coefficients,
00183 Eigen::VectorXf &optimized_coefficients);
00184
00185 void
00186 projectPoints (const std::vector<int> &inliers,
00187 const Eigen::VectorXf &model_coefficients,
00188 PointCloud &projected_points, bool copy_data_fields = true)
00189 {};
00190
00191 bool
00192 doSamplesVerifyModel (const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, double threshold)
00193 {
00194 ROS_ERROR ("[pcl::SampleConsensusModelRegistration::doSamplesVerifyModel] called!");
00195 return (false);
00196 }
00197
00199 inline pcl::SacModel getModelType() const { return (SACMODEL_REGISTRATION); }
00200
00201 protected:
00205 inline bool
00206 isModelValid (const Eigen::VectorXf &model_coefficients)
00207 {
00208
00209 if (model_coefficients.size () != 16)
00210 return (false);
00211
00212 return (true);
00213 }
00214
00215 private:
00217 PointCloudConstPtr target_;
00218
00220 IndicesPtr indices_tgt_;
00221
00223 double sample_dist_thresh_;
00224
00226 const static int MAX_ITERATIONS_COLLINEAR = 1000;
00227 };
00228 }
00229
00230 #endif //#ifndef PCL_SAMPLE_CONSENSUS_MODEL_REGISTRATION_H_