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_IMPL_SAC_MODEL_LINE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_
00040
00041 #include <pcl/sample_consensus/sac_model_line.h>
00042 #include <pcl/common/centroid.h>
00043 #include <pcl/common/concatenate.h>
00044
00046 template <typename PointT> bool
00047 pcl::SampleConsensusModelLine<PointT>::isSampleGood (const std::vector<int> &samples) const
00048 {
00049 if (
00050 (input_->points[samples[0]].x != input_->points[samples[1]].x)
00051 &&
00052 (input_->points[samples[0]].y != input_->points[samples[1]].y)
00053 &&
00054 (input_->points[samples[0]].z != input_->points[samples[1]].z))
00055 return (true);
00056
00057 return (true);
00058 }
00059
00061 template <typename PointT> bool
00062 pcl::SampleConsensusModelLine<PointT>::computeModelCoefficients (
00063 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00064 {
00065
00066 if (samples.size () != 2)
00067 {
00068 PCL_ERROR ("[pcl::SampleConsensusModelLine::computeModelCoefficients] Invalid set of samples given (%zu)!\n", samples.size ());
00069 return (false);
00070 }
00071
00072 model_coefficients.resize (6);
00073 model_coefficients[0] = input_->points[samples[0]].x;
00074 model_coefficients[1] = input_->points[samples[0]].y;
00075 model_coefficients[2] = input_->points[samples[0]].z;
00076
00077 model_coefficients[3] = input_->points[samples[1]].x - model_coefficients[0];
00078 model_coefficients[4] = input_->points[samples[1]].y - model_coefficients[1];
00079 model_coefficients[5] = input_->points[samples[1]].z - model_coefficients[2];
00080
00081 model_coefficients.template tail<3> ().normalize ();
00082 return (true);
00083 }
00084
00086 template <typename PointT> void
00087 pcl::SampleConsensusModelLine<PointT>::getDistancesToModel (
00088 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00089 {
00090
00091 if (!isModelValid (model_coefficients))
00092 return;
00093
00094 distances.resize (indices_->size ());
00095
00096
00097 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00098 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00099 line_dir.normalize ();
00100
00101
00102 for (size_t i = 0; i < indices_->size (); ++i)
00103 {
00104
00105
00106
00107 distances[i] = sqrt ((line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ());
00108 }
00109 }
00110
00112 template <typename PointT> void
00113 pcl::SampleConsensusModelLine<PointT>::selectWithinDistance (
00114 const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00115 {
00116
00117 if (!isModelValid (model_coefficients))
00118 return;
00119
00120 double sqr_threshold = threshold * threshold;
00121
00122 int nr_p = 0;
00123 inliers.resize (indices_->size ());
00124
00125
00126 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00127 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00128 line_dir.normalize ();
00129
00130
00131 for (size_t i = 0; i < indices_->size (); ++i)
00132 {
00133
00134
00135 double sqr_distance = (line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ();
00136
00137 if (sqr_distance < sqr_threshold)
00138 {
00139
00140 inliers[nr_p] = (*indices_)[i];
00141 nr_p++;
00142 }
00143 }
00144 inliers.resize (nr_p);
00145 }
00146
00148 template <typename PointT> int
00149 pcl::SampleConsensusModelLine<PointT>::countWithinDistance (
00150 const Eigen::VectorXf &model_coefficients, const double threshold)
00151 {
00152
00153 if (!isModelValid (model_coefficients))
00154 return (0);
00155
00156 double sqr_threshold = threshold * threshold;
00157
00158 int nr_p = 0;
00159
00160
00161 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00162 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00163 line_dir.normalize ();
00164
00165
00166 for (size_t i = 0; i < indices_->size (); ++i)
00167 {
00168
00169
00170 double sqr_distance = (line_pt - input_->points[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ();
00171
00172 if (sqr_distance < sqr_threshold)
00173 nr_p++;
00174 }
00175 return (nr_p);
00176 }
00177
00179 template <typename PointT> void
00180 pcl::SampleConsensusModelLine<PointT>::optimizeModelCoefficients (
00181 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00182 {
00183
00184 if (!isModelValid (model_coefficients))
00185 {
00186 optimized_coefficients = model_coefficients;
00187 return;
00188 }
00189
00190
00191 if (inliers.size () <= 2)
00192 {
00193 PCL_ERROR ("[pcl::SampleConsensusModelLine::optimizeModelCoefficients] Not enough inliers found to support a model (%zu)! Returning the same coefficients.\n", inliers.size ());
00194 optimized_coefficients = model_coefficients;
00195 return;
00196 }
00197
00198 optimized_coefficients.resize (6);
00199
00200
00201 Eigen::Vector4f centroid;
00202 compute3DCentroid (*input_, inliers, centroid);
00203 Eigen::Matrix3f covariance_matrix;
00204 computeCovarianceMatrix (*input_, inliers, centroid, covariance_matrix);
00205 optimized_coefficients[0] = centroid[0];
00206 optimized_coefficients[1] = centroid[1];
00207 optimized_coefficients[2] = centroid[2];
00208
00209
00210 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00211 EIGEN_ALIGN16 Eigen::Vector3f eigen_vector;
00212 pcl::eigen33 (covariance_matrix, eigen_values);
00213 pcl::computeCorrespondingEigenVector (covariance_matrix, eigen_values [2], eigen_vector);
00214
00215
00216 optimized_coefficients.template tail<3> () = eigen_vector;
00217 }
00218
00220 template <typename PointT> void
00221 pcl::SampleConsensusModelLine<PointT>::projectPoints (
00222 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields)
00223 {
00224
00225 if (!isModelValid (model_coefficients))
00226 return;
00227
00228
00229 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00230 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00231
00232 projected_points.header = input_->header;
00233 projected_points.is_dense = input_->is_dense;
00234
00235
00236 if (copy_data_fields)
00237 {
00238
00239 projected_points.points.resize (input_->points.size ());
00240 projected_points.width = input_->width;
00241 projected_points.height = input_->height;
00242
00243 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00244
00245 for (size_t i = 0; i < projected_points.points.size (); ++i)
00246
00247 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
00248
00249
00250 for (size_t i = 0; i < inliers.size (); ++i)
00251 {
00252 Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0);
00253
00254 float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir);
00255
00256 Eigen::Vector4f pp = line_pt + k * line_dir;
00257
00258 projected_points.points[inliers[i]].x = pp[0];
00259 projected_points.points[inliers[i]].y = pp[1];
00260 projected_points.points[inliers[i]].z = pp[2];
00261 }
00262 }
00263 else
00264 {
00265
00266 projected_points.points.resize (inliers.size ());
00267 projected_points.width = static_cast<uint32_t> (inliers.size ());
00268 projected_points.height = 1;
00269
00270 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00271
00272 for (size_t i = 0; i < inliers.size (); ++i)
00273
00274 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[inliers[i]], projected_points.points[i]));
00275
00276
00277 for (size_t i = 0; i < inliers.size (); ++i)
00278 {
00279 Eigen::Vector4f pt (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z, 0);
00280
00281 float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir);
00282
00283 Eigen::Vector4f pp = line_pt + k * line_dir;
00284
00285 projected_points.points[i].x = pp[0];
00286 projected_points.points[i].y = pp[1];
00287 projected_points.points[i].z = pp[2];
00288 }
00289 }
00290 }
00291
00293 template <typename PointT> bool
00294 pcl::SampleConsensusModelLine<PointT>::doSamplesVerifyModel (
00295 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
00296 {
00297
00298 if (!isModelValid (model_coefficients))
00299 return (false);
00300
00301
00302 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
00303 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
00304 line_dir.normalize ();
00305
00306 double sqr_threshold = threshold * threshold;
00307
00308 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00309 {
00310
00311
00312 if ((line_pt - input_->points[*it].getVector4fMap ()).cross3 (line_dir).squaredNorm () > sqr_threshold)
00313 return (false);
00314 }
00315
00316 return (true);
00317 }
00318
00319 #define PCL_INSTANTIATE_SampleConsensusModelLine(T) template class PCL_EXPORTS pcl::SampleConsensusModelLine<T>;
00320
00321 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_
00322