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
00033 #include <door_handle_detector/sample_consensus/sac_model_sphere.h>
00034 #include <door_handle_detector/geometry/nearest.h>
00035 #include <Eigen/LU>
00036
00037 #include <cminpack.h>
00038
00039 namespace sample_consensus
00040 {
00042
00052 void
00053 SACModelSphere::getSamples (int &iterations, std::vector<int> &samples)
00054 {
00055 samples.resize (4);
00056 double trand = indices_.size () / (RAND_MAX + 1.0);
00057
00058
00059 int idx = (int)(rand () * trand);
00060
00061 samples[0] = indices_.at (idx);
00062
00063
00064 do
00065 {
00066 idx = (int)(rand () * trand);
00067 samples[1] = indices_.at (idx);
00068 iterations++;
00069 } while (samples[1] == samples[0]);
00070 iterations--;
00071
00072 double Dx1, Dy1, Dz1, Dx2, Dy2, Dz2, Dy1Dy2;
00073
00074 Dx1 = cloud_->points[samples[1]].x - cloud_->points[samples[0]].x;
00075 Dy1 = cloud_->points[samples[1]].y - cloud_->points[samples[0]].y;
00076 Dz1 = cloud_->points[samples[1]].z - cloud_->points[samples[0]].z;
00077
00078 int iter = 0;
00079 do
00080 {
00081
00082 do
00083 {
00084 idx = (int)(rand () * trand);
00085 samples[2] = indices_.at (idx);
00086 iterations++;
00087 } while ( (samples[2] == samples[1]) || (samples[2] == samples[0]) );
00088 iterations--;
00089
00090
00091 Dx2 = cloud_->points[samples[2]].x - cloud_->points[samples[0]].x;
00092 Dy2 = cloud_->points[samples[2]].y - cloud_->points[samples[0]].y;
00093 Dz2 = cloud_->points[samples[2]].z - cloud_->points[samples[0]].z;
00094
00095 Dy1Dy2 = Dy1 / Dy2;
00096 iter++;
00097
00098 if (iter > MAX_ITERATIONS_COLLINEAR )
00099 {
00100 ROS_WARN ("[SACModelSphere::getSamples] WARNING: Could not select 3 non collinear points in %d iterations!", MAX_ITERATIONS_COLLINEAR);
00101 break;
00102 }
00103 iterations++;
00104 }
00105
00106 while (((Dx1 / Dx2) == Dy1Dy2) && (Dy1Dy2 == (Dz1 / Dz2)));
00107 iterations--;
00108
00109
00110
00111 do
00112 {
00113 samples[3] = (int)(rand () * trand);
00114 iterations++;
00115 } while ( (samples[3] == samples[2]) || (samples[3] == samples[1]) || (samples[3] == samples[0]) );
00116 iterations--;
00117
00118 return;
00119 }
00120
00122
00129 void
00130 SACModelSphere::selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers)
00131 {
00132 int nr_p = 0;
00133 inliers.resize (indices_.size ());
00134
00135
00136 for (unsigned int i = 0; i < indices_.size (); i++)
00137 {
00138
00139
00140 if (fabs (sqrt (
00141 ( cloud_->points.at (indices_[i]).x - model_coefficients.at (0) ) *
00142 ( cloud_->points.at (indices_[i]).x - model_coefficients.at (0) ) +
00143
00144 ( cloud_->points.at (indices_[i]).y - model_coefficients.at (1) ) *
00145 ( cloud_->points.at (indices_[i]).y - model_coefficients.at (1) ) +
00146
00147 ( cloud_->points.at (indices_[i]).z - model_coefficients.at (2) ) *
00148 ( cloud_->points.at (indices_[i]).z - model_coefficients.at (2) )
00149 ) - model_coefficients.at (3)) < threshold)
00150 {
00151
00152 inliers[nr_p] = indices_[i];
00153 nr_p++;
00154 }
00155 }
00156 inliers.resize (nr_p);
00157 return;
00158 }
00159
00161
00165 void
00166 SACModelSphere::getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances)
00167 {
00168 distances.resize (indices_.size ());
00169
00170
00171 for (unsigned int i = 0; i < indices_.size (); i++)
00172
00173
00174 distances[i] = fabs (sqrt (
00175 ( cloud_->points.at (indices_[i]).x - model_coefficients.at (0) ) *
00176 ( cloud_->points.at (indices_[i]).x - model_coefficients.at (0) ) +
00177
00178 ( cloud_->points.at (indices_[i]).y - model_coefficients.at (1) ) *
00179 ( cloud_->points.at (indices_[i]).y - model_coefficients.at (1) ) +
00180
00181 ( cloud_->points.at (indices_[i]).z - model_coefficients.at (2) ) *
00182 ( cloud_->points.at (indices_[i]).z - model_coefficients.at (2) )
00183 ) - model_coefficients.at (3));
00184 return;
00185 }
00186
00188
00194 void
00195 SACModelSphere::projectPoints (const std::vector<int> &inliers, const std::vector<double> &model_coefficients,
00196 sensor_msgs::PointCloud &projected_points)
00197 {
00198 std::cerr << "[SACModelSphere::projecPoints] Not implemented yet." << std::endl;
00199 projected_points = *cloud_;
00200 }
00201
00203
00208 void
00209 SACModelSphere::projectPointsInPlace (const std::vector<int> &inliers, const std::vector<double> &model_coefficients)
00210 {
00211 std::cerr << "[SACModelSphere::projecPointsInPlace] Not implemented yet." << std::endl;
00212 }
00213
00215
00219 bool
00220 SACModelSphere::computeModelCoefficients (const std::vector<int> &samples)
00221 {
00222 model_coefficients_.resize (4);
00223
00224 Eigen::Matrix4d temp;
00225 for (int i = 0; i < 4; i++)
00226 {
00227 temp (i, 0) = cloud_->points.at (samples.at (i)).x;
00228 temp (i, 1) = cloud_->points.at (samples.at (i)).y;
00229 temp (i, 2) = cloud_->points.at (samples.at (i)).z;
00230 temp (i, 3) = 1;
00231 }
00232 double m11 = temp.determinant ();
00233 if (m11 == 0)
00234 return (false);
00235
00236 for (int i = 0; i < 4; i++)
00237 temp (i, 0) = (cloud_->points.at (samples.at (i)).x) * (cloud_->points.at (samples.at (i)).x) +
00238 (cloud_->points.at (samples.at (i)).y) * (cloud_->points.at (samples.at (i)).y) +
00239 (cloud_->points.at (samples.at (i)).z) * (cloud_->points.at (samples.at (i)).z);
00240 double m12 = temp.determinant ();
00241
00242 for (int i = 0; i < 4; i++)
00243 {
00244 temp (i, 1) = temp (i, 0);
00245 temp (i, 0) = cloud_->points.at (samples.at (i)).x;
00246 }
00247 double m13 = temp.determinant ();
00248
00249 for (int i = 0; i < 4; i++)
00250 {
00251 temp (i, 2) = temp (i, 1);
00252 temp (i, 1) = cloud_->points.at (samples.at (i)).y;
00253 }
00254 double m14 = temp.determinant ();
00255
00256 for (int i = 0; i < 4; i++)
00257 {
00258 temp (i, 0) = temp (i, 2);
00259 temp (i, 1) = cloud_->points.at (samples.at (i)).x;
00260 temp (i, 2) = cloud_->points.at (samples.at (i)).y;
00261 temp (i, 3) = cloud_->points.at (samples.at (i)).z;
00262 }
00263 double m15 = temp.determinant ();
00264
00265
00266 model_coefficients_[0] = 0.5 * m12 / m11;
00267 model_coefficients_[1] = 0.5 * m13 / m11;
00268 model_coefficients_[2] = 0.5 * m14 / m11;
00269
00270 model_coefficients_[3] = sqrt (
00271 model_coefficients_[0] * model_coefficients_[0] +
00272 model_coefficients_[1] * model_coefficients_[1] +
00273 model_coefficients_[2] * model_coefficients_[2] - m15 / m11);
00274
00275 return (true);
00276 }
00277
00279
00284 void
00285 SACModelSphere::refitModel (const std::vector<int> &inliers, std::vector<double> &refit_coefficients)
00286 {
00287 if (inliers.size () == 0)
00288 {
00289 ROS_ERROR ("[SACModelSphere::RefitModel] Cannot re-fit 0 inliers!");
00290 refit_coefficients = model_coefficients_;
00291 return;
00292 }
00293 if (model_coefficients_.size () == 0)
00294 {
00295 ROS_WARN ("[SACModelSphere::RefitModel] Initial model coefficients have not been estimated yet - proceeding without an initial solution!");
00296 best_inliers_ = indices_;
00297 }
00298
00299 tmp_inliers_ = &inliers;
00300
00301 int m = inliers.size ();
00302
00303 double *fvec = new double[m];
00304
00305 int n = 4;
00306 int iwa[n];
00307
00308 int lwa = m * n + 5 * n + m;
00309 double *wa = new double[lwa];
00310
00311
00312 double x[4] = {0.0, 0.0, 0.0, 0.0};
00313 if ((int)model_coefficients_.size () == n)
00314 for (int d = 0; d < n; d++)
00315 x[d] = model_coefficients_.at (d);
00316
00317
00318 double tol = sqrt (dpmpar (1));
00319
00320
00321 int info = lmdif1 (&sample_consensus::SACModelSphere::functionToOptimize, this, m, n, x, fvec, tol, iwa, wa, lwa);
00322
00323
00324 ROS_DEBUG ("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",
00325 info, enorm (m, fvec), model_coefficients_.at (0), model_coefficients_.at (1), model_coefficients_.at (2), model_coefficients_.at (3),
00326 x[0], x[1], x[2], x[3]);
00327
00328 refit_coefficients.resize (n);
00329 for (int d = 0; d < n; d++)
00330 refit_coefficients[d] = x[d];
00331
00332 free (wa); free (fvec);
00333 }
00334
00336
00344 int
00345 SACModelSphere::functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag)
00346 {
00347 SACModelSphere *model = (SACModelSphere*)p;
00348
00349 for (int i = 0; i < m; i ++)
00350 {
00351
00352 double xt = model->cloud_->points[model->tmp_inliers_->at (i)].x - x[0];
00353 double yt = model->cloud_->points[model->tmp_inliers_->at (i)].y - x[1];
00354 double zt = model->cloud_->points[model->tmp_inliers_->at (i)].z - x[2];
00355
00356
00357 fvec[i] = sqrt (xt * xt + yt * yt + zt * zt) - x[3];
00358 }
00359 return (0);
00360 }
00361
00363
00367 bool
00368 SACModelSphere::doSamplesVerifyModel (const std::set<int> &indices, double threshold)
00369 {
00370 for (std::set<int>::iterator it = indices.begin (); it != indices.end (); ++it)
00371
00372
00373 if (fabs (sqrt (
00374 ( cloud_->points.at (*it).x - model_coefficients_.at (0) ) *
00375 ( cloud_->points.at (*it).x - model_coefficients_.at (0) ) +
00376
00377 ( cloud_->points.at (*it).y - model_coefficients_.at (1) ) *
00378 ( cloud_->points.at (*it).y - model_coefficients_.at (1) ) +
00379
00380 ( cloud_->points.at (*it).z - model_coefficients_.at (2) ) *
00381 ( cloud_->points.at (*it).z - model_coefficients_.at (2) )
00382 ) - model_coefficients_.at (3)) > threshold)
00383 return (false);
00384
00385 return (true);
00386 }
00387 }