sac_model_line.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu>
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  *
27  * $Id: sac_model_line.cpp 21050 2009-08-07 21:24:30Z jfaustwg $
28  *
29  */
30 
36 #include <Eigen/Core>
37 #include <Eigen/QR>
38 #include <Eigen/Eigenvalues>
39 #include <sac_model_line.h>
40 
41 #include <ros/console.h>
42 
43 namespace sample_consensus
44 {
46 
51  void
52  SACModelLine::getSamples (int &iterations, std::vector<int> &samples)
53  {
54  samples.resize (2);
55  double trand = indices_.size () / (RAND_MAX + 1.0);
56 
57  // Get a random number between 1 and max_indices
58  int idx = (int)(rand () * trand);
59  // Get the index
60  samples[0] = indices_.at (idx);
61 
62  // Get a second point which is different than the first
63  int iter = 0;
64  do
65  {
66  idx = (int)(rand () * trand);
67  samples[1] = indices_.at (idx);
68  iter++;
69 
70  if (iter > MAX_ITERATIONS_UNIQUE)
71  {
72  ROS_WARN ("[SACModelLine::getSamples] WARNING: Could not select 2 unique points in %d iterations!", MAX_ITERATIONS_UNIQUE);
73  break;
74  }
75  iterations++;
76  } while (samples[1] == samples[0]);
77  iterations--;
78  return;
79  }
80 
82 
89  void
90  SACModelLine::selectWithinDistance (const std::vector<double> &model_coefficients, double threshold, std::vector<int> &inliers)
91  {
92  double sqr_threshold = threshold * threshold;
93 
94  int nr_p = 0;
95  inliers.resize (indices_.size ());
96 
97  // Obtain the line direction
98  pcl::PointXYZ p3, p4;
99  p3.x = model_coefficients.at (3) - model_coefficients.at (0);
100  p3.y = model_coefficients.at (4) - model_coefficients.at (1);
101  p3.z = model_coefficients.at (5) - model_coefficients.at (2);
102 
103  // Iterate through the 3d points and calculate the distances from them to the plane
104  for (unsigned int i = 0; i < indices_.size (); i++)
105  {
106  // Calculate the distance from the point to the line
107  // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1)
108  // P1, P2 = line points, P0 = query point
109  // P1P2 = <x2-x1, y2-y1, z2-z1> = <x3, y3, z3>
110  // P1P0 = < x-x1, y-y1, z-z1 > = <x4, y4, z4>
111  // P1P2 x P1P0 = < y3*z4 - z3*y4, -(x3*z4 - x4*z3), x3*y4 - x4*y3 >
112  // = < (y2-y1)*(z-z1) - (z2-z1)*(y-y1), -[(x2-x1)*(z-z1) - (x-x1)*(z2-z1)], (x2-x1)*(y-y1) - (x-x1)*(y2-y1) >
113  p4.x = model_coefficients.at (3) - cloud_->points.at (indices_.at (i)).x;
114  p4.y = model_coefficients.at (4) - cloud_->points.at (indices_.at (i)).y;
115  p4.z = model_coefficients.at (5) - cloud_->points.at (indices_.at (i)).z;
116 
117  // P1P2 = sqrt (x3^2 + y3^2 + z3^2)
118  // a = sqrt [(y3*z4 - z3*y4)^2 + (x3*z4 - x4*z3)^2 + (x3*y4 - x4*y3)^2]
119  //double distance = SQR_NORM (cANN::cross (p4, p3)) / SQR_NORM (p3);
120  pcl::PointXYZ c = cross (p4, p3);
121  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);
122 
123  if (sqr_distance < sqr_threshold)
124  {
125  // Returns the indices of the points whose squared distances are smaller than the threshold
126  inliers[nr_p] = indices_[i];
127  nr_p++;
128  }
129  }
130  inliers.resize (nr_p);
131  return;
132  }
133 
135 
139  void
140  SACModelLine::getDistancesToModel (const std::vector<double> &model_coefficients, std::vector<double> &distances)
141  {
142  distances.resize (indices_.size ());
143 
144  // Obtain the line direction
145  pcl::PointXYZ p3, p4;
146  p3.x = model_coefficients.at (3) - model_coefficients.at (0);
147  p3.y = model_coefficients.at (4) - model_coefficients.at (1);
148  p3.z = model_coefficients.at (5) - model_coefficients.at (2);
149 
150  // Iterate through the 3d points and calculate the distances from them to the plane
151  for (unsigned int i = 0; i < indices_.size (); i++)
152  {
153  // Calculate the distance from the point to the line
154  // D = ||(P2-P1) x (P1-P0)|| / ||P2-P1|| = norm (cross (p2-p1, p2-p0)) / norm(p2-p1)
155  p4.x = model_coefficients.at (3) - cloud_->points.at (indices_.at (i)).x;
156  p4.y = model_coefficients.at (4) - cloud_->points.at (indices_.at (i)).y;
157  p4.z = model_coefficients.at (5) - cloud_->points.at (indices_.at (i)).z;
158 
159  pcl::PointXYZ c = cross (p4, p3);
160  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);
161  }
162  return;
163  }
164 
166 
171  void
172  SACModelLine::projectPoints (const std::vector<int> &inliers, const std::vector<double> &model_coefficients,
173  PointCloud &projected_points)
174  {
175  // Allocate enough space
176  projected_points.points.resize (inliers.size ());
177 
178  // Compute the line direction (P2 - P1)
179  pcl::PointXYZ p21;
180  p21.x = model_coefficients.at (3) - model_coefficients.at (0);
181  p21.y = model_coefficients.at (4) - model_coefficients.at (1);
182  p21.z = model_coefficients.at (5) - model_coefficients.at (2);
183 
184  // Iterate through the 3d points and calculate the distances from them to the line
185  for (unsigned int i = 0; i < inliers.size (); i++)
186  {
187  // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B;
188  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 -
189  (model_coefficients_[0] * p21.x + model_coefficients_[1] * p21.y + model_coefficients_[2] * p21.z)
190  ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
191  // Calculate the projection of the point on the line (pointProj = A + k * B)
192  projected_points.points[i].x = model_coefficients_.at (0) + k * p21.x;
193  projected_points.points[i].y = model_coefficients_.at (1) + k * p21.y;
194  projected_points.points[i].z = model_coefficients_.at (2) + k * p21.z;
195  // Copy the other attributes
196  }
197  }
198 
200 
204  void
205  SACModelLine::projectPointsInPlace (const std::vector<int> &inliers, const std::vector<double> &model_coefficients)
206  {
207  // Compute the line direction (P2 - P1)
208  pcl::PointXYZ p21;
209  p21.x = model_coefficients.at (3) - model_coefficients.at (0);
210  p21.y = model_coefficients.at (4) - model_coefficients.at (1);
211  p21.z = model_coefficients.at (5) - model_coefficients.at (2);
212 
213  // Iterate through the 3d points and calculate the distances from them to the line
214  for (unsigned int i = 0; i < inliers.size (); i++)
215  {
216  // double k = (DOT_PROD_3D (points[i], p21) - dotA_B) / dotB_B;
217  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 -
218  (model_coefficients_[0] * p21.x + model_coefficients_[1] * p21.y + model_coefficients_[2] * p21.z)
219  ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
220  // Calculate the projection of the point on the line (pointProj = A + k * B)
221  cloud_->points.at (inliers.at (i)).x = model_coefficients_.at (0) + k * p21.x;
222  cloud_->points.at (inliers.at (i)).y = model_coefficients_.at (1) + k * p21.y;
223  cloud_->points.at (inliers.at (i)).z = model_coefficients_.at (2) + k * p21.z;
224  }
225  }
226 
228 
233  bool
234  SACModelLine::computeModelCoefficients (const std::vector<int> &samples)
235  {
236  model_coefficients_.resize (6);
237  model_coefficients_[0] = cloud_->points.at (samples.at (0)).x;
238  model_coefficients_[1] = cloud_->points.at (samples.at (0)).y;
239  model_coefficients_[2] = cloud_->points.at (samples.at (0)).z;
240  model_coefficients_[3] = cloud_->points.at (samples.at (1)).x;
241  model_coefficients_[4] = cloud_->points.at (samples.at (1)).y;
242  model_coefficients_[5] = cloud_->points.at (samples.at (1)).z;
243 
244  return (true);
245  }
246 
248 
253  void
254  SACModelLine::refitModel (const std::vector<int> &inliers, std::vector<double> &refit_coefficients)
255  {
256  if (inliers.size () == 0)
257  {
258  ROS_ERROR ("[SACModelLine::RefitModel] Cannot re-fit 0 inliers!");
259  refit_coefficients = model_coefficients_;
260  return;
261  }
262 
263  refit_coefficients.resize (6);
264 
265  // Compute the centroid of the samples
266  pcl::PointXYZ centroid;
267  // Compute the 3x3 covariance matrix
268  Eigen::Matrix3d covariance_matrix;
269  computeCovarianceMatrix (*cloud_, inliers, covariance_matrix, centroid);
270 
271  refit_coefficients[0] = centroid.x;
272  refit_coefficients[1] = centroid.y;
273  refit_coefficients[2] = centroid.z;
274 
275  // Extract the eigenvalues and eigenvectors
276  //cloud_geometry::eigen_cov (covariance_matrix, eigen_values, eigen_vectors);
277  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> ei_symm (covariance_matrix.cast<float> ());
278  Eigen::Vector3f eigen_values = ei_symm.eigenvalues ();
279  Eigen::Matrix3f eigen_vectors = ei_symm.eigenvectors ();
280 
281  refit_coefficients[3] = eigen_vectors (0, 2) + refit_coefficients[0];
282  refit_coefficients[4] = eigen_vectors (1, 2) + refit_coefficients[1];
283  refit_coefficients[5] = eigen_vectors (2, 2) + refit_coefficients[2];
284  }
285 
287 
291  bool
292  SACModelLine::doSamplesVerifyModel (const std::set<int> &indices, double threshold)
293  {
294  double sqr_threshold = threshold * threshold;
295  for (std::set<int>::iterator it = indices.begin (); it != indices.end (); ++it)
296  {
297  pcl::PointXYZ p3, p4;
298  p3.x = model_coefficients_.at (3) - model_coefficients_.at (0);
299  p3.y = model_coefficients_.at (4) - model_coefficients_.at (1);
300  p3.z = model_coefficients_.at (5) - model_coefficients_.at (2);
301 
302  p4.x = model_coefficients_.at (3) - cloud_->points.at (*it).x;
303  p4.y = model_coefficients_.at (4) - cloud_->points.at (*it).y;
304  p4.z = model_coefficients_.at (5) - cloud_->points.at (*it).z;
305 
306  pcl::PointXYZ c = cross (p4, p3);
307  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);
308 
309  if (sqr_distance < sqr_threshold)
310  return (false);
311  }
312  return (true);
313  }
314 }
std::vector< int > indices_
The list of internal point indices used.
Definition: sac_model.h:194
std::vector< double > model_coefficients_
The coefficients of our model computed directly from the best samples found.
Definition: sac_model.h:197
virtual bool computeModelCoefficients(const std::vector< int > &samples)
Check whether the given index samples can form a valid line model, compute the model coefficients fro...
virtual void projectPoints(const std::vector< int > &inliers, const std::vector< double > &model_coefficients, PointCloud &projected_points)
Create a new point cloud with inliers projected onto the line model.
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: sac_model.h:43
virtual void refitModel(const std::vector< int > &inliers, std::vector< double > &refit_coefficients)
Recompute the line coefficients using the given inlier set and return them to the user...
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
virtual void getSamples(int &iterations, std::vector< int > &samples)
Get 2 random points as data samples and return them as point indices.
void computeCovarianceMatrix(const PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, pcl::PointXYZ &centroid)
Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returne...
PointCloud * cloud_
Holds a pointer to the point cloud data array, since we don&#39;t want to copy the whole thing here...
Definition: sac_model.h:191
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
virtual void projectPointsInPlace(const std::vector< int > &inliers, const std::vector< double > &model_coefficients)
Project inliers (in place) onto the given line model.
pcl::PointXYZ cross(const pcl::PointXYZ &p1, const pcl::PointXYZ &p2)
Compute the cross product between two points (vectors).
#define ROS_ERROR(...)
virtual void getDistancesToModel(const std::vector< double > &model_coefficients, std::vector< double > &distances)
Compute all distances from the cloud data to a given line model.
#define MAX_ITERATIONS_UNIQUE
Define the maximum number of iterations for selecting 2 unique points.
virtual void selectWithinDistance(const std::vector< double > &model_coefficients, double threshold, std::vector< int > &inliers)
Select all the points which respect the given model coefficients as inliers.
virtual bool doSamplesVerifyModel(const std::set< int > &indices, double threshold)
Verify whether a subset of indices verifies the internal line model coefficients. ...


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Mon Jun 10 2019 14:29:03