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_REGISTRATION_H_
00039 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
00040
00041 #include "pcl/sample_consensus/sac_model_registration.h"
00042
00043
00044
00045
00047 template <typename PointT> void
00048 pcl::SampleConsensusModelRegistration<PointT>::getSamples (int &iterations, std::vector<int> &samples)
00049 {
00050
00051 if (indices_->size () < 3)
00052 return;
00053
00054 samples.resize (3);
00055 double trand = indices_->size () / (RAND_MAX + 1.0);
00056
00057
00058 if (samples.size () > indices_->size ())
00059 {
00060 ROS_ERROR ("[pcl::SampleConsensusModelRegistration::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] = idx;
00071
00072
00073 Eigen::Array4f p1p0, p2p0, p2p1;
00074 int iter = 0;
00075 do
00076 {
00077 int iter2 = 0;
00078 do
00079 {
00080 idx = (int)(rand () * trand);
00081 samples[1] = idx;
00082 ++iter2;
00083 if (iter2 > MAX_ITERATIONS_COLLINEAR)
00084 break;
00085 }
00086 while (samples[1] == samples[0]);
00087
00088
00089 pcl::Array4fMapConst p0 = input_->points[(*indices_)[samples[0]]].getArray4fMap ();
00090 pcl::Array4fMapConst p1 = input_->points[(*indices_)[samples[1]]].getArray4fMap ();
00091
00092
00093 p1p0 = p1 - p0;
00094 ++iter;
00095 if (iter > MAX_ITERATIONS_COLLINEAR)
00096 {
00097 ROS_DEBUG ("[pcl::SampleConsensusModelRegistration::getSamples] WARNING1: Could not select 3 non collinear points in %d iterations!", MAX_ITERATIONS_COLLINEAR);
00098 break;
00099 }
00100 }
00101 while (p1p0.matrix ().squaredNorm () <= sample_dist_thresh_);
00102
00103 int iter1 = 0;
00104 do
00105 {
00106 Eigen::Array4f dy1dy2;
00107 int iter2 = 0;
00108 do
00109 {
00110
00111 int iter3 = 0;
00112 do
00113 {
00114 idx = (int)(rand () * trand);
00115 samples[2] = idx;
00116 ++iter3;
00117 if (iter3 > MAX_ITERATIONS_COLLINEAR)
00118 break;
00119 } while ( (samples[2] == samples[1]) || (samples[2] == samples[0]) );
00120
00121 pcl::Array4fMapConst p0 = input_->points[(*indices_)[samples[0]]].getArray4fMap ();
00122 pcl::Array4fMapConst p1 = input_->points[(*indices_)[samples[1]]].getArray4fMap ();
00123 pcl::Array4fMapConst p2 = input_->points[(*indices_)[samples[2]]].getArray4fMap ();
00124
00125
00126 p2p0 = p2 - p0;
00127 p2p1 = p2 - p1;
00128
00129 dy1dy2 = p1p0 / p2p0;
00130 ++iter2;
00131 if (iter2 > MAX_ITERATIONS_COLLINEAR)
00132 {
00133 ROS_DEBUG ("[pcl::SampleConsensusModelRegistration::getSamples] WARNING2: Could not select 3 non collinear points in %d iterations!", MAX_ITERATIONS_COLLINEAR);
00134 break;
00135 }
00136 }
00137 while ( (dy1dy2[0] == dy1dy2[1]) && (dy1dy2[2] == dy1dy2[1]) );
00138
00139 ++iter1;
00140 if (iter1 > MAX_ITERATIONS_COLLINEAR)
00141 {
00142 ROS_DEBUG ("[pcl::SampleConsensusModelRegistration::getSamples] WARNING2: Could not select 3 non collinear points in %d iterations!", MAX_ITERATIONS_COLLINEAR);
00143 break;
00144 }
00145 }
00146 while (p2p0.matrix ().squaredNorm () < sample_dist_thresh_ || p2p1.matrix ().squaredNorm () < sample_dist_thresh_);
00147 }
00148
00150 template <typename PointT> bool
00151 pcl::SampleConsensusModelRegistration<PointT>::computeModelCoefficients (const std::vector<int> &samples, Eigen::VectorXf &model_coefficients)
00152 {
00153
00154 if (samples.size () != 3)
00155 return (false);
00156
00157 std::vector<int> indices_src (3);
00158 std::vector<int> indices_tgt (3);
00159 for (int i = 0; i < 3; ++i)
00160 {
00161 indices_src[i] = (*indices_)[samples[i]];
00162 indices_tgt[i] = (*indices_tgt_)[samples[i]];
00163 }
00164
00165 Eigen::Matrix4f transform;
00166 estimateRigidTransformationSVD<PointT, PointT> (*input_, indices_src, *target_, indices_tgt, transform);
00167 model_coefficients.resize (16);
00168 model_coefficients.segment<4>(0) = transform.row (0);
00169 model_coefficients.segment<4>(4) = transform.row (1);
00170 model_coefficients.segment<4>(8) = transform.row (2);
00171 model_coefficients.segment<4>(12) = transform.row (3);
00172
00173 return (true);
00174 }
00175
00177 template <typename PointT> void
00178 pcl::SampleConsensusModelRegistration<PointT>::getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
00179 {
00180 if (indices_->size () != indices_tgt_->size ())
00181 {
00182 ROS_ERROR ("[pcl::SampleConsensusModelRegistration::getDistancesToModel] Number of source indices (%zu) differs than number of target indices (%zu)!", indices_->size (), indices_tgt_->size ());
00183 distances.clear ();
00184 return;
00185 }
00186
00187 if (!isModelValid (model_coefficients))
00188 {
00189 distances.clear ();
00190 return;
00191 }
00192 distances.resize (indices_->size ());
00193
00194
00195 Eigen::Matrix4f transform;
00196 transform.row (0) = model_coefficients.segment<4>(0);
00197 transform.row (1) = model_coefficients.segment<4>(4);
00198 transform.row (2) = model_coefficients.segment<4>(8);
00199 transform.row (3) = model_coefficients.segment<4>(12);
00200
00201 for (size_t i = 0; i < indices_->size (); ++i)
00202 {
00203 Vector4fMapConst pt_src = input_->points[(*indices_)[i]].getVector4fMap ();
00204 Vector4fMapConst pt_tgt = target_->points[(*indices_tgt_)[i]].getVector4fMap ();
00205 Eigen::Vector4f p_tr = transform * pt_src;
00206
00207
00208 distances[i] = (p_tr - pt_tgt).norm ();
00209 }
00210 }
00211
00213 template <typename PointT> void
00214 pcl::SampleConsensusModelRegistration<PointT>::selectWithinDistance (const Eigen::VectorXf &model_coefficients, double threshold, std::vector<int> &inliers)
00215 {
00216 if (indices_->size () != indices_tgt_->size ())
00217 {
00218 ROS_ERROR ("[pcl::SampleConsensusModelRegistration::selectWithinDistance] Number of source indices (%zu) differs than number of target indices (%zu)!", indices_->size (), indices_tgt_->size ());
00219 inliers.clear ();
00220 return;
00221 }
00222
00223 double thresh = threshold * threshold;
00224
00225
00226 if (!isModelValid (model_coefficients))
00227 {
00228 inliers.clear ();
00229 return;
00230 }
00231
00232 inliers.resize (indices_->size ());
00233
00234 Eigen::Matrix4f transform;
00235 transform.row (0) = model_coefficients.segment<4>(0);
00236 transform.row (1) = model_coefficients.segment<4>(4);
00237 transform.row (2) = model_coefficients.segment<4>(8);
00238 transform.row (3) = model_coefficients.segment<4>(12);
00239
00240 int nr_p = 0;
00241 for (size_t i = 0; i < indices_->size (); ++i)
00242 {
00243 Vector4fMapConst pt_src = input_->points[(*indices_)[i]].getVector4fMap ();
00244 Vector4fMapConst pt_tgt = target_->points[(*indices_tgt_)[i]].getVector4fMap ();
00245 Eigen::Vector4f p_tr = transform * pt_src;
00246
00247 if ((p_tr - pt_tgt).squaredNorm () < thresh)
00248 inliers[nr_p++] = i;
00249 }
00250 inliers.resize (nr_p);
00251 }
00252
00254 template <typename PointT> void
00255 pcl::SampleConsensusModelRegistration<PointT>::optimizeModelCoefficients (const std::vector<int> &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
00256 {
00257 if (indices_->size () != indices_tgt_->size ())
00258 {
00259 ROS_ERROR ("[pcl::SampleConsensusModelRegistration::optimizeModelCoefficients] Number of source indices (%zu) differs than number of target indices (%zu)!", indices_->size (), indices_tgt_->size ());
00260 optimized_coefficients = model_coefficients;
00261 return;
00262 }
00263
00264
00265 if (!isModelValid (model_coefficients))
00266 {
00267 optimized_coefficients = model_coefficients;
00268 return;
00269 }
00270
00271 std::vector<int> indices_src (inliers.size ());
00272 std::vector<int> indices_tgt (inliers.size ());
00273 for (size_t i = 0; i < inliers.size (); ++i)
00274 {
00275
00276 indices_src[i] = (*indices_)[inliers[i]];
00277 indices_tgt[i] = (*indices_tgt_)[inliers[i]];
00278 }
00279
00280 Eigen::Matrix4f transform;
00281 estimateRigidTransformationSVD<PointT, PointT> (*input_, indices_src, *target_, indices_tgt, transform);
00282 optimized_coefficients.resize (16);
00283 optimized_coefficients.segment<4>(0) = transform.row (0);
00284 optimized_coefficients.segment<4>(4) = transform.row (1);
00285 optimized_coefficients.segment<4>(8) = transform.row (2);
00286 optimized_coefficients.segment<4>(12) = transform.row (3);
00287 }
00288
00289 #define PCL_INSTANTIATE_SampleConsensusModelRegistration(T) template class pcl::SampleConsensusModelRegistration<T>;
00290
00291 #endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_REGISTRATION_H_
00292