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 #include <unsupported/Eigen/NonLinearOptimization>
00043
00045 template <typename PointT> bool
00046 pcl::SampleConsensusModelSphere<PointT>::isSampleGood (const std::vector<int> &) const
00047 {
00048 return (true);
00049 }
00050
00052 template <typename PointT> bool
00053 pcl::SampleConsensusModelSphere<PointT>::computeModelCoefficients (
00054 const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00055 {
00056
00057 if (samples.size () != 4)
00058 {
00059 PCL_ERROR ("[pcl::SampleConsensusModelSphere::computeModelCoefficients] Invalid set of samples given (%zu)!\n", samples.size ());
00060 return (false);
00061 }
00062
00063 Eigen::Matrix4f temp;
00064 for (int i = 0; i < 4; i++)
00065 {
00066 temp (i, 0) = input_->points[samples[i]].x;
00067 temp (i, 1) = input_->points[samples[i]].y;
00068 temp (i, 2) = input_->points[samples[i]].z;
00069 temp (i, 3) = 1;
00070 }
00071 float m11 = temp.determinant ();
00072 if (m11 == 0)
00073 return (false);
00074
00075 for (int i = 0; i < 4; ++i)
00076 temp (i, 0) = (input_->points[samples[i]].x) * (input_->points[samples[i]].x) +
00077 (input_->points[samples[i]].y) * (input_->points[samples[i]].y) +
00078 (input_->points[samples[i]].z) * (input_->points[samples[i]].z);
00079 float m12 = temp.determinant ();
00080
00081 for (int i = 0; i < 4; ++i)
00082 {
00083 temp (i, 1) = temp (i, 0);
00084 temp (i, 0) = input_->points[samples[i]].x;
00085 }
00086 float m13 = temp.determinant ();
00087
00088 for (int i = 0; i < 4; ++i)
00089 {
00090 temp (i, 2) = temp (i, 1);
00091 temp (i, 1) = input_->points[samples[i]].y;
00092 }
00093 float m14 = temp.determinant ();
00094
00095 for (int i = 0; i < 4; ++i)
00096 {
00097 temp (i, 0) = temp (i, 2);
00098 temp (i, 1) = input_->points[samples[i]].x;
00099 temp (i, 2) = input_->points[samples[i]].y;
00100 temp (i, 3) = input_->points[samples[i]].z;
00101 }
00102 float m15 = temp.determinant ();
00103
00104
00105 model_coefficients.resize (4);
00106 model_coefficients[0] = 0.5f * m12 / m11;
00107 model_coefficients[1] = 0.5f * m13 / m11;
00108 model_coefficients[2] = 0.5f * m14 / m11;
00109
00110 model_coefficients[3] = sqrtf (
00111 model_coefficients[0] * model_coefficients[0] +
00112 model_coefficients[1] * model_coefficients[1] +
00113 model_coefficients[2] * model_coefficients[2] - m15 / m11);
00114
00115 return (true);
00116 }
00117
00119 template <typename PointT> void
00120 pcl::SampleConsensusModelSphere<PointT>::getDistancesToModel (
00121 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00122 {
00123
00124 if (!isModelValid (model_coefficients))
00125 {
00126 distances.clear ();
00127 return;
00128 }
00129 distances.resize (indices_->size ());
00130
00131
00132 for (size_t i = 0; i < indices_->size (); ++i)
00133
00134
00135 distances[i] = fabs (sqrtf (
00136 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00137 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00138
00139 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00140 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) +
00141
00142 ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) *
00143 ( input_->points[(*indices_)[i]].z - model_coefficients[2] )
00144 ) - model_coefficients[3]);
00145 }
00146
00148 template <typename PointT> void
00149 pcl::SampleConsensusModelSphere<PointT>::selectWithinDistance (
00150 const Eigen::VectorXf &model_coefficients, const double threshold, std::vector<int> &inliers)
00151 {
00152
00153 if (!isModelValid (model_coefficients))
00154 {
00155 inliers.clear ();
00156 return;
00157 }
00158
00159 int nr_p = 0;
00160 inliers.resize (indices_->size ());
00161
00162
00163 for (size_t i = 0; i < indices_->size (); ++i)
00164 {
00165
00166
00167 if (fabs (sqrtf (
00168 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00169 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00170
00171 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00172 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) +
00173
00174 ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) *
00175 ( input_->points[(*indices_)[i]].z - model_coefficients[2] )
00176 ) - model_coefficients[3]) < threshold)
00177 {
00178
00179 inliers[nr_p] = (*indices_)[i];
00180 nr_p++;
00181 }
00182 }
00183 inliers.resize (nr_p);
00184 }
00185
00187 template <typename PointT> int
00188 pcl::SampleConsensusModelSphere<PointT>::countWithinDistance (
00189 const Eigen::VectorXf &model_coefficients, const double threshold)
00190 {
00191
00192 if (!isModelValid (model_coefficients))
00193 return (0);
00194
00195 int nr_p = 0;
00196
00197
00198 for (size_t i = 0; i < indices_->size (); ++i)
00199 {
00200
00201
00202 if (fabs (sqrtf (
00203 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) *
00204 ( input_->points[(*indices_)[i]].x - model_coefficients[0] ) +
00205
00206 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) *
00207 ( input_->points[(*indices_)[i]].y - model_coefficients[1] ) +
00208
00209 ( input_->points[(*indices_)[i]].z - model_coefficients[2] ) *
00210 ( input_->points[(*indices_)[i]].z - model_coefficients[2] )
00211 ) - model_coefficients[3]) < threshold)
00212 nr_p++;
00213 }
00214 return (nr_p);
00215 }
00216
00218 template <typename PointT> void
00219 pcl::SampleConsensusModelSphere<PointT>::optimizeModelCoefficients (
00220 const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00221 {
00222 optimized_coefficients = model_coefficients;
00223
00224
00225 if (model_coefficients.size () != 4)
00226 {
00227 PCL_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00228 return;
00229 }
00230
00231
00232 if (inliers.size () <= 4)
00233 {
00234 PCL_ERROR ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Not enough inliers found to support a model (%zu)! Returning the same coefficients.\n", inliers.size ());
00235 return;
00236 }
00237
00238 tmp_inliers_ = &inliers;
00239
00240 OptimizationFunctor functor (static_cast<int> (inliers.size ()), this);
00241 Eigen::NumericalDiff<OptimizationFunctor> num_diff (functor);
00242 Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, float> lm (num_diff);
00243 int info = lm.minimize (optimized_coefficients);
00244
00245
00246 PCL_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\n",
00247 info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]);
00248 }
00249
00251 template <typename PointT> void
00252 pcl::SampleConsensusModelSphere<PointT>::projectPoints (
00253 const std::vector<int> &, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool)
00254 {
00255
00256 if (model_coefficients.size () != 4)
00257 {
00258 PCL_ERROR ("[pcl::SampleConsensusModelSphere::projectPoints] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00259 return;
00260 }
00261
00262
00263 projected_points.points.resize (input_->points.size ());
00264 projected_points.header = input_->header;
00265 projected_points.width = input_->width;
00266 projected_points.height = input_->height;
00267 projected_points.is_dense = input_->is_dense;
00268
00269 PCL_WARN ("[pcl::SampleConsensusModelSphere::projectPoints] Not implemented yet.\n");
00270 projected_points.points = input_->points;
00271 }
00272
00274 template <typename PointT> bool
00275 pcl::SampleConsensusModelSphere<PointT>::doSamplesVerifyModel (
00276 const std::set<int> &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
00277 {
00278
00279 if (model_coefficients.size () != 4)
00280 {
00281 PCL_ERROR ("[pcl::SampleConsensusModelSphere::doSamplesVerifyModel] Invalid number of model coefficients given (%zu)!\n", model_coefficients.size ());
00282 return (false);
00283 }
00284
00285 for (std::set<int>::const_iterator it = indices.begin (); it != indices.end (); ++it)
00286
00287
00288 if (fabs (sqrt (
00289 ( input_->points[*it].x - model_coefficients[0] ) *
00290 ( input_->points[*it].x - model_coefficients[0] ) +
00291 ( input_->points[*it].y - model_coefficients[1] ) *
00292 ( input_->points[*it].y - model_coefficients[1] ) +
00293 ( input_->points[*it].z - model_coefficients[2] ) *
00294 ( input_->points[*it].z - model_coefficients[2] )
00295 ) - model_coefficients[3]) > threshold)
00296 return (false);
00297
00298 return (true);
00299 }
00300
00301 #define PCL_INSTANTIATE_SampleConsensusModelSphere(T) template class PCL_EXPORTS pcl::SampleConsensusModelSphere<T>;
00302
00303 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_
00304