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