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
00036 #include <door_handle_detector/sample_consensus/sac_model_line.h>
00037 #include <door_handle_detector/geometry/point.h>
00038 #include <door_handle_detector/geometry/nearest.h>
00039
00040 namespace sample_consensus
00041 {
00043
00048 void
00049 SACModelLine::getSamples (int &iterations, std::vector<int> &samples)
00050 {
00051 samples.resize (2);
00052 double trand = indices_.size () / (RAND_MAX + 1.0);
00053
00054
00055 int idx = (int)(rand () * trand);
00056
00057 samples[0] = indices_.at (idx);
00058
00059
00060 int iter = 0;
00061 do
00062 {
00063 idx = (int)(rand () * trand);
00064 samples[1] = indices_.at (idx);
00065 iter++;
00066
00067 if (iter > MAX_ITERATIONS_UNIQUE)
00068 {
00069 ROS_WARN ("[SACModelLine::getSamples] WARNING: Could not select 2 unique points in %d iterations!", MAX_ITERATIONS_UNIQUE);
00070 break;
00071 }
00072 iterations++;
00073 } while (samples[1] == samples[0]);
00074 iterations--;
00075 return;
00076 }
00077
00079
00086 void
00087 SACModelLine::selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers)
00088 {
00089 double sqr_threshold = threshold * threshold;
00090
00091 int nr_p = 0;
00092 inliers.resize (indices_.size ());
00093
00094
00095 geometry_msgs::Point32 p3, p4;
00096 p3.x = model_coefficients.at (3) - model_coefficients.at (0);
00097 p3.y = model_coefficients.at (4) - model_coefficients.at (1);
00098 p3.z = model_coefficients.at (5) - model_coefficients.at (2);
00099
00100
00101 for (unsigned int i = 0; i < indices_.size (); i++)
00102 {
00103
00104
00105
00106
00107
00108
00109
00110 p4.x = model_coefficients.at (3) - cloud_->points.at (indices_.at (i)).x;
00111 p4.y = model_coefficients.at (4) - cloud_->points.at (indices_.at (i)).y;
00112 p4.z = model_coefficients.at (5) - cloud_->points.at (indices_.at (i)).z;
00113
00114
00115
00116
00117 geometry_msgs::Point32 c = cloud_geometry::cross (p4, p3);
00118 double sqr_distance = (c.x * c.x + c.y * c.y + c.z * c.z) / (p3.x * p3.x + p3.y * p3.y + p3.z * p3.z);
00119
00120 if (sqr_distance < sqr_threshold)
00121 {
00122
00123 inliers[nr_p] = indices_[i];
00124 nr_p++;
00125 }
00126 }
00127 inliers.resize (nr_p);
00128 return;
00129 }
00130
00132
00136 void
00137 SACModelLine::getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances)
00138 {
00139 distances.resize (indices_.size ());
00140
00141
00142 geometry_msgs::Point32 p3, p4;
00143 p3.x = model_coefficients.at (3) - model_coefficients.at (0);
00144 p3.y = model_coefficients.at (4) - model_coefficients.at (1);
00145 p3.z = model_coefficients.at (5) - model_coefficients.at (2);
00146
00147
00148 for (unsigned int i = 0; i < indices_.size (); i++)
00149 {
00150
00151
00152 p4.x = model_coefficients.at (3) - cloud_->points.at (indices_.at (i)).x;
00153 p4.y = model_coefficients.at (4) - cloud_->points.at (indices_.at (i)).y;
00154 p4.z = model_coefficients.at (5) - cloud_->points.at (indices_.at (i)).z;
00155
00156 geometry_msgs::Point32 c = cloud_geometry::cross (p4, p3);
00157 distances[i] = sqrt (c.x * c.x + c.y * c.y + c.z * c.z) / (p3.x * p3.x + p3.y * p3.y + p3.z * p3.z);
00158 }
00159 return;
00160 }
00161
00163
00168 void
00169 SACModelLine::projectPoints (const std::vector<int> &inliers, const std::vector<double> &model_coefficients,
00170 sensor_msgs::PointCloud &projected_points)
00171 {
00172
00173 projected_points.points.resize (inliers.size ());
00174 projected_points.set_channels_size (cloud_->get_channels_size ());
00175
00176
00177 for (unsigned int d = 0; d < projected_points.get_channels_size (); d++)
00178 {
00179 projected_points.channels[d].name = cloud_->channels[d].name;
00180 projected_points.channels[d].values.resize (inliers.size ());
00181 }
00182
00183
00184 geometry_msgs::Point32 p21;
00185 p21.x = model_coefficients.at (3) - model_coefficients.at (0);
00186 p21.y = model_coefficients.at (4) - model_coefficients.at (1);
00187 p21.z = model_coefficients.at (5) - model_coefficients.at (2);
00188
00189
00190 for (unsigned int i = 0; i < inliers.size (); i++)
00191 {
00192
00193 double k = ( cloud_->points.at (inliers.at (i)).x * p21.x + cloud_->points.at (inliers.at (i)).y * p21.y + cloud_->points.at (inliers.at (i)).z * p21.z -
00194 (model_coefficients_[0] * p21.x + model_coefficients_[1] * p21.y + model_coefficients_[2] * p21.z)
00195 ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
00196
00197 projected_points.points[i].x = model_coefficients_.at (0) + k * p21.x;
00198 projected_points.points[i].y = model_coefficients_.at (1) + k * p21.y;
00199 projected_points.points[i].z = model_coefficients_.at (2) + k * p21.z;
00200
00201 for (unsigned int d = 0; d < projected_points.get_channels_size (); d++)
00202 projected_points.channels[d].values[i] = cloud_->channels[d].values[inliers.at (i)];
00203 }
00204 }
00205
00207
00211 void
00212 SACModelLine::projectPointsInPlace (const std::vector<int> &inliers, const std::vector<double> &model_coefficients)
00213 {
00214
00215 geometry_msgs::Point32 p21;
00216 p21.x = model_coefficients.at (3) - model_coefficients.at (0);
00217 p21.y = model_coefficients.at (4) - model_coefficients.at (1);
00218 p21.z = model_coefficients.at (5) - model_coefficients.at (2);
00219
00220
00221 for (unsigned int i = 0; i < inliers.size (); i++)
00222 {
00223
00224 double k = ( cloud_->points.at (inliers.at (i)).x * p21.x + cloud_->points.at (inliers.at (i)).y * p21.y + cloud_->points.at (inliers.at (i)).z * p21.z -
00225 (model_coefficients_[0] * p21.x + model_coefficients_[1] * p21.y + model_coefficients_[2] * p21.z)
00226 ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
00227
00228 cloud_->points.at (inliers.at (i)).x = model_coefficients_.at (0) + k * p21.x;
00229 cloud_->points.at (inliers.at (i)).y = model_coefficients_.at (1) + k * p21.y;
00230 cloud_->points.at (inliers.at (i)).z = model_coefficients_.at (2) + k * p21.z;
00231 }
00232 }
00233
00235
00240 bool
00241 SACModelLine::computeModelCoefficients (const std::vector<int> &samples)
00242 {
00243 model_coefficients_.resize (6);
00244 model_coefficients_[0] = cloud_->points.at (samples.at (0)).x;
00245 model_coefficients_[1] = cloud_->points.at (samples.at (0)).y;
00246 model_coefficients_[2] = cloud_->points.at (samples.at (0)).z;
00247 model_coefficients_[3] = cloud_->points.at (samples.at (1)).x;
00248 model_coefficients_[4] = cloud_->points.at (samples.at (1)).y;
00249 model_coefficients_[5] = cloud_->points.at (samples.at (1)).z;
00250
00251 return (true);
00252 }
00253
00255
00260 void
00261 SACModelLine::refitModel (const std::vector<int> &inliers, std::vector<double> &refit_coefficients)
00262 {
00263 if (inliers.size () == 0)
00264 {
00265 ROS_ERROR ("[SACModelLine::RefitModel] Cannot re-fit 0 inliers!");
00266 refit_coefficients = model_coefficients_;
00267 return;
00268 }
00269
00270 refit_coefficients.resize (6);
00271
00272
00273 geometry_msgs::Point32 centroid;
00274
00275 Eigen::Matrix3d covariance_matrix;
00276 cloud_geometry::nearest::computeCovarianceMatrix (*cloud_, inliers, covariance_matrix, centroid);
00277
00278 refit_coefficients[0] = centroid.x;
00279 refit_coefficients[1] = centroid.y;
00280 refit_coefficients[2] = centroid.z;
00281
00282
00283
00284 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
00285 Eigen::Vector3d eigen_values = ei_symm.eigenvalues ();
00286 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors ();
00287
00288 refit_coefficients[3] = eigen_vectors (0, 2) + refit_coefficients[0];
00289 refit_coefficients[4] = eigen_vectors (1, 2) + refit_coefficients[1];
00290 refit_coefficients[5] = eigen_vectors (2, 2) + refit_coefficients[2];
00291 }
00292
00294
00298 bool
00299 SACModelLine::doSamplesVerifyModel (const std::set<int> &indices, double threshold)
00300 {
00301 double sqr_threshold = threshold * threshold;
00302 for (std::set<int>::iterator it = indices.begin (); it != indices.end (); ++it)
00303 {
00304 geometry_msgs::Point32 p3, p4;
00305 p3.x = model_coefficients_.at (3) - model_coefficients_.at (0);
00306 p3.y = model_coefficients_.at (4) - model_coefficients_.at (1);
00307 p3.z = model_coefficients_.at (5) - model_coefficients_.at (2);
00308
00309 p4.x = model_coefficients_.at (3) - cloud_->points.at (*it).x;
00310 p4.y = model_coefficients_.at (4) - cloud_->points.at (*it).y;
00311 p4.z = model_coefficients_.at (5) - cloud_->points.at (*it).z;
00312
00313 geometry_msgs::Point32 c = cloud_geometry::cross (p4, p3);
00314 double sqr_distance = (c.x * c.x + c.y * c.y + c.z * c.z) / (p3.x * p3.x + p3.y * p3.y + p3.z * p3.z);
00315
00316 if (sqr_distance < sqr_threshold)
00317 return (false);
00318 }
00319 return (true);
00320 }
00321 }