38 #include <Eigen/Eigenvalues> 55 double trand =
indices_.size () / (RAND_MAX + 1.0);
58 int idx = (int)(rand () * trand);
66 idx = (int)(rand () * trand);
76 }
while (samples[1] == samples[0]);
92 double sqr_threshold = threshold * threshold;
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);
104 for (
unsigned int i = 0; i <
indices_.size (); i++)
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;
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);
123 if (sqr_distance < sqr_threshold)
130 inliers.resize (nr_p);
142 distances.resize (
indices_.size ());
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);
151 for (
unsigned int i = 0; i <
indices_.size (); i++)
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;
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);
176 projected_points.points.resize (inliers.size ());
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);
185 for (
unsigned int i = 0; i < inliers.size (); i++)
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 -
190 ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
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);
214 for (
unsigned int i = 0; i < inliers.size (); i++)
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 -
219 ) / (p21.x * p21.x + p21.y * p21.y + p21.z * p21.z);
256 if (inliers.size () == 0)
258 ROS_ERROR (
"[SACModelLine::RefitModel] Cannot re-fit 0 inliers!");
263 refit_coefficients.resize (6);
266 pcl::PointXYZ centroid;
268 Eigen::Matrix3d covariance_matrix;
271 refit_coefficients[0] = centroid.x;
272 refit_coefficients[1] = centroid.y;
273 refit_coefficients[2] = centroid.z;
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 ();
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];
294 double sqr_threshold = threshold * threshold;
295 for (std::set<int>::iterator it = indices.begin (); it != indices.end (); ++it)
297 pcl::PointXYZ p3, p4;
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);
309 if (sqr_distance < sqr_threshold)
std::vector< int > indices_
The list of internal point indices used.
std::vector< double > model_coefficients_
The coefficients of our model computed directly from the best samples found.
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
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
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 ¢roid)
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't want to copy the whole thing here...
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).
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. ...