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
00039 #include <gtest/gtest.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include "boost.h"
00042 #include <pcl/sample_consensus/sac.h>
00043 #include <pcl/sample_consensus/lmeds.h>
00044 #include <pcl/sample_consensus/ransac.h>
00045 #include <pcl/sample_consensus/rransac.h>
00046 #include <pcl/sample_consensus/msac.h>
00047 #include <pcl/sample_consensus/rmsac.h>
00048 #include <pcl/sample_consensus/mlesac.h>
00049 #include <pcl/sample_consensus/sac_model.h>
00050 #include <pcl/sample_consensus/sac_model_plane.h>
00051 #include <pcl/sample_consensus/sac_model_sphere.h>
00052 #include <pcl/sample_consensus/sac_model_cone.h>
00053 #include <pcl/sample_consensus/sac_model_cylinder.h>
00054 #include <pcl/sample_consensus/sac_model_circle.h>
00055 #include <pcl/sample_consensus/sac_model_circle3d.h>
00056 #include <pcl/sample_consensus/sac_model_line.h>
00057 #include <pcl/sample_consensus/sac_model_normal_plane.h>
00058 #include <pcl/sample_consensus/sac_model_normal_sphere.h>
00059 #include <pcl/sample_consensus/sac_model_parallel_plane.h>
00060 #include <pcl/sample_consensus/sac_model_normal_parallel_plane.h>
00061 #include <pcl/features/normal_3d.h>
00062
00063 using namespace pcl;
00064 using namespace pcl::io;
00065 using namespace std;
00066
00067 typedef SampleConsensusModel<PointXYZ>::Ptr SampleConsensusModelPtr;
00068 typedef SampleConsensusModelPlane<PointXYZ>::Ptr SampleConsensusModelPlanePtr;
00069 typedef SampleConsensusModelSphere<PointXYZ>::Ptr SampleConsensusModelSpherePtr;
00070 typedef SampleConsensusModelCylinder<PointXYZ, Normal>::Ptr SampleConsensusModelCylinderPtr;
00071 typedef SampleConsensusModelCone<PointXYZ, Normal>::Ptr SampleConsensusModelConePtr;
00072 typedef SampleConsensusModelCircle2D<PointXYZ>::Ptr SampleConsensusModelCircle2DPtr;
00073 typedef SampleConsensusModelCircle3D<PointXYZ>::Ptr SampleConsensusModelCircle3DPtr;
00074 typedef SampleConsensusModelLine<PointXYZ>::Ptr SampleConsensusModelLinePtr;
00075 typedef SampleConsensusModelNormalPlane<PointXYZ, Normal>::Ptr SampleConsensusModelNormalPlanePtr;
00076 typedef SampleConsensusModelNormalSphere<PointXYZ, Normal>::Ptr SampleConsensusModelNormalSpherePtr;
00077 typedef SampleConsensusModelParallelPlane<PointXYZ>::Ptr SampleConsensusModelParallelPlanePtr;
00078 typedef SampleConsensusModelNormalParallelPlane<PointXYZ, Normal>::Ptr SampleConsensusModelNormalParallelPlanePtr;
00079
00080 PointCloud<PointXYZ>::Ptr cloud_ (new PointCloud<PointXYZ> ());
00081 PointCloud<Normal>::Ptr normals_ (new PointCloud<Normal> ());
00082 vector<int> indices_;
00083 float plane_coeffs_[] = {-0.8964f, -0.5868f, -1.208f};
00084
00086
00087 template<typename ModelType, typename SacType>
00088 void verifyPlaneSac (ModelType & model, SacType & sac, unsigned int inlier_number = 2000, float tol = 1e-1f,
00089 float refined_tol = 1e-1f, float proj_tol = 1e-3f)
00090 {
00091
00092 bool result = sac.computeModel ();
00093 ASSERT_EQ (result, true);
00094
00095 std::vector<int> sample;
00096 sac.getModel (sample);
00097 EXPECT_EQ (int (sample.size ()), 3);
00098
00099 std::vector<int> inliers;
00100 sac.getInliers (inliers);
00101 EXPECT_GE (int (inliers.size ()), inlier_number);
00102
00103 Eigen::VectorXf coeff;
00104 sac.getModelCoefficients (coeff);
00105 EXPECT_EQ (int (coeff.size ()), 4);
00106 EXPECT_NEAR (coeff[0]/coeff[3], plane_coeffs_[0], tol);
00107 EXPECT_NEAR (coeff[1]/coeff[3], plane_coeffs_[1], tol);
00108 EXPECT_NEAR (coeff[2]/coeff[3], plane_coeffs_[2], tol);
00109
00110
00111 Eigen::VectorXf coeff_refined;
00112 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00113 EXPECT_EQ (int (coeff_refined.size ()), 4);
00114 EXPECT_NEAR (coeff_refined[0]/coeff_refined[3], plane_coeffs_[0], refined_tol);
00115 EXPECT_NEAR (coeff_refined[1]/coeff_refined[3], plane_coeffs_[1], refined_tol);
00116
00117
00118
00119
00120
00121 PointCloud<PointXYZ> proj_points;
00122 model->projectPoints (inliers, coeff_refined, proj_points);
00123 EXPECT_NEAR (proj_points.points[20].x, 1.1266, proj_tol);
00124 EXPECT_NEAR (proj_points.points[20].y, 0.0152, proj_tol);
00125 EXPECT_NEAR (proj_points.points[20].z, -0.0156, proj_tol);
00126
00127 EXPECT_NEAR (proj_points.points[30].x, 1.1843, proj_tol);
00128 EXPECT_NEAR (proj_points.points[30].y, -0.0635, proj_tol);
00129 EXPECT_NEAR (proj_points.points[30].z, -0.0201, proj_tol);
00130
00131 EXPECT_NEAR (proj_points.points[50].x, 1.0749, proj_tol);
00132 EXPECT_NEAR (proj_points.points[50].y, -0.0586, proj_tol);
00133 EXPECT_NEAR (proj_points.points[50].z, 0.0587, refined_tol);
00134 }
00135
00137 TEST (SampleConsensusModelPlane, Base)
00138 {
00139
00140 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00141
00142
00143 PointCloud<PointXYZ>::ConstPtr cloud = model->getInputCloud ();
00144 ASSERT_EQ (cloud->points.size (), cloud_->points.size ());
00145
00146 model->setInputCloud (cloud);
00147 cloud = model->getInputCloud ();
00148 ASSERT_EQ (cloud->points.size (), cloud_->points.size ());
00149
00150 boost::shared_ptr<vector<int> > indices = model->getIndices ();
00151 ASSERT_EQ (indices->size (), indices_.size ());
00152 model->setIndices (indices_);
00153 indices = model->getIndices ();
00154 ASSERT_EQ (indices->size (), indices_.size ());
00155 model->setIndices (indices);
00156 indices = model->getIndices ();
00157 ASSERT_EQ (indices->size (), indices_.size ());
00158 }
00159
00161 TEST (RANSAC, Base)
00162 {
00163
00164 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00165
00166
00167 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00168
00169
00170 ASSERT_EQ (sac.getDistanceThreshold (), 0.03);
00171 sac.setDistanceThreshold (0.03);
00172 ASSERT_EQ (sac.getDistanceThreshold (), 0.03);
00173
00174 sac.setProbability (0.99);
00175 ASSERT_EQ (sac.getProbability (), 0.99);
00176
00177 sac.setMaxIterations (10000);
00178 ASSERT_EQ (sac.getMaxIterations (), 10000);
00179 }
00180
00182 TEST (RANSAC, SampleConsensusModelPlane)
00183 {
00184 srand (0);
00185
00186 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00187
00188
00189 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00190
00191 verifyPlaneSac(model, sac);
00192 }
00193
00195 TEST (LMedS, SampleConsensusModelPlane)
00196 {
00197 srand (0);
00198
00199 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00200
00201
00202 LeastMedianSquares<PointXYZ> sac (model, 0.03);
00203
00204 verifyPlaneSac(model, sac);
00205 }
00206
00208 TEST (MSAC, SampleConsensusModelPlane)
00209 {
00210 srand (0);
00211
00212 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00213
00214
00215 MEstimatorSampleConsensus<PointXYZ> sac (model, 0.03);
00216
00217 verifyPlaneSac (model, sac);
00218 }
00219
00221 TEST (RRANSAC, SampleConsensusModelPlane)
00222 {
00223 srand (0);
00224
00225 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00226
00227
00228 RandomizedRandomSampleConsensus<PointXYZ> sac (model, 0.03);
00229
00230 sac.setFractionNrPretest (10.0);
00231 ASSERT_EQ (sac.getFractionNrPretest (), 10.0);
00232
00233 verifyPlaneSac(model, sac, 600, 1.0f, 1.0f, 0.01f);
00234 }
00235
00237 TEST (RMSAC, SampleConsensusModelPlane)
00238 {
00239 srand (0);
00240
00241 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00242
00243
00244 RandomizedMEstimatorSampleConsensus<PointXYZ> sac (model, 0.03);
00245
00246 sac.setFractionNrPretest (10.0);
00247 ASSERT_EQ (sac.getFractionNrPretest (), 10.0);
00248
00249 verifyPlaneSac(model, sac, 600, 1.0f, 1.0f, 0.01f);
00250 }
00251
00253 TEST (RANSAC, SampleConsensusModelNormalParallelPlane)
00254 {
00255 srand (0);
00256
00257 PointCloud<PointXYZ> cloud;
00258 PointCloud<Normal> normals;
00259 cloud.points.resize (10);
00260 normals.resize (10);
00261
00262 for (unsigned idx = 0; idx < cloud.size (); ++idx)
00263 {
00264 cloud.points[idx].x = static_cast<float> ((rand () % 200) - 100);
00265 cloud.points[idx].y = static_cast<float> ((rand () % 200) - 100);
00266 cloud.points[idx].z = 0.0f;
00267
00268 normals.points[idx].normal_x = 0.0f;
00269 normals.points[idx].normal_y = 0.0f;
00270 normals.points[idx].normal_z = 1.0f;
00271 }
00272
00273
00274 SampleConsensusModelNormalParallelPlanePtr model (new SampleConsensusModelNormalParallelPlane<PointXYZ, Normal> (cloud.makeShared ()));
00275 model->setInputNormals (normals.makeShared ());
00276
00277 const float max_angle_rad = 0.01f;
00278 const float angle_eps = 0.001f;
00279 model->setEpsAngle (max_angle_rad);
00280
00281
00282 {
00283 model->setAxis (Eigen::Vector3f (0, 0, 1));
00284
00285 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00286 sac.computeModel();
00287
00288 std::vector<int> inliers;
00289 sac.getInliers (inliers);
00290 ASSERT_EQ (inliers.size (), cloud.size ());
00291 }
00292
00293
00294 {
00295 model->setAxis (Eigen::Vector3f(0, sin(max_angle_rad * (1 - angle_eps)), cos(max_angle_rad * (1 - angle_eps))));
00296 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00297 sac.computeModel();
00298
00299 std::vector<int> inliers;
00300 sac.getInliers (inliers);
00301 ASSERT_EQ (inliers.size (), cloud.size ());
00302 }
00303
00304
00305 {
00306 model->setAxis (Eigen::Vector3f(0, sin(max_angle_rad * (1 + angle_eps)), cos(max_angle_rad * (1 + angle_eps))));
00307 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00308 sac.computeModel();
00309
00310 std::vector<int> inliers;
00311 sac.getInliers (inliers);
00312 ASSERT_EQ (inliers.size (), 0);
00313 }
00314 }
00315
00316
00318 TEST (MLESAC, SampleConsensusModelPlane)
00319 {
00320 srand (0);
00321
00322 SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (cloud_));
00323
00324
00325 MaximumLikelihoodSampleConsensus<PointXYZ> sac (model, 0.03);
00326
00327 verifyPlaneSac(model, sac, 1000, 0.3f, 0.2f, 0.01f);
00328 }
00329
00331 TEST (RANSAC, SampleConsensusModelSphere)
00332 {
00333 srand (0);
00334
00335
00336 PointCloud<PointXYZ> cloud;
00337 cloud.points.resize (10);
00338 cloud.points[0].x = 1.7068f; cloud.points[0].y = 1.0684f; cloud.points[0].z = 2.2147f;
00339 cloud.points[1].x = 2.4708f; cloud.points[1].y = 2.3081f; cloud.points[1].z = 1.1736f;
00340 cloud.points[2].x = 2.7609f; cloud.points[2].y = 1.9095f; cloud.points[2].z = 1.3574f;
00341 cloud.points[3].x = 2.8016f; cloud.points[3].y = 1.6704f; cloud.points[3].z = 1.5009f;
00342 cloud.points[4].x = 1.8517f; cloud.points[4].y = 2.0276f; cloud.points[4].z = 1.0112f;
00343 cloud.points[5].x = 1.8726f; cloud.points[5].y = 1.3539f; cloud.points[5].z = 2.7523f;
00344 cloud.points[6].x = 2.5179f; cloud.points[6].y = 2.3218f; cloud.points[6].z = 1.2074f;
00345 cloud.points[7].x = 2.4026f; cloud.points[7].y = 2.5114f; cloud.points[7].z = 2.7588f;
00346 cloud.points[8].x = 2.6999f; cloud.points[8].y = 2.5606f; cloud.points[8].z = 1.5571f;
00347 cloud.points[9].x = 0.0f; cloud.points[9].y = 0.0f; cloud.points[9].z = 0.0f;
00348
00349
00350 SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere<PointXYZ> (cloud.makeShared ()));
00351
00352
00353 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00354
00355
00356 bool result = sac.computeModel ();
00357 ASSERT_EQ (result, true);
00358
00359 std::vector<int> sample;
00360 sac.getModel (sample);
00361 EXPECT_EQ (int (sample.size ()), 4);
00362
00363 std::vector<int> inliers;
00364 sac.getInliers (inliers);
00365 EXPECT_EQ (int (inliers.size ()), 9);
00366
00367 Eigen::VectorXf coeff;
00368 sac.getModelCoefficients (coeff);
00369 EXPECT_EQ (int (coeff.size ()), 4);
00370 EXPECT_NEAR (coeff[0]/coeff[3], 2, 1e-2);
00371 EXPECT_NEAR (coeff[1]/coeff[3], 2, 1e-2);
00372 EXPECT_NEAR (coeff[2]/coeff[3], 2, 1e-2);
00373
00374 Eigen::VectorXf coeff_refined;
00375 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00376 EXPECT_EQ (int (coeff_refined.size ()), 4);
00377 EXPECT_NEAR (coeff_refined[0]/coeff_refined[3], 2, 1e-2);
00378 EXPECT_NEAR (coeff_refined[1]/coeff_refined[3], 2, 1e-2);
00379 EXPECT_NEAR (coeff_refined[2]/coeff_refined[3], 2, 1e-2);
00380 }
00381
00383 TEST (RANSAC, SampleConsensusModelNormalSphere)
00384 {
00385 srand (0);
00386
00387
00388 PointCloud<PointXYZ> cloud;
00389 PointCloud<Normal> normals;
00390 cloud.points.resize (27); normals.points.resize (27);
00391 cloud.points[0].x = -0.014695f; cloud.points[0].y = 0.009549f; cloud.points[0].z = 0.954775f;
00392 cloud.points[1].x = 0.014695f; cloud.points[1].y = 0.009549f; cloud.points[1].z = 0.954775f;
00393 cloud.points[2].x = -0.014695f; cloud.points[2].y = 0.040451f; cloud.points[2].z = 0.954775f;
00394 cloud.points[3].x = 0.014695f; cloud.points[3].y = 0.040451f; cloud.points[3].z = 0.954775f;
00395 cloud.points[4].x = -0.009082f; cloud.points[4].y = -0.015451f; cloud.points[4].z = 0.972049f;
00396 cloud.points[5].x = 0.009082f; cloud.points[5].y = -0.015451f; cloud.points[5].z = 0.972049f;
00397 cloud.points[6].x = -0.038471f; cloud.points[6].y = 0.009549f; cloud.points[6].z = 0.972049f;
00398 cloud.points[7].x = 0.038471f; cloud.points[7].y = 0.009549f; cloud.points[7].z = 0.972049f;
00399 cloud.points[8].x = -0.038471f; cloud.points[8].y = 0.040451f; cloud.points[8].z = 0.972049f;
00400 cloud.points[9].x = 0.038471f; cloud.points[9].y = 0.040451f; cloud.points[9].z = 0.972049f;
00401 cloud.points[10].x = -0.009082f; cloud.points[10].y = 0.065451f; cloud.points[10].z = 0.972049f;
00402 cloud.points[11].x = 0.009082f; cloud.points[11].y = 0.065451f; cloud.points[11].z = 0.972049f;
00403 cloud.points[12].x = -0.023776f; cloud.points[12].y = -0.015451f; cloud.points[12].z = 0.982725f;
00404 cloud.points[13].x = 0.023776f; cloud.points[13].y = -0.015451f; cloud.points[13].z = 0.982725f;
00405 cloud.points[14].x = -0.023776f; cloud.points[14].y = 0.065451f; cloud.points[14].z = 0.982725f;
00406 cloud.points[15].x = 0.023776f; cloud.points[15].y = 0.065451f; cloud.points[15].z = 0.982725f;
00407 cloud.points[16].x = -0.000000f; cloud.points[16].y = -0.025000f; cloud.points[16].z = 1.000000f;
00408 cloud.points[17].x = 0.000000f; cloud.points[17].y = -0.025000f; cloud.points[17].z = 1.000000f;
00409 cloud.points[18].x = -0.029389f; cloud.points[18].y = -0.015451f; cloud.points[18].z = 1.000000f;
00410 cloud.points[19].x = 0.029389f; cloud.points[19].y = -0.015451f; cloud.points[19].z = 1.000000f;
00411 cloud.points[20].x = -0.047553f; cloud.points[20].y = 0.009549f; cloud.points[20].z = 1.000000f;
00412 cloud.points[21].x = 0.047553f; cloud.points[21].y = 0.009549f; cloud.points[21].z = 1.000000f;
00413 cloud.points[22].x = -0.047553f; cloud.points[22].y = 0.040451f; cloud.points[22].z = 1.000000f;
00414 cloud.points[23].x = 0.047553f; cloud.points[23].y = 0.040451f; cloud.points[23].z = 1.000000f;
00415 cloud.points[24].x = -0.029389f; cloud.points[24].y = 0.065451f; cloud.points[24].z = 1.000000f;
00416 cloud.points[25].x = 0.029389f; cloud.points[25].y = 0.065451f; cloud.points[25].z = 1.000000f;
00417 cloud.points[26].x = 0.000000f; cloud.points[26].y = 0.075000f; cloud.points[26].z = 1.000000f;
00418
00419 normals.points[0].normal[0] = -0.293893f; normals.points[0].normal[1] = -0.309017f; normals.points[0].normal[2] = -0.904509f;
00420 normals.points[1].normal[0] = 0.293893f; normals.points[1].normal[1] = -0.309017f; normals.points[1].normal[2] = -0.904508f;
00421 normals.points[2].normal[0] = -0.293893f; normals.points[2].normal[1] = 0.309017f; normals.points[2].normal[2] = -0.904509f;
00422 normals.points[3].normal[0] = 0.293893f; normals.points[3].normal[1] = 0.309017f; normals.points[3].normal[2] = -0.904508f;
00423 normals.points[4].normal[0] = -0.181636f; normals.points[4].normal[1] = -0.809017f; normals.points[4].normal[2] = -0.559017f;
00424 normals.points[5].normal[0] = 0.181636f; normals.points[5].normal[1] = -0.809017f; normals.points[5].normal[2] = -0.559017f;
00425 normals.points[6].normal[0] = -0.769421f; normals.points[6].normal[1] = -0.309017f; normals.points[6].normal[2] = -0.559017f;
00426 normals.points[7].normal[0] = 0.769421f; normals.points[7].normal[1] = -0.309017f; normals.points[7].normal[2] = -0.559017f;
00427 normals.points[8].normal[0] = -0.769421f; normals.points[8].normal[1] = 0.309017f; normals.points[8].normal[2] = -0.559017f;
00428 normals.points[9].normal[0] = 0.769421f; normals.points[9].normal[1] = 0.309017f; normals.points[9].normal[2] = -0.559017f;
00429 normals.points[10].normal[0] = -0.181636f; normals.points[10].normal[1] = 0.809017f; normals.points[10].normal[2] = -0.559017f;
00430 normals.points[11].normal[0] = 0.181636f; normals.points[11].normal[1] = 0.809017f; normals.points[11].normal[2] = -0.559017f;
00431 normals.points[12].normal[0] = -0.475528f; normals.points[12].normal[1] = -0.809017f; normals.points[12].normal[2] = -0.345491f;
00432 normals.points[13].normal[0] = 0.475528f; normals.points[13].normal[1] = -0.809017f; normals.points[13].normal[2] = -0.345491f;
00433 normals.points[14].normal[0] = -0.475528f; normals.points[14].normal[1] = 0.809017f; normals.points[14].normal[2] = -0.345491f;
00434 normals.points[15].normal[0] = 0.475528f; normals.points[15].normal[1] = 0.809017f; normals.points[15].normal[2] = -0.345491f;
00435 normals.points[16].normal[0] = -0.000000f; normals.points[16].normal[1] = -1.000000f; normals.points[16].normal[2] = 0.000000f;
00436 normals.points[17].normal[0] = 0.000000f; normals.points[17].normal[1] = -1.000000f; normals.points[17].normal[2] = 0.000000f;
00437 normals.points[18].normal[0] = -0.587785f; normals.points[18].normal[1] = -0.809017f; normals.points[18].normal[2] = 0.000000f;
00438 normals.points[19].normal[0] = 0.587785f; normals.points[19].normal[1] = -0.809017f; normals.points[19].normal[2] = 0.000000f;
00439 normals.points[20].normal[0] = -0.951057f; normals.points[20].normal[1] = -0.309017f; normals.points[20].normal[2] = 0.000000f;
00440 normals.points[21].normal[0] = 0.951057f; normals.points[21].normal[1] = -0.309017f; normals.points[21].normal[2] = 0.000000f;
00441 normals.points[22].normal[0] = -0.951057f; normals.points[22].normal[1] = 0.309017f; normals.points[22].normal[2] = 0.000000f;
00442 normals.points[23].normal[0] = 0.951057f; normals.points[23].normal[1] = 0.309017f; normals.points[23].normal[2] = 0.000000f;
00443 normals.points[24].normal[0] = -0.587785f; normals.points[24].normal[1] = 0.809017f; normals.points[24].normal[2] = 0.000000f;
00444 normals.points[25].normal[0] = 0.587785f; normals.points[25].normal[1] = 0.809017f; normals.points[25].normal[2] = 0.000000f;
00445 normals.points[26].normal[0] = 0.000000f; normals.points[26].normal[1] = 1.000000f; normals.points[26].normal[2] = 0.000000f;
00446
00447
00448 SampleConsensusModelNormalSpherePtr model (new SampleConsensusModelNormalSphere<PointXYZ, Normal> (cloud.makeShared ()));
00449 model->setInputNormals(normals.makeShared ());
00450
00451
00452 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00453
00454
00455 bool result = sac.computeModel ();
00456 ASSERT_EQ (result, true);
00457
00458 std::vector<int> sample;
00459 sac.getModel (sample);
00460 EXPECT_EQ (int (sample.size ()), 4);
00461
00462 std::vector<int> inliers;
00463 sac.getInliers (inliers);
00464 EXPECT_EQ (int (inliers.size ()), 27);
00465
00466 Eigen::VectorXf coeff;
00467 sac.getModelCoefficients (coeff);
00468 EXPECT_EQ (int (coeff.size ()), 4);
00469 EXPECT_NEAR (coeff[0], 0.0, 1e-2);
00470 EXPECT_NEAR (coeff[1], 0.025, 1e-2);
00471 EXPECT_NEAR (coeff[2], 1.0, 1e-2);
00472 EXPECT_NEAR (coeff[3], 0.05, 1e-2);
00473 Eigen::VectorXf coeff_refined;
00474 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00475 EXPECT_EQ (int (coeff_refined.size ()), 4);
00476 EXPECT_NEAR (coeff_refined[0], 0.0, 1e-2);
00477 EXPECT_NEAR (coeff_refined[1], 0.025, 1e-2);
00478 EXPECT_NEAR (coeff_refined[2], 1.0, 1e-2);
00479 EXPECT_NEAR (coeff_refined[3], 0.05, 1e-2);
00480 }
00482 TEST (RANSAC, SampleConsensusModelCone)
00483 {
00484 srand (0);
00485
00486
00487 PointCloud<PointXYZ> cloud;
00488 PointCloud<Normal> normals;
00489 cloud.points.resize (31); normals.points.resize (31);
00490
00491 cloud.points[0].x = -0.011247f; cloud.points[0].y = 0.200000f; cloud.points[0].z = 0.965384f;
00492 cloud.points[1].x = 0.000000f; cloud.points[1].y = 0.200000f; cloud.points[1].z = 0.963603f;
00493 cloud.points[2].x = 0.011247f; cloud.points[2].y = 0.200000f; cloud.points[2].z = 0.965384f;
00494 cloud.points[3].x = -0.016045f; cloud.points[3].y = 0.175000f; cloud.points[3].z = 0.977916f;
00495 cloud.points[4].x = -0.008435f; cloud.points[4].y = 0.175000f; cloud.points[4].z = 0.974038f;
00496 cloud.points[5].x = 0.004218f; cloud.points[5].y = 0.175000f; cloud.points[5].z = 0.973370f;
00497 cloud.points[6].x = 0.016045f; cloud.points[6].y = 0.175000f; cloud.points[6].z = 0.977916f;
00498 cloud.points[7].x = -0.025420f; cloud.points[7].y = 0.200000f; cloud.points[7].z = 0.974580f;
00499 cloud.points[8].x = 0.025420f; cloud.points[8].y = 0.200000f; cloud.points[8].z = 0.974580f;
00500 cloud.points[9].x = -0.012710f; cloud.points[9].y = 0.150000f; cloud.points[9].z = 0.987290f;
00501 cloud.points[10].x = -0.005624f; cloud.points[10].y = 0.150000f; cloud.points[10].z = 0.982692f;
00502 cloud.points[11].x = 0.002812f; cloud.points[11].y = 0.150000f; cloud.points[11].z = 0.982247f;
00503 cloud.points[12].x = 0.012710f; cloud.points[12].y = 0.150000f; cloud.points[12].z = 0.987290f;
00504 cloud.points[13].x = -0.022084f; cloud.points[13].y = 0.175000f; cloud.points[13].z = 0.983955f;
00505 cloud.points[14].x = 0.022084f; cloud.points[14].y = 0.175000f; cloud.points[14].z = 0.983955f;
00506 cloud.points[15].x = -0.034616f; cloud.points[15].y = 0.200000f; cloud.points[15].z = 0.988753f;
00507 cloud.points[16].x = 0.034616f; cloud.points[16].y = 0.200000f; cloud.points[16].z = 0.988753f;
00508 cloud.points[17].x = -0.006044f; cloud.points[17].y = 0.125000f; cloud.points[17].z = 0.993956f;
00509 cloud.points[18].x = 0.004835f; cloud.points[18].y = 0.125000f; cloud.points[18].z = 0.993345f;
00510 cloud.points[19].x = -0.017308f; cloud.points[19].y = 0.150000f; cloud.points[19].z = 0.994376f;
00511 cloud.points[20].x = 0.017308f; cloud.points[20].y = 0.150000f; cloud.points[20].z = 0.994376f;
00512 cloud.points[21].x = -0.025962f; cloud.points[21].y = 0.175000f; cloud.points[21].z = 0.991565f;
00513 cloud.points[22].x = 0.025962f; cloud.points[22].y = 0.175000f; cloud.points[22].z = 0.991565f;
00514 cloud.points[23].x = -0.009099f; cloud.points[23].y = 0.125000f; cloud.points[23].z = 1.000000f;
00515 cloud.points[24].x = 0.009099f; cloud.points[24].y = 0.125000f; cloud.points[24].z = 1.000000f;
00516 cloud.points[25].x = -0.018199f; cloud.points[25].y = 0.150000f; cloud.points[25].z = 1.000000f;
00517 cloud.points[26].x = 0.018199f; cloud.points[26].y = 0.150000f; cloud.points[26].z = 1.000000f;
00518 cloud.points[27].x = -0.027298f; cloud.points[27].y = 0.175000f; cloud.points[27].z = 1.000000f;
00519 cloud.points[28].x = 0.027298f; cloud.points[28].y = 0.175000f; cloud.points[28].z = 1.000000f;
00520 cloud.points[29].x = -0.036397f; cloud.points[29].y = 0.200000f; cloud.points[29].z = 1.000000f;
00521 cloud.points[30].x = 0.036397f; cloud.points[30].y = 0.200000f; cloud.points[30].z = 1.000000f;
00522
00523 normals.points[0].normal[0] = -0.290381f; normals.points[0].normal[1] = -0.342020f; normals.points[0].normal[2] = -0.893701f;
00524 normals.points[1].normal[0] = 0.000000f; normals.points[1].normal[1] = -0.342020f; normals.points[1].normal[2] = -0.939693f;
00525 normals.points[2].normal[0] = 0.290381f; normals.points[2].normal[1] = -0.342020f; normals.points[2].normal[2] = -0.893701f;
00526 normals.points[3].normal[0] = -0.552338f; normals.points[3].normal[1] = -0.342020f; normals.points[3].normal[2] = -0.760227f;
00527 normals.points[4].normal[0] = -0.290381f; normals.points[4].normal[1] = -0.342020f; normals.points[4].normal[2] = -0.893701f;
00528 normals.points[5].normal[0] = 0.145191f; normals.points[5].normal[1] = -0.342020f; normals.points[5].normal[2] = -0.916697f;
00529 normals.points[6].normal[0] = 0.552337f; normals.points[6].normal[1] = -0.342020f; normals.points[6].normal[2] = -0.760227f;
00530 normals.points[7].normal[0] = -0.656282f; normals.points[7].normal[1] = -0.342020f; normals.points[7].normal[2] = -0.656283f;
00531 normals.points[8].normal[0] = 0.656282f; normals.points[8].normal[1] = -0.342020f; normals.points[8].normal[2] = -0.656283f;
00532 normals.points[9].normal[0] = -0.656283f; normals.points[9].normal[1] = -0.342020f; normals.points[9].normal[2] = -0.656282f;
00533 normals.points[10].normal[0] = -0.290381f; normals.points[10].normal[1] = -0.342020f; normals.points[10].normal[2] = -0.893701f;
00534 normals.points[11].normal[0] = 0.145191f; normals.points[11].normal[1] = -0.342020f; normals.points[11].normal[2] = -0.916697f;
00535 normals.points[12].normal[0] = 0.656282f; normals.points[12].normal[1] = -0.342020f; normals.points[12].normal[2] = -0.656282f;
00536 normals.points[13].normal[0] = -0.760228f; normals.points[13].normal[1] = -0.342020f; normals.points[13].normal[2] = -0.552337f;
00537 normals.points[14].normal[0] = 0.760228f; normals.points[14].normal[1] = -0.342020f; normals.points[14].normal[2] = -0.552337f;
00538 normals.points[15].normal[0] = -0.893701f; normals.points[15].normal[1] = -0.342020f; normals.points[15].normal[2] = -0.290380f;
00539 normals.points[16].normal[0] = 0.893701f; normals.points[16].normal[1] = -0.342020f; normals.points[16].normal[2] = -0.290380f;
00540 normals.points[17].normal[0] = -0.624162f; normals.points[17].normal[1] = -0.342020f; normals.points[17].normal[2] = -0.624162f;
00541 normals.points[18].normal[0] = 0.499329f; normals.points[18].normal[1] = -0.342020f; normals.points[18].normal[2] = -0.687268f;
00542 normals.points[19].normal[0] = -0.893701f; normals.points[19].normal[1] = -0.342020f; normals.points[19].normal[2] = -0.290380f;
00543 normals.points[20].normal[0] = 0.893701f; normals.points[20].normal[1] = -0.342020f; normals.points[20].normal[2] = -0.290380f;
00544 normals.points[21].normal[0] = -0.893701f; normals.points[21].normal[1] = -0.342020f; normals.points[21].normal[2] = -0.290381f;
00545 normals.points[22].normal[0] = 0.893701f; normals.points[22].normal[1] = -0.342020f; normals.points[22].normal[2] = -0.290381f;
00546 normals.points[23].normal[0] = -0.939693f; normals.points[23].normal[1] = -0.342020f; normals.points[23].normal[2] = 0.000000f;
00547 normals.points[24].normal[0] = 0.939693f; normals.points[24].normal[1] = -0.342020f; normals.points[24].normal[2] = 0.000000f;
00548 normals.points[25].normal[0] = -0.939693f; normals.points[25].normal[1] = -0.342020f; normals.points[25].normal[2] = 0.000000f;
00549 normals.points[26].normal[0] = 0.939693f; normals.points[26].normal[1] = -0.342020f; normals.points[26].normal[2] = 0.000000f;
00550 normals.points[27].normal[0] = -0.939693f; normals.points[27].normal[1] = -0.342020f; normals.points[27].normal[2] = 0.000000f;
00551 normals.points[28].normal[0] = 0.939693f; normals.points[28].normal[1] = -0.342020f; normals.points[28].normal[2] = 0.000000f;
00552 normals.points[29].normal[0] = -0.939693f; normals.points[29].normal[1] = -0.342020f; normals.points[29].normal[2] = 0.000000f;
00553 normals.points[30].normal[0] = 0.939693f; normals.points[30].normal[1] = -0.342020f; normals.points[30].normal[2] = 0.000000f;
00554
00555
00556
00557 SampleConsensusModelConePtr model (new SampleConsensusModelCone<PointXYZ, Normal> (cloud.makeShared ()));
00558 model->setInputNormals (normals.makeShared ());
00559
00560
00561 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00562
00563
00564 bool result = sac.computeModel ();
00565 ASSERT_EQ (result, true);
00566
00567 std::vector<int> sample;
00568 sac.getModel (sample);
00569 EXPECT_EQ (int (sample.size ()), 3);
00570
00571 std::vector<int> inliers;
00572 sac.getInliers (inliers);
00573 EXPECT_EQ (int (inliers.size ()), 31);
00574
00575 Eigen::VectorXf coeff;
00576 sac.getModelCoefficients (coeff);
00577 EXPECT_EQ (int (coeff.size ()), 7);
00578 EXPECT_NEAR (coeff[0], 0, 1e-2);
00579 EXPECT_NEAR (coeff[1], 0.1, 1e-2);
00580 EXPECT_NEAR (coeff[6], 0.349066, 1e-2);
00581
00582 Eigen::VectorXf coeff_refined;
00583 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00584 EXPECT_EQ (int (coeff_refined.size ()), 7);
00585 EXPECT_NEAR (coeff_refined[6], 0.349066 , 1e-2);
00586 }
00587
00589 TEST (RANSAC, SampleConsensusModelCylinder)
00590 {
00591 srand (0);
00592
00593
00594 PointCloud<PointXYZ> cloud;
00595 PointCloud<Normal> normals;
00596 cloud.points.resize (20); normals.points.resize (20);
00597
00598 cloud.points[0].x = -0.499902f; cloud.points[0].y = 2.199701f; cloud.points[0].z = 0.000008f;
00599 cloud.points[1].x = -0.875397f; cloud.points[1].y = 2.030177f; cloud.points[1].z = 0.050104f;
00600 cloud.points[2].x = -0.995875f; cloud.points[2].y = 1.635973f; cloud.points[2].z = 0.099846f;
00601 cloud.points[3].x = -0.779523f; cloud.points[3].y = 1.285527f; cloud.points[3].z = 0.149961f;
00602 cloud.points[4].x = -0.373285f; cloud.points[4].y = 1.216488f; cloud.points[4].z = 0.199959f;
00603 cloud.points[5].x = -0.052893f; cloud.points[5].y = 1.475973f; cloud.points[5].z = 0.250101f;
00604 cloud.points[6].x = -0.036558f; cloud.points[6].y = 1.887591f; cloud.points[6].z = 0.299839f;
00605 cloud.points[7].x = -0.335048f; cloud.points[7].y = 2.171994f; cloud.points[7].z = 0.350001f;
00606 cloud.points[8].x = -0.745456f; cloud.points[8].y = 2.135528f; cloud.points[8].z = 0.400072f;
00607 cloud.points[9].x = -0.989282f; cloud.points[9].y = 1.803311f; cloud.points[9].z = 0.449983f;
00608 cloud.points[10].x = -0.900651f; cloud.points[10].y = 1.400701f; cloud.points[10].z = 0.500126f;
00609 cloud.points[11].x = -0.539658f; cloud.points[11].y = 1.201468f; cloud.points[11].z = 0.550079f;
00610 cloud.points[12].x = -0.151875f; cloud.points[12].y = 1.340951f; cloud.points[12].z = 0.599983f;
00611 cloud.points[13].x = -0.000724f; cloud.points[13].y = 1.724373f; cloud.points[13].z = 0.649882f;
00612 cloud.points[14].x = -0.188573f; cloud.points[14].y = 2.090983f; cloud.points[14].z = 0.699854f;
00613 cloud.points[15].x = -0.587925f; cloud.points[15].y = 2.192257f; cloud.points[15].z = 0.749956f;
00614 cloud.points[16].x = -0.927724f; cloud.points[16].y = 1.958846f; cloud.points[16].z = 0.800008f;
00615 cloud.points[17].x = -0.976888f; cloud.points[17].y = 1.549655f; cloud.points[17].z = 0.849970f;
00616 cloud.points[18].x = -0.702003f; cloud.points[18].y = 1.242707f; cloud.points[18].z = 0.899954f;
00617 cloud.points[19].x = -0.289916f; cloud.points[19].y = 1.246296f; cloud.points[19].z = 0.950075f;
00618
00619 normals.points[0].normal[0] = 0.000098f; normals.points[0].normal[1] = 1.000098f; normals.points[0].normal[2] = 0.000008f;
00620 normals.points[1].normal[0] = -0.750891f; normals.points[1].normal[1] = 0.660413f; normals.points[1].normal[2] = 0.000104f;
00621 normals.points[2].normal[0] = -0.991765f; normals.points[2].normal[1] = -0.127949f; normals.points[2].normal[2] = -0.000154f;
00622 normals.points[3].normal[0] = -0.558918f; normals.points[3].normal[1] = -0.829439f; normals.points[3].normal[2] = -0.000039f;
00623 normals.points[4].normal[0] = 0.253627f; normals.points[4].normal[1] = -0.967447f; normals.points[4].normal[2] = -0.000041f;
00624 normals.points[5].normal[0] = 0.894105f; normals.points[5].normal[1] = -0.447965f; normals.points[5].normal[2] = 0.000101f;
00625 normals.points[6].normal[0] = 0.926852f; normals.points[6].normal[1] = 0.375543f; normals.points[6].normal[2] = -0.000161f;
00626 normals.points[7].normal[0] = 0.329948f; normals.points[7].normal[1] = 0.943941f; normals.points[7].normal[2] = 0.000001f;
00627 normals.points[8].normal[0] = -0.490966f; normals.points[8].normal[1] = 0.871203f; normals.points[8].normal[2] = 0.000072f;
00628 normals.points[9].normal[0] = -0.978507f; normals.points[9].normal[1] = 0.206425f; normals.points[9].normal[2] = -0.000017f;
00629 normals.points[10].normal[0] = -0.801227f; normals.points[10].normal[1] = -0.598534f; normals.points[10].normal[2] = 0.000126f;
00630 normals.points[11].normal[0] = -0.079447f; normals.points[11].normal[1] = -0.996697f; normals.points[11].normal[2] = 0.000079f;
00631 normals.points[12].normal[0] = 0.696154f; normals.points[12].normal[1] = -0.717889f; normals.points[12].normal[2] = -0.000017f;
00632 normals.points[13].normal[0] = 0.998685f; normals.points[13].normal[1] = 0.048502f; normals.points[13].normal[2] = -0.000118f;
00633 normals.points[14].normal[0] = 0.622933f; normals.points[14].normal[1] = 0.782133f; normals.points[14].normal[2] = -0.000146f;
00634 normals.points[15].normal[0] = -0.175948f; normals.points[15].normal[1] = 0.984480f; normals.points[15].normal[2] = -0.000044f;
00635 normals.points[16].normal[0] = -0.855476f; normals.points[16].normal[1] = 0.517824f; normals.points[16].normal[2] = 0.000008f;
00636 normals.points[17].normal[0] = -0.953769f; normals.points[17].normal[1] = -0.300571f; normals.points[17].normal[2] = -0.000030f;
00637 normals.points[18].normal[0] = -0.404035f; normals.points[18].normal[1] = -0.914700f; normals.points[18].normal[2] = -0.000046f;
00638 normals.points[19].normal[0] = 0.420154f; normals.points[19].normal[1] = -0.907445f; normals.points[19].normal[2] = 0.000075f;
00639
00640
00641 SampleConsensusModelCylinderPtr model (new SampleConsensusModelCylinder<PointXYZ, Normal> (cloud.makeShared ()));
00642 model->setInputNormals (normals.makeShared ());
00643
00644
00645 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00646
00647
00648 bool result = sac.computeModel ();
00649 ASSERT_EQ (result, true);
00650
00651 std::vector<int> sample;
00652 sac.getModel (sample);
00653 EXPECT_EQ (int (sample.size ()), 2);
00654
00655 std::vector<int> inliers;
00656 sac.getInliers (inliers);
00657 EXPECT_EQ (int (inliers.size ()), 20);
00658
00659 Eigen::VectorXf coeff;
00660 sac.getModelCoefficients (coeff);
00661 EXPECT_EQ (int (coeff.size ()), 7);
00662 EXPECT_NEAR (coeff[0], -0.5, 1e-3);
00663 EXPECT_NEAR (coeff[1], 1.7, 1e-3);
00664 EXPECT_NEAR (coeff[6], 0.5, 1e-3);
00665
00666 Eigen::VectorXf coeff_refined;
00667 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00668 EXPECT_EQ (int (coeff_refined.size ()), 7);
00669 EXPECT_NEAR (coeff_refined[6], 0.5, 1e-3);
00670 }
00671
00673 TEST (RANSAC, SampleConsensusModelCircle2D)
00674 {
00675 srand (0);
00676
00677
00678 PointCloud<PointXYZ> cloud;
00679 cloud.points.resize (18);
00680
00681 cloud.points[0].x = 3.587751f; cloud.points[0].y = -4.190982f; cloud.points[0].z = 0.0f;
00682 cloud.points[1].x = 3.808883f; cloud.points[1].y = -4.412265f; cloud.points[1].z = 0.0f;
00683 cloud.points[2].x = 3.587525f; cloud.points[2].y = -5.809143f; cloud.points[2].z = 0.0f;
00684 cloud.points[3].x = 2.999913f; cloud.points[3].y = -5.999980f; cloud.points[3].z = 0.0f;
00685 cloud.points[4].x = 2.412224f; cloud.points[4].y = -5.809090f; cloud.points[4].z = 0.0f;
00686 cloud.points[5].x = 2.191080f; cloud.points[5].y = -5.587682f; cloud.points[5].z = 0.0f;
00687 cloud.points[6].x = 2.048941f; cloud.points[6].y = -5.309003f; cloud.points[6].z = 0.0f;
00688 cloud.points[7].x = 2.000397f; cloud.points[7].y = -4.999944f; cloud.points[7].z = 0.0f;
00689 cloud.points[8].x = 2.999953f; cloud.points[8].y = -6.000056f; cloud.points[8].z = 0.0f;
00690 cloud.points[9].x = 2.691127f; cloud.points[9].y = -5.951136f; cloud.points[9].z = 0.0f;
00691 cloud.points[10].x = 2.190892f; cloud.points[10].y = -5.587838f; cloud.points[10].z = 0.0f;
00692 cloud.points[11].x = 2.048874f; cloud.points[11].y = -5.309052f; cloud.points[11].z = 0.0f;
00693 cloud.points[12].x = 1.999990f; cloud.points[12].y = -5.000147f; cloud.points[12].z = 0.0f;
00694 cloud.points[13].x = 2.049026f; cloud.points[13].y = -4.690918f; cloud.points[13].z = 0.0f;
00695 cloud.points[14].x = 2.190956f; cloud.points[14].y = -4.412162f; cloud.points[14].z = 0.0f;
00696 cloud.points[15].x = 2.412231f; cloud.points[15].y = -4.190918f; cloud.points[15].z = 0.0f;
00697 cloud.points[16].x = 2.691027f; cloud.points[16].y = -4.049060f; cloud.points[16].z = 0.0f;
00698 cloud.points[17].x = 2.0f; cloud.points[17].y = -3.0f; cloud.points[17].z = 0.0f;
00699
00700
00701 SampleConsensusModelCircle2DPtr model (new SampleConsensusModelCircle2D<PointXYZ> (cloud.makeShared ()));
00702
00703
00704 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00705
00706
00707 bool result = sac.computeModel ();
00708 ASSERT_EQ (result, true);
00709
00710 std::vector<int> sample;
00711 sac.getModel (sample);
00712 EXPECT_EQ (int (sample.size ()), 3);
00713
00714 std::vector<int> inliers;
00715 sac.getInliers (inliers);
00716 EXPECT_EQ (int (inliers.size ()), 17);
00717
00718 Eigen::VectorXf coeff;
00719 sac.getModelCoefficients (coeff);
00720 EXPECT_EQ (int (coeff.size ()), 3);
00721 EXPECT_NEAR (coeff[0], 3, 1e-3);
00722 EXPECT_NEAR (coeff[1], -5, 1e-3);
00723 EXPECT_NEAR (coeff[2], 1, 1e-3);
00724
00725 Eigen::VectorXf coeff_refined;
00726 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00727 EXPECT_EQ (int (coeff_refined.size ()), 3);
00728 EXPECT_NEAR (coeff_refined[0], 3, 1e-3);
00729 EXPECT_NEAR (coeff_refined[1], -5, 1e-3);
00730 EXPECT_NEAR (coeff_refined[2], 1, 1e-3);
00731 }
00732
00734 TEST (RANSAC, SampleConsensusModelCircle3D)
00735 {
00736 srand (0);
00737
00738
00739 PointCloud<PointXYZ> cloud;
00740 cloud.points.resize (20);
00741
00742 cloud.points[0].x = 1.0f; cloud.points[0].y = 5.0f; cloud.points[0].z = -2.9000001f;
00743 cloud.points[1].x = 1.034202f; cloud.points[1].y = 5.0f; cloud.points[1].z = -2.9060307f;
00744 cloud.points[2].x = 1.0642787f; cloud.points[2].y = 5.0f; cloud.points[2].z = -2.9233956f;
00745 cloud.points[3].x = 1.0866026f; cloud.points[3].y = 5.0f; cloud.points[3].z = -2.95f;
00746 cloud.points[4].x = 1.0984808f; cloud.points[4].y = 5.0f; cloud.points[4].z = -2.9826353f;
00747 cloud.points[5].x = 1.0984808f; cloud.points[5].y = 5.0f; cloud.points[5].z = -3.0173647f;
00748 cloud.points[6].x = 1.0866026f; cloud.points[6].y = 5.0f; cloud.points[6].z = -3.05f;
00749 cloud.points[7].x = 1.0642787f; cloud.points[7].y = 5.0f; cloud.points[7].z = -3.0766044f;
00750 cloud.points[8].x = 1.034202f; cloud.points[8].y = 5.0f; cloud.points[8].z = -3.0939693f;
00751 cloud.points[9].x = 1.0f; cloud.points[9].y = 5.0f; cloud.points[9].z = -3.0999999f;
00752 cloud.points[10].x = 0.96579796f; cloud.points[10].y = 5.0f; cloud.points[10].z = -3.0939693f;
00753 cloud.points[11].x = 0.93572122f; cloud.points[11].y = 5.0f; cloud.points[11].z = -3.0766044f;
00754 cloud.points[12].x = 0.91339743f; cloud.points[12].y = 5.0f; cloud.points[12].z = -3.05f;
00755 cloud.points[13].x = 0.90151924f; cloud.points[13].y = 5.0f; cloud.points[13].z = -3.0173647f;
00756 cloud.points[14].x = 0.90151924f; cloud.points[14].y = 5.0f; cloud.points[14].z = -2.9826353f;
00757 cloud.points[15].x = 0.91339743f; cloud.points[15].y = 5.0f; cloud.points[15].z = -2.95f;
00758 cloud.points[16].x = 0.93572122f; cloud.points[16].y = 5.0f; cloud.points[16].z = -2.9233956f;
00759 cloud.points[17].x = 0.96579796f; cloud.points[17].y = 5.0; cloud.points[17].z = -2.9060307f;
00760 cloud.points[18].x = 0.85000002f; cloud.points[18].y = 4.8499999f; cloud.points[18].z = -3.1500001f;
00761 cloud.points[19].x = 1.15f; cloud.points[19].y = 5.1500001f; cloud.points[19].z = -2.8499999f;
00762
00763
00764 SampleConsensusModelCircle3DPtr model (new SampleConsensusModelCircle3D<PointXYZ> (cloud.makeShared ()));
00765
00766
00767 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00768
00769
00770 bool result = sac.computeModel ();
00771 ASSERT_EQ (result, true);
00772
00773 std::vector<int> sample;
00774 sac.getModel (sample);
00775 EXPECT_EQ (int (sample.size ()), 3);
00776
00777 std::vector<int> inliers;
00778 sac.getInliers (inliers);
00779 EXPECT_EQ (int (inliers.size ()), 18);
00780
00781 Eigen::VectorXf coeff;
00782 sac.getModelCoefficients (coeff);
00783 EXPECT_EQ (int (coeff.size ()), 7);
00784 EXPECT_NEAR (coeff[0], 1, 1e-3);
00785 EXPECT_NEAR (coeff[1], 5, 1e-3);
00786 EXPECT_NEAR (coeff[2], -3, 1e-3);
00787 EXPECT_NEAR (coeff[3],0.1, 1e-3);
00788 EXPECT_NEAR (coeff[4], 0, 1e-3);
00789 EXPECT_NEAR (coeff[5], -1, 1e-3);
00790 EXPECT_NEAR (coeff[6], 0, 1e-3);
00791
00792 Eigen::VectorXf coeff_refined;
00793 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00794 EXPECT_EQ (int (coeff_refined.size ()), 7);
00795 EXPECT_NEAR (coeff_refined[0], 1, 1e-3);
00796 EXPECT_NEAR (coeff_refined[1], 5, 1e-3);
00797 EXPECT_NEAR (coeff_refined[2], -3, 1e-3);
00798 EXPECT_NEAR (coeff_refined[3],0.1, 1e-3);
00799 EXPECT_NEAR (coeff_refined[4], 0, 1e-3);
00800 EXPECT_NEAR (coeff_refined[5], -1, 1e-3);
00801 EXPECT_NEAR (coeff_refined[6], 0, 1e-3);
00802 }
00803
00805 TEST (RANSAC, SampleConsensusModelLine)
00806 {
00807 srand (0);
00808
00809
00810 PointCloud<PointXYZ> cloud;
00811 cloud.points.resize (10);
00812
00813 cloud.points[0].x = 1.0f; cloud.points[0].y = 2.0f; cloud.points[0].z = 3.0f;
00814 cloud.points[1].x = 4.0f; cloud.points[1].y = 5.0f; cloud.points[1].z = 6.0f;
00815 cloud.points[2].x = 7.0f; cloud.points[2].y = 8.0f; cloud.points[2].z = 9.0f;
00816 cloud.points[3].x = 10.0f; cloud.points[3].y = 11.0f; cloud.points[3].z = 12.0f;
00817 cloud.points[4].x = 13.0f; cloud.points[4].y = 14.0f; cloud.points[4].z = 15.0f;
00818 cloud.points[5].x = 16.0f; cloud.points[5].y = 17.0f; cloud.points[5].z = 18.0f;
00819 cloud.points[6].x = 19.0f; cloud.points[6].y = 20.0f; cloud.points[6].z = 21.0f;
00820 cloud.points[7].x = 22.0f; cloud.points[7].y = 23.0f; cloud.points[7].z = 24.0f;
00821 cloud.points[8].x = -5.0f; cloud.points[8].y = 1.57f; cloud.points[8].z = 0.75f;
00822 cloud.points[9].x = 4.0f; cloud.points[9].y = 2.0f; cloud.points[9].z = 3.0f;
00823
00824
00825 SampleConsensusModelLinePtr model (new SampleConsensusModelLine<PointXYZ> (cloud.makeShared ()));
00826
00827
00828 RandomSampleConsensus<PointXYZ> sac (model, 0.001);
00829
00830
00831 bool result = sac.computeModel ();
00832 ASSERT_EQ (result, true);
00833
00834 std::vector<int> sample;
00835 sac.getModel (sample);
00836 EXPECT_EQ (int (sample.size ()), 2);
00837
00838 std::vector<int> inliers;
00839 sac.getInliers (inliers);
00840 EXPECT_EQ (int (inliers.size ()), 8);
00841
00842 Eigen::VectorXf coeff;
00843 sac.getModelCoefficients (coeff);
00844 EXPECT_EQ (int (coeff.size ()), 6);
00845 EXPECT_NEAR (coeff[4]/coeff[3], 1, 1e-4);
00846 EXPECT_NEAR (coeff[5]/coeff[3], 1, 1e-4);
00847
00848 Eigen::VectorXf coeff_refined;
00849 model->optimizeModelCoefficients (inliers, coeff, coeff_refined);
00850 EXPECT_EQ (int (coeff_refined.size ()), 6);
00851 EXPECT_NEAR (coeff[4]/coeff[3], 1, 1e-4);
00852 EXPECT_NEAR (coeff[5]/coeff[3], 1, 1e-4);
00853
00854
00855 PointCloud<PointXYZ> proj_points;
00856 model->projectPoints (inliers, coeff_refined, proj_points);
00857
00858 EXPECT_NEAR (proj_points.points[2].x, 7.0, 1e-4);
00859 EXPECT_NEAR (proj_points.points[2].y, 8.0, 1e-4);
00860 EXPECT_NEAR (proj_points.points[2].z, 9.0, 1e-4);
00861
00862 EXPECT_NEAR (proj_points.points[3].x, 10.0, 1e-4);
00863 EXPECT_NEAR (proj_points.points[3].y, 11.0, 1e-4);
00864 EXPECT_NEAR (proj_points.points[3].z, 12.0, 1e-4);
00865
00866 EXPECT_NEAR (proj_points.points[5].x, 16.0, 1e-4);
00867 EXPECT_NEAR (proj_points.points[5].y, 17.0, 1e-4);
00868 EXPECT_NEAR (proj_points.points[5].z, 18.0, 1e-4);
00869 }
00870
00872 TEST (RANSAC, SampleConsensusModelNormalPlane)
00873 {
00874 srand (0);
00875
00876 SampleConsensusModelNormalPlanePtr model (new SampleConsensusModelNormalPlane<PointXYZ, Normal> (cloud_));
00877 model->setInputNormals (normals_);
00878 model->setNormalDistanceWeight (0.01);
00879
00880 RandomSampleConsensus<PointXYZ> sac (model, 0.03);
00881
00882 verifyPlaneSac (model, sac);
00883 }
00884
00886
00887 TEST (SAC, InfiniteLoop)
00888 {
00889 const unsigned point_count = 100;
00890 PointCloud<PointXYZ> cloud;
00891 cloud.points.resize (point_count);
00892 for (unsigned pIdx = 0; pIdx < point_count; ++pIdx)
00893 {
00894 cloud.points[pIdx].x = static_cast<float> (pIdx);
00895 cloud.points[pIdx].y = 0.0;
00896 cloud.points[pIdx].z = 0.0;
00897 }
00898
00899 boost::posix_time::time_duration delay(0,0,1,0);
00900 boost::function<bool ()> sac_function;
00901 SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere<PointXYZ> (cloud.makeShared ()));
00902
00903
00904 RandomSampleConsensus<PointXYZ> ransac (model, 0.03);
00905 sac_function = boost::bind (&RandomSampleConsensus<PointXYZ>::computeModel, &ransac, 0);
00906 boost::thread thread1 (sac_function);
00907 ASSERT_TRUE(thread1.timed_join(delay));
00908
00909
00910 LeastMedianSquares<PointXYZ> lmsac (model, 0.03);
00911 sac_function = boost::bind (&LeastMedianSquares<PointXYZ>::computeModel, &lmsac, 0);
00912 boost::thread thread2 (sac_function);
00913 ASSERT_TRUE(thread2.timed_join(delay));
00914
00915
00916 MEstimatorSampleConsensus<PointXYZ> mesac (model, 0.03);
00917 sac_function = boost::bind (&MEstimatorSampleConsensus<PointXYZ>::computeModel, &mesac, 0);
00918 boost::thread thread3 (sac_function);
00919 ASSERT_TRUE(thread3.timed_join(delay));
00920
00921
00922 RandomizedRandomSampleConsensus<PointXYZ> rrsac (model, 0.03);
00923 sac_function = boost::bind (&RandomizedRandomSampleConsensus<PointXYZ>::computeModel, &rrsac, 0);
00924 boost::thread thread4 (sac_function);
00925 ASSERT_TRUE(thread4.timed_join(delay));
00926
00927
00928 RandomizedMEstimatorSampleConsensus<PointXYZ> rmsac (model, 0.03);
00929 sac_function = boost::bind (&RandomizedMEstimatorSampleConsensus<PointXYZ>::computeModel, &rmsac, 0);
00930 boost::thread thread5 (sac_function);
00931 ASSERT_TRUE(thread5.timed_join(delay));
00932
00933
00934 MaximumLikelihoodSampleConsensus<PointXYZ> mlesac (model, 0.03);
00935 sac_function = boost::bind (&MaximumLikelihoodSampleConsensus<PointXYZ>::computeModel, &mlesac, 0);
00936 boost::thread thread6 (sac_function);
00937 ASSERT_TRUE(thread6.timed_join(delay));
00938 }
00939
00940
00941 int
00942 main (int argc, char** argv)
00943 {
00944 if (argc < 2)
00945 {
00946 std::cerr << "No test file given. Please download `sac_plane_test.pcd` and pass its path to the test." << std::endl;
00947 return (-1);
00948 }
00949
00950
00951 pcl::PCLPointCloud2 cloud_blob;
00952 if (loadPCDFile (argv[1], cloud_blob) < 0)
00953 {
00954 std::cerr << "Failed to read test file. Please download `sac_plane_test.pcd` and pass its path to the test." << std::endl;
00955 return (-1);
00956 }
00957 fromPCLPointCloud2 (cloud_blob, *cloud_);
00958
00959 indices_.resize (cloud_->points.size ());
00960 for (size_t i = 0; i < indices_.size (); ++i) { indices_[i] = int (i); }
00961
00962
00963 NormalEstimation<PointXYZ, Normal> n;
00964 search::Search<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ>);
00965 tree->setInputCloud (cloud_);
00966 n.setInputCloud (cloud_);
00967 boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices_));
00968 n.setIndices (indicesptr);
00969 n.setSearchMethod (tree);
00970 n.setRadiusSearch (0.02);
00971 n.compute (*normals_);
00972
00973 testing::InitGoogleTest (&argc, argv);
00974 return (RUN_ALL_TESTS ());
00975 }
00976