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 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_
00040
00041 #include <pcl/sample_consensus/sac_model_circle.h>
00042 #include <pcl/common/concatenate.h>
00043 #include <unsupported/Eigen/NonLinearOptimization>
00044
00046 template <typename PointT> bool
00047 pcl::SampleConsensusModelCircle2D<PointT>::isSampleGood(const std::vector<int> &samples) const
00048 {
00049
00050 Eigen::Array2d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y);
00051 Eigen::Array2d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y);
00052 Eigen::Array2d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y);
00053
00054
00055 p1 -= p0;
00056
00057 p2 -= p0;
00058
00059 Eigen::Array2d dy1dy2 = p1 / p2;
00060
00061 return (dy1dy2[0] != dy1dy2[1]);
00062 }
00063
00065 template <typename PointT> bool
00066 pcl::SampleConsensusModelCircle2D<PointT>::computeModelCoefficients (const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00067 {
00068
00069 if (samples.size () != 3)
00070 {
00071 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::computeModelCoefficients] Invalid set of samples given (%zu)!\n", samples.size ());
00072 return (false);
00073 }
00074
00075 model_coefficients.resize (3);
00076
00077 Eigen::Vector2d p0 (input_->points[samples[0]].x, input_->points[samples[0]].y);
00078 Eigen::Vector2d p1 (input_->points[samples[1]].x, input_->points[samples[1]].y);
00079 Eigen::Vector2d p2 (input_->points[samples[2]].x, input_->points[samples[2]].y);
00080
00081 Eigen::Vector2d u = (p0 + p1) / 2.0;
00082 Eigen::Vector2d v = (p1 + p2) / 2.0;
00083
00084 Eigen::Vector2d p1p0dif = p1 - p0;
00085 Eigen::Vector2d p2p1dif = p2 - p1;
00086 Eigen::Vector2d uvdif = u - v;
00087
00088 Eigen::Vector2d m (- p1p0dif[0] / p1p0dif[1], - p2p1dif[0] / p2p1dif[1]);
00089
00090
00091 model_coefficients[0] = static_cast<float> ((m[0] * u[0] - m[1] * v[0] - uvdif[1] ) / (m[0] - m[1]));
00092 model_coefficients[1] = static_cast<float> ((m[0] * m[1] * uvdif[0] + m[0] * v[1] - m[1] * u[1]) / (m[0] - m[1]));
00093
00094
00095 model_coefficients[2] = static_cast<float> (sqrt ((model_coefficients[0] - p0[0]) * (model_coefficients[0] - p0[0]) +
00096 (model_coefficients[1] - p0[1]) * (model_coefficients[1] - p0[1])));
00097 return (true);
00098 }
00099
00101 template <typename PointT> void
00102 pcl::SampleConsensusModelCircle2D<PointT>::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00103 {
00104
00105 if (!isModelValid (model_coefficients))
00106 {
00107 distances.clear ();
00108 return;
00109 }
00110 distances.resize (indices_->size ());
00111
00112
00113 for (size_t i = 0; i < indices_->size (); ++i)
00114
00115
00116 distances[i] = fabsf (sqrtf (
00117 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00118 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00119
00120 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00121 ( input_->points[(*indices_)[i]].y - model_coefficients[1] )
00122 ) - model_coefficients[2]);
00123 }
00124
00126 template <typename PointT> void
00127 pcl::SampleConsensusModelCircle2D<PointT>::selectWithinDistance (
00128 const Eigen::VectorXf &model_coefficients, const double threshold,
00129 std::vector<int> &inliers)
00130 {
00131
00132 if (!isModelValid (model_coefficients))
00133 {
00134 inliers.clear ();
00135 return;
00136 }
00137 int nr_p = 0;
00138 inliers.resize (indices_->size ());
00139
00140
00141 for (size_t i = 0; i < indices_->size (); ++i)
00142 {
00143
00144
00145 float distance = fabsf (sqrtf (
00146 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00147 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00148
00149 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00150 ( input_->points[(*indices_)[i]].y - model_coefficients[1] )
00151 ) - model_coefficients[2]);
00152 if (distance < threshold)
00153 {
00154
00155 inliers[nr_p] = (*indices_)[i];
00156 nr_p++;
00157 }
00158 }
00159 inliers.resize (nr_p);
00160 }
00161
00163 template <typename PointT> int
00164 pcl::SampleConsensusModelCircle2D<PointT>::countWithinDistance (
00165 const Eigen::VectorXf &model_coefficients, const double threshold)
00166 {
00167
00168 if (!isModelValid (model_coefficients))
00169 return (0);
00170 int nr_p = 0;
00171
00172
00173 for (size_t i = 0; i < indices_->size (); ++i)
00174 {
00175
00176
00177 float distance = fabsf (sqrtf (
00178 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00179 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00180
00181 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00182 ( input_->points[(*indices_)[i]].y - model_coefficients[1] )
00183 ) - model_coefficients[2]);
00184 if (distance < threshold)
00185 nr_p++;
00186 }
00187 return (nr_p);
00188 }
00189
00191 template <typename PointT> void
00192 pcl::SampleConsensusModelCircle2D<PointT>::optimizeModelCoefficients (
00193 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00194 {
00195 optimized_coefficients = model_coefficients;
00196
00197
00198 if (model_coefficients.size () != 3)
00199 {
00200 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00201 return;
00202 }
00203
00204
00205 if (inliers.size () <= 3)
00206 {
00207 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] Not enough inliers found to support a model (%zu)! Returning the same coefficients.\n", inliers.size ());
00208 return;
00209 }
00210
00211 tmp_inliers_ = &inliers;
00212
00213 OptimizationFunctor functor (static_cast<int> (inliers.size ()), this);
00214 Eigen::NumericalDiff<OptimizationFunctor> num_diff (functor);
00215 Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
00216 int info = lm.minimize (optimized_coefficients);
00217
00218
00219 PCL_DEBUG ("[pcl::SampleConsensusModelCircle2D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g \nFinal solution: %g %g %g\n",
00220 info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2]);
00221 }
00222
00224 template <typename PointT> void
00225 pcl::SampleConsensusModelCircle2D<PointT>::projectPoints (
00226 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients,
00227 PointCloud &projected_points, bool copy_data_fields)
00228 {
00229
00230 if (model_coefficients.size () != 3)
00231 {
00232 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::projectPoints] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00233 return;
00234 }
00235
00236 projected_points.header = input_->header;
00237 projected_points.is_dense = input_->is_dense;
00238
00239
00240 if (copy_data_fields)
00241 {
00242
00243 projected_points.points.resize (input_->points.size ());
00244 projected_points.width = input_->width;
00245 projected_points.height = input_->height;
00246
00247 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00248
00249 for (size_t i = 0; i < projected_points.points.size (); ++i)
00250
00251 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[i], projected_points.points[i]));
00252
00253
00254 for (size_t i = 0; i < inliers.size (); ++i)
00255 {
00256 float dx = input_->points[inliers[i]].x - model_coefficients[0];
00257 float dy = input_->points[inliers[i]].y - model_coefficients[1];
00258 float a = sqrtf ( (model_coefficients[2] * model_coefficients[2]) / (dx * dx + dy * dy) );
00259
00260 projected_points.points[inliers[i]].x = a * dx + model_coefficients[0];
00261 projected_points.points[inliers[i]].y = a * dy + model_coefficients[1];
00262 }
00263 }
00264 else
00265 {
00266
00267 projected_points.points.resize (inliers.size ());
00268 projected_points.width = static_cast<uint32_t> (inliers.size ());
00269 projected_points.height = 1;
00270
00271 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00272
00273 for (size_t i = 0; i < inliers.size (); ++i)
00274
00275 pcl::for_each_type <FieldList> (NdConcatenateFunctor <PointT, PointT> (input_->points[inliers[i]], projected_points.points[i]));
00276
00277
00278 for (size_t i = 0; i < inliers.size (); ++i)
00279 {
00280 float dx = input_->points[inliers[i]].x - model_coefficients[0];
00281 float dy = input_->points[inliers[i]].y - model_coefficients[1];
00282 float a = sqrtf ( (model_coefficients[2] * model_coefficients[2]) / (dx * dx + dy * dy) );
00283
00284 projected_points.points[i].x = a * dx + model_coefficients[0];
00285 projected_points.points[i].y = a * dy + model_coefficients[1];
00286 }
00287 }
00288 }
00289
00291 template <typename PointT> bool
00292 pcl::SampleConsensusModelCircle2D<PointT>::doSamplesVerifyModel (
00293 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
00294 {
00295
00296 if (model_coefficients.size () != 3)
00297 {
00298 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00299 return (false);
00300 }
00301
00302 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00303
00304
00305 if (fabsf (sqrtf (
00306 ( input_->points[*it].x - model_coefficients[0] ) *
00307 ( input_->points[*it].x - model_coefficients[0] ) +
00308 ( input_->points[*it].y - model_coefficients[1] ) *
00309 ( input_->points[*it].y - model_coefficients[1] )
00310 ) - model_coefficients[2]) > threshold)
00311 return (false);
00312
00313 return (true);
00314 }
00315
00317 template <typename PointT> bool
00318 pcl::SampleConsensusModelCircle2D<PointT>::isModelValid (const Eigen::VectorXf &model_coefficients)
00319 {
00320
00321 if (model_coefficients.size () != 3)
00322 {
00323 PCL_ERROR ("[pcl::SampleConsensusModelCircle2D::isModelValid] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00324 return (false);
00325 }
00326
00327 if (radius_min_ != -std::numeric_limits<double>::max() && model_coefficients[2] < radius_min_)
00328 return (false);
00329 if (radius_max_ != std::numeric_limits<double>::max() && model_coefficients[2] > radius_max_)
00330 return (false);
00331
00332 return (true);
00333 }
00334
00335 #define PCL_INSTANTIATE_SampleConsensusModelCircle2D(T) template class PCL_EXPORTS pcl::SampleConsensusModelCircle2D<T>;
00336
00337 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_
00338