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