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_SPHERE_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_
00040
00041 #include "pcl/sample_consensus/sac_model_sphere.h"
00042
00044 template <typename PointT> void
00045 pcl::SampleConsensusModelSphere<PointT>::getSamples (int &iterations, std::vector<int> &samples)
00046 {
00047
00048 if (indices_->empty ())
00049 {
00050 ROS_ERROR ("[pcl::SampleConsensusModelSphere::getSamples] Empty set of indices given!");
00051 return;
00052 }
00053
00054 samples.resize (4);
00055 double trand = indices_->size () / (RAND_MAX + 1.0);
00056
00057
00058 if (samples.size () > indices_->size ())
00059 {
00060 ROS_ERROR ("[pcl::SampleConsensusModelSphere::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 do
00074 {
00075 idx = (int)(rand () * trand);
00076 samples[1] = (*indices_)[idx];
00077
00078 } while (samples[1] == samples[0]);
00079
00080
00081
00082 pcl::Array4fMapConst p0 = input_->points[samples[0]].getArray4fMap ();
00083 pcl::Array4fMapConst p1 = input_->points[samples[1]].getArray4fMap ();
00084
00085
00086 Eigen::Array4f p1p0 = p1 - p0;
00087
00088 Eigen::Array4f dy1dy2;
00089 int iter = 0;
00090 do
00091 {
00092
00093 do
00094 {
00095 idx = (int)(rand () * trand);
00096 samples[2] = (*indices_)[idx];
00097
00098 } while ( (samples[2] == samples[1]) || (samples[2] == samples[0]) );
00099
00100
00101 pcl::Array4fMapConst p2 = input_->points[samples[2]].getArray4fMap ();
00102
00103
00104 Eigen::Array4f p2p0 = p2 - p0;
00105
00106 dy1dy2 = p1p0 / p2p0;
00107 ++iter;
00108 if (iter > MAX_ITERATIONS_COLLINEAR )
00109 {
00110 ROS_DEBUG ("[pcl::SampleConsensusModelSphere::getSamples] WARNING: Could not select 3 non collinear points in %d iterations!", MAX_ITERATIONS_COLLINEAR);
00111 break;
00112 }
00113
00114 }
00115 while ( (dy1dy2[0] == dy1dy2[1]) && (dy1dy2[2] == dy1dy2[1]) );
00116
00117
00118
00119
00120 do
00121 {
00122 samples[3] = (int)(rand () * trand);
00123
00124 } while ( (samples[3] == samples[2]) || (samples[3] == samples[1]) || (samples[3] == samples[0]) );
00125
00126
00127 }
00128
00130 template <typename PointT> bool
00131 pcl::SampleConsensusModelSphere<PointT>::computeModelCoefficients (
00132 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00133 {
00134
00135 if (samples.size () != 4)
00136 {
00137 ROS_ERROR ("[pcl::SampleConsensusModelSphere::computeModelCoefficients] Invalid set of samples given (%zu)!", samples.size ());
00138 return (false);
00139 }
00140
00141 Eigen::Matrix4f temp;
00142 for (int i = 0; i < 4; i++)
00143 {
00144 temp (i, 0) = input_->points[samples[i]].x;
00145 temp (i, 1) = input_->points[samples[i]].y;
00146 temp (i, 2) = input_->points[samples[i]].z;
00147 temp (i, 3) = 1;
00148 }
00149 float m11 = temp.determinant ();
00150 if (m11 == 0)
00151 return (false);
00152
00153 for (int i = 0; i < 4; ++i)
00154 temp (i, 0) = (input_->points[samples[i]].x) * (input_->points[samples[i]].x) +
00155 (input_->points[samples[i]].y) * (input_->points[samples[i]].y) +
00156 (input_->points[samples[i]].z) * (input_->points[samples[i]].z);
00157 float m12 = temp.determinant ();
00158
00159 for (int i = 0; i < 4; ++i)
00160 {
00161 temp (i, 1) = temp (i, 0);
00162 temp (i, 0) = input_->points[samples[i]].x;
00163 }
00164 float m13 = temp.determinant ();
00165
00166 for (int i = 0; i < 4; ++i)
00167 {
00168 temp (i, 2) = temp (i, 1);
00169 temp (i, 1) = input_->points[samples[i]].y;
00170 }
00171 float m14 = temp.determinant ();
00172
00173 for (int i = 0; i < 4; ++i)
00174 {
00175 temp (i, 0) = temp (i, 2);
00176 temp (i, 1) = input_->points[samples[i]].x;
00177 temp (i, 2) = input_->points[samples[i]].y;
00178 temp (i, 3) = input_->points[samples[i]].z;
00179 }
00180 float m15 = temp.determinant ();
00181
00182
00183 model_coefficients.resize (4);
00184 model_coefficients[0] = 0.5 * m12 / m11;
00185 model_coefficients[1] = 0.5 * m13 / m11;
00186 model_coefficients[2] = 0.5 * m14 / m11;
00187
00188 model_coefficients[3] = sqrt (
00189 model_coefficients[0] * model_coefficients[0] +
00190 model_coefficients[1] * model_coefficients[1] +
00191 model_coefficients[2] * model_coefficients[2] - m15 / m11);
00192
00193 return (true);
00194 }
00195
00197 template <typename PointT> void
00198 pcl::SampleConsensusModelSphere<PointT>::getDistancesToModel (
00199 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00200 {
00201
00202 if (!isModelValid (model_coefficients))
00203 {
00204 distances.clear ();
00205 return;
00206 }
00207 distances.resize (indices_->size ());
00208
00209
00210 for (size_t i = 0; i < indices_->size (); ++i)
00211
00212
00213 distances[i] = fabs (sqrt (
00214 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00215 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00216
00217 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00218 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) +
00219
00220 ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) *
00221 ( input_->points[(*indices_)[i]].z - model_coefficients[2] )
00222 ) - model_coefficients[3]);
00223 }
00224
00226 template <typename PointT> void
00227 pcl::SampleConsensusModelSphere<PointT>::selectWithinDistance (
00228 const Eigen::VectorXf &model_coefficients, double threshold, std::vector<int> &inliers)
00229 {
00230
00231 if (!isModelValid (model_coefficients))
00232 {
00233 inliers.clear ();
00234 return;
00235 }
00236
00237 int nr_p = 0;
00238 inliers.resize (indices_->size ());
00239
00240
00241 for (size_t i = 0; i < indices_->size (); ++i)
00242 {
00243
00244
00245 if (fabs (sqrt (
00246 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00247 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00248
00249 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00250 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) +
00251
00252 ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) *
00253 ( input_->points[(*indices_)[i]].z - model_coefficients[2] )
00254 ) - model_coefficients[3]) < threshold)
00255 {
00256
00257 inliers[nr_p] = (*indices_)[i];
00258 nr_p++;
00259 }
00260 }
00261 inliers.resize (nr_p);
00262 }
00263
00265 template <typename PointT> void
00266 pcl::SampleConsensusModelSphere<PointT>::optimizeModelCoefficients (
00267 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00268 {
00269 boost::mutex::scoped_lock lock (tmp_mutex_);
00270
00271 const int n_unknowns = 4;
00272
00273 if (model_coefficients.size () != n_unknowns)
00274 {
00275 ROS_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00276 optimized_coefficients = model_coefficients;
00277 return;
00278 }
00279
00280
00281 if (inliers.size () <= 4)
00282 {
00283 ROS_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Not enough inliers found to support a model (%zu)! Returning the same coefficients.", inliers.size ());
00284 optimized_coefficients = model_coefficients;
00285 return;
00286 }
00287
00288 tmp_inliers_ = &inliers;
00289
00290 int m = inliers.size ();
00291
00292 double *fvec = new double[m];
00293
00294 int iwa[n_unknowns];
00295
00296 int lwa = m * n_unknowns + 5 * n_unknowns + m;
00297 double *wa = new double[lwa];
00298
00299
00300 double x[n_unknowns];
00301 for (int d = 0; d < n_unknowns; ++d)
00302 x[d] = model_coefficients[d];
00303
00304
00305 double tol = sqrt (dpmpar (1));
00306
00307
00308 int info = lmdif1 (&pcl::SampleConsensusModelSphere<PointT>::functionToOptimize, this, m, n_unknowns, x, fvec, tol, iwa, wa, lwa);
00309
00310
00311 ROS_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g \nFinal solution: %g %g %g %g",
00312 info, enorm (m, fvec), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], x[0], x[1], x[2], x[3]);
00313
00314 optimized_coefficients = Eigen::Vector4f (x[0], x[1], x[2], x[3]);
00315
00316 free (wa); free (fvec);
00317 }
00318
00320 template <typename PointT> int
00321 pcl::SampleConsensusModelSphere<PointT>::functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag)
00322 {
00323 SampleConsensusModelSphere *model = (SampleConsensusModelSphere*)p;
00324
00325 Eigen::Vector4f cen_t;
00326 cen_t[3] = 0;
00327 for (int i = 0; i < m; ++i)
00328 {
00329
00330 cen_t[0] = model->input_->points[(*model->tmp_inliers_)[i]].x - x[0];
00331 cen_t[1] = model->input_->points[(*model->tmp_inliers_)[i]].y - x[1];
00332 cen_t[2] = model->input_->points[(*model->tmp_inliers_)[i]].z - x[2];
00333
00334
00335 fvec[i] = sqrt (cen_t.dot (cen_t)) - x[3];
00336 }
00337 return (0);
00338 }
00339
00341 template <typename PointT> void
00342 pcl::SampleConsensusModelSphere<PointT>::projectPoints (
00343 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields)
00344 {
00345
00346 if (model_coefficients.size () != 4)
00347 {
00348 ROS_ERROR ("[pcl::SampleConsensusModelSphere::projectPoints] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00349 return;
00350 }
00351
00352
00353 projected_points.points.resize (input_->points.size ());
00354 projected_points.header = input_->header;
00355 projected_points.width = input_->width;
00356 projected_points.height = input_->height;
00357 projected_points.is_dense = input_->is_dense;
00358
00359 ROS_WARN ("[pcl::SampleConsensusModelSphere::projectPoints] Not implemented yet.");
00360 projected_points.points = input_->points;
00361 }
00362
00364 template <typename PointT> bool
00365 pcl::SampleConsensusModelSphere<PointT>::doSamplesVerifyModel (
00366 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, double threshold)
00367 {
00368
00369 if (model_coefficients.size () != 4)
00370 {
00371 ROS_ERROR ("[pcl::SampleConsensusModelSphere::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!", model_coefficients.size ());
00372 return (false);
00373 }
00374
00375 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00376
00377
00378 if (fabs (sqrt (
00379 ( input_->points[*it].x - model_coefficients[0] ) *
00380 ( input_->points[*it].x - model_coefficients[0] ) +
00381 ( input_->points[*it].y - model_coefficients[1] ) *
00382 ( input_->points[*it].y - model_coefficients[1] ) +
00383 ( input_->points[*it].z - model_coefficients[2] ) *
00384 ( input_->points[*it].z - model_coefficients[2] )
00385 ) - model_coefficients[3]) > threshold)
00386 return (false);
00387
00388 return (true);
00389 }
00390
00391 #define PCL_INSTANTIATE_SampleConsensusModelSphere(T) template class pcl::SampleConsensusModelSphere<T>;
00392
00393 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_
00394