41 #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_
42 #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_LINE_H_
44 #include <pcl/sample_consensus/sac_model_line.h>
46 #include <pcl/common/concatenate.h>
47 #include <pcl/common/eigen.h>
50 template <
typename Po
intT>
bool
53 if (samples.size () != sample_size_)
55 PCL_ERROR (
"[pcl::SampleConsensusModelLine::isSampleGood] Wrong number of samples (is %lu, should be %lu)!\n", samples.size (), sample_size_);
61 std::abs ((*input_)[samples[0]].x - (*input_)[samples[1]].x) <= std::numeric_limits<float>::epsilon ()
63 std::abs ((*input_)[samples[0]].y - (*input_)[samples[1]].y) <= std::numeric_limits<float>::epsilon ()
65 std::abs ((*input_)[samples[0]].z - (*input_)[samples[1]].z) <= std::numeric_limits<float>::epsilon ())
67 PCL_ERROR (
"[pcl::SampleConsensusModelLine::isSampleGood] The two sample points are (almost) identical!\n");
75 template <
typename Po
intT>
bool
77 const Indices &samples, Eigen::VectorXf &model_coefficients)
const
80 if (!isSampleGood (samples))
82 PCL_ERROR (
"[pcl::SampleConsensusModelLine::computeModelCoefficients] Invalid set of samples given!\n");
86 model_coefficients.resize (model_size_);
87 model_coefficients[0] = (*input_)[samples[0]].x;
88 model_coefficients[1] = (*input_)[samples[0]].y;
89 model_coefficients[2] = (*input_)[samples[0]].z;
91 model_coefficients[3] = (*input_)[samples[1]].x - model_coefficients[0];
92 model_coefficients[4] = (*input_)[samples[1]].y - model_coefficients[1];
93 model_coefficients[5] = (*input_)[samples[1]].z - model_coefficients[2];
96 assert (model_coefficients.template tail<3> ().squaredNorm () > 0.0f);
98 model_coefficients.template tail<3> ().normalize ();
99 PCL_DEBUG (
"[pcl::SampleConsensusModelLine::computeModelCoefficients] Model is (%g,%g,%g,%g,%g,%g).\n",
100 model_coefficients[0], model_coefficients[1], model_coefficients[2],
101 model_coefficients[3], model_coefficients[4], model_coefficients[5]);
106 template <
typename Po
intT>
void
108 const Eigen::VectorXf &model_coefficients, std::vector<double> &distances)
const
111 if (!isModelValid (model_coefficients))
116 distances.resize (indices_->size ());
119 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
120 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
121 line_dir.normalize ();
124 for (std::size_t i = 0; i < indices_->size (); ++i)
129 distances[i] = sqrt ((line_pt - (*input_)[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ());
134 template <
typename Po
intT>
void
136 const Eigen::VectorXf &model_coefficients,
const double threshold,
Indices &inliers)
139 if (!isModelValid (model_coefficients))
142 double sqr_threshold = threshold * threshold;
145 error_sqr_dists_.clear ();
146 inliers.reserve (indices_->size ());
147 error_sqr_dists_.reserve (indices_->size ());
150 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0);
151 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0);
152 line_dir.normalize ();
155 for (std::size_t i = 0; i < indices_->size (); ++i)
159 double sqr_distance = (line_pt - (*input_)[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ();
161 if (sqr_distance < sqr_threshold)
164 inliers.push_back ((*indices_)[i]);
165 error_sqr_dists_.push_back (sqr_distance);
171 template <
typename Po
intT> std::size_t
173 const Eigen::VectorXf &model_coefficients,
const double threshold)
const
176 if (!isModelValid (model_coefficients))
179 double sqr_threshold = threshold * threshold;
181 std::size_t nr_p = 0;
184 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
185 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0.0f);
186 line_dir.normalize ();
189 for (std::size_t i = 0; i < indices_->size (); ++i)
193 double sqr_distance = (line_pt - (*input_)[(*indices_)[i]].getVector4fMap ()).cross3 (line_dir).squaredNorm ();
195 if (sqr_distance < sqr_threshold)
202 template <
typename Po
intT>
void
204 const Indices &inliers,
const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
const
207 if (!isModelValid (model_coefficients))
209 optimized_coefficients = model_coefficients;
214 if (inliers.size () <= sample_size_)
216 PCL_ERROR (
"[pcl::SampleConsensusModelLine::optimizeModelCoefficients] Not enough inliers to refine/optimize the model's coefficients (%lu)! Returning the same coefficients.\n", inliers.size ());
217 optimized_coefficients = model_coefficients;
221 optimized_coefficients.resize (model_size_);
224 Eigen::Vector4f centroid;
227 PCL_WARN (
"[pcl::SampleConsensusModelLine::optimizeModelCoefficients] compute3DCentroid failed (returned 0) because there are no valid inliers.\n");
228 optimized_coefficients = model_coefficients;
231 Eigen::Matrix3f covariance_matrix;
233 optimized_coefficients[0] = centroid[0];
234 optimized_coefficients[1] = centroid[1];
235 optimized_coefficients[2] = centroid[2];
238 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
239 EIGEN_ALIGN16 Eigen::Vector3f eigen_vector;
244 optimized_coefficients.template tail<3> ().matrix () = eigen_vector;
248 template <
typename Po
intT>
void
250 const Indices &inliers,
const Eigen::VectorXf &model_coefficients,
PointCloud &projected_points,
bool copy_data_fields)
const
253 if (!isModelValid (model_coefficients))
255 PCL_ERROR (
"[pcl::SampleConsensusModelLine::projectPoints] Given model is invalid!\n");
260 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
261 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0.0f);
263 projected_points.
header = input_->header;
264 projected_points.
is_dense = input_->is_dense;
267 if (copy_data_fields)
270 projected_points.
resize (input_->size ());
271 projected_points.
width = input_->width;
272 projected_points.
height = input_->height;
274 using FieldList =
typename pcl::traits::fieldList<PointT>::type;
276 for (std::size_t i = 0; i < projected_points.
size (); ++i)
281 for (
const auto &inlier : inliers)
283 Eigen::Vector4f pt ((*input_)[inlier].x, (*input_)[inlier].y, (*input_)[inlier].z, 0.0f);
285 float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir);
287 Eigen::Vector4f pp = line_pt + k * line_dir;
289 projected_points[inlier].x = pp[0];
290 projected_points[inlier].y = pp[1];
291 projected_points[inlier].z = pp[2];
297 projected_points.
resize (inliers.size ());
298 projected_points.
width = inliers.size ();
299 projected_points.
height = 1;
301 using FieldList =
typename pcl::traits::fieldList<PointT>::type;
303 for (std::size_t i = 0; i < inliers.size (); ++i)
308 for (std::size_t i = 0; i < inliers.size (); ++i)
310 Eigen::Vector4f pt ((*input_)[inliers[i]].x, (*input_)[inliers[i]].y, (*input_)[inliers[i]].z, 0.0f);
312 float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir);
314 Eigen::Vector4f pp = line_pt + k * line_dir;
316 projected_points[i].x = pp[0];
317 projected_points[i].y = pp[1];
318 projected_points[i].z = pp[2];
324 template <
typename Po
intT>
bool
326 const std::set<index_t> &indices,
const Eigen::VectorXf &model_coefficients,
const double threshold)
const
329 if (!isModelValid (model_coefficients))
333 Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f);
334 Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0.0f);
335 line_dir.normalize ();
337 double sqr_threshold = threshold * threshold;
339 for (
const auto &index : indices)
343 if ((line_pt - (*input_)[index].getVector4fMap ()).cross3 (line_dir).squaredNorm () > sqr_threshold)
350 #define PCL_INSTANTIATE_SampleConsensusModelLine(T) template class PCL_EXPORTS pcl::SampleConsensusModelLine<T>;
Define methods for centroid estimation and covariance matrix calculus.
PointCloud represents the base class in PCL for storing collections of 3D points.
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
void resize(std::size_t count)
Resizes the container to contain count elements.
std::uint32_t width
The point cloud width (if organized as an image-structure).
pcl::PCLHeader header
The point cloud header.
std::uint32_t height
The point cloud height (if organized as an image-structure).
bool computeModelCoefficients(const Indices &samples, Eigen::VectorXf &model_coefficients) const override
Check whether the given index samples can form a valid line model, compute the model coefficients fro...
std::size_t countWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold) const override
Count all the points which respect the given model coefficients as inliers.
void getDistancesToModel(const Eigen::VectorXf &model_coefficients, std::vector< double > &distances) const override
Compute all squared distances from the cloud data to a given line model.
bool isSampleGood(const Indices &samples) const override
Check if a sample of indices results in a good sample of points indices.
bool doSamplesVerifyModel(const std::set< index_t > &indices, const Eigen::VectorXf &model_coefficients, const double threshold) const override
Verify whether a subset of indices verifies the given line model coefficients.
void optimizeModelCoefficients(const Indices &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients) const override
Recompute the line coefficients using the given inlier set and return them to the user.
void projectPoints(const Indices &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields=true) const override
Create a new point cloud with inliers projected onto the line model.
void selectWithinDistance(const Eigen::VectorXf &model_coefficients, const double threshold, Indices &inliers) override
Select all the points which respect the given model coefficients as inliers.
void computeCorrespondingEigenVector(const Matrix &mat, const typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi defin...
unsigned int computeCovarianceMatrix(const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix)
Compute the 3x3 covariance matrix of a given set of points.
void eigen33(const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi d...
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > ¢roid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
IndicesAllocator<> Indices
Type used for indices in PCL.
Helper functor structure for concatenate.