Skip to content

Commit ba3ea48

Browse files
mviethlarshg
andauthored
Misc small fixes and improvements (#6256)
* Misc small fixes and improvements - switch vmImage to "ubuntu-22.04". This does not make much difference as we use docker anyway, but azure complained that "Ubuntu 20.04" will be removed soon - enable more warnings on clang - delete several unused variables - switch from Eigen::EigenSolver to Eigen::SelfAdjointEigenSolver where possible. The latter is faster and more accurate ( https://eigen.tuxfamily.org/dox/classEigen_1_1SelfAdjointEigenSolver.html ). For real matrices, selfadjoint means symmetric, which is for example true for covariance matrices. - in shot_lrf_omp.hpp, use dynamic schedule because the loop iterations do a radius search, which is quite unbalanced - fix problem with enum arithmetic in dinast_grabber.cpp - fix MSVC warning about unsafe bool-int mix in octree_pointcloud.hpp - in sac_model_torus.hpp, switch from bdcSvd to jacobiSvd. This should save some time and memory while compiling, and the matrix A is so small that bdcSvd would anyway use jacobiSvd internally. - in flann_search.hpp, use delete[] instead of delete to correctly match the new[] - in grabcut_segmentation.cpp, check svd.info() to fix warning that svd.singularValues() may be uninitialized - in octree_poisson.hpp, fix maybe-uninitialized warning * Add more const Co-authored-by: Lars Glud <[email protected]> --------- Co-authored-by: Lars Glud <[email protected]>
1 parent 9815825 commit ba3ea48

File tree

33 files changed

+99
-101
lines changed

33 files changed

+99
-101
lines changed

Diff for: .ci/azure-pipelines/documentation.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ jobs:
22
- job: documentation
33
displayName: Generate Documentation
44
pool:
5-
vmImage: 'Ubuntu 20.04'
5+
vmImage: 'ubuntu-22.04'
66
container: doc
77
variables:
88
BUILD_DIR: '$(Agent.BuildDirectory)/build'

Diff for: .ci/azure-pipelines/tutorials.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ jobs:
22
- job: tutorials
33
displayName: Building Tutorials
44
pool:
5-
vmImage: 'Ubuntu 20.04'
5+
vmImage: 'ubuntu-22.04'
66
container: env2204
77
timeoutInMinutes: 0
88
variables:

Diff for: CMakeLists.txt

+5-2
Original file line numberDiff line numberDiff line change
@@ -228,13 +228,14 @@ endif()
228228

229229
if(CMAKE_COMPILER_IS_CLANG)
230230
if("${CMAKE_C_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}")
231-
set(CMAKE_C_FLAGS "-Qunused-arguments")
231+
string(APPEND CMAKE_C_FLAGS " -Wall -Wextra")
232232
endif()
233233
if("${CMAKE_CXX_FLAGS}" STREQUAL "")
234-
set(CMAKE_CXX_FLAGS "-ftemplate-depth=1024 -Qunused-arguments -Wno-invalid-offsetof ${SSE_FLAGS} ${AVX_FLAGS}") # Unfortunately older Clang versions do not have this: -Wno-unnamed-type-template-args
234+
set(CMAKE_CXX_FLAGS "-ftemplate-depth=1024 -Wno-invalid-offsetof ${SSE_FLAGS} ${AVX_FLAGS}") # Unfortunately older Clang versions do not have this: -Wno-unnamed-type-template-args
235235
if(APPLE AND WITH_CUDA AND CUDA_FOUND)
236236
string(APPEND CMAKE_CXX_FLAGS " -stdlib=libstdc++")
237237
endif()
238+
string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra")
238239
endif()
239240
set(CLANG_LIBRARIES "stdc++")
240241
endif()
@@ -434,6 +435,8 @@ if(WITH_SYSTEM_ZLIB)
434435
if(ZLIB_FOUND)
435436
set(HAVE_ZLIB ON)
436437
endif()
438+
else()
439+
message(WARNING "CMake will use a ZLIB version bundled with the PCL source code. However, that is an older version which may pose a risk and may be removed in a future PCL release. It is recommended to install an up-to-date version of ZLIB on your system and set WITH_SYSTEM_ZLIB=TRUE.")
437440
endif()
438441

439442
option(WITH_SYSTEM_CJSON "Use system cJSON" TRUE)

Diff for: common/include/pcl/impl/pcl_base.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ pcl::PCLBase<PointT>::initCompute ()
164164
PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", input_->size ());
165165
return (false);
166166
}
167-
for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
167+
for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = i; }
168168
}
169169

170170
return (true);

Diff for: features/include/pcl/features/impl/flare.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -178,8 +178,6 @@ template<typename PointInT, typename PointNT, typename PointOutT, typename Signe
178178
SignedDistanceT best_shape_score = -std::numeric_limits<SignedDistanceT>::max ();
179179
int best_shape_index = -1;
180180

181-
Eigen::Vector3f best_margin_point;
182-
183181
const float radius2 = tangent_radius_ * tangent_radius_;
184182
const float margin_distance2 = margin_thresh_ * margin_thresh_ * radius2;
185183

Diff for: features/include/pcl/features/impl/integral_image2D.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -194,7 +194,6 @@ IntegralImage2D<DataType, Dimension>::computeIntegralImages (
194194
for (unsigned int i = 0; i < (width_ + 1); ++i)
195195
so_previous_row[i].setZero();
196196

197-
SecondOrderType so_element;
198197
for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride,
199198
previous_row = current_row, current_row += (width_ + 1),
200199
count_previous_row = count_current_row, count_current_row += (width_ + 1),

Diff for: features/include/pcl/features/impl/moment_of_inertia_estimation.hpp

+12-15
Original file line numberDiff line numberDiff line change
@@ -399,47 +399,44 @@ pcl::MomentOfInertiaEstimation<PointT>::computeEigenVectors (const Eigen::Matrix
399399
Eigen::Vector3f& major_axis, Eigen::Vector3f& middle_axis, Eigen::Vector3f& minor_axis, float& major_value,
400400
float& middle_value, float& minor_value)
401401
{
402-
Eigen::EigenSolver <Eigen::Matrix <float, 3, 3> > eigen_solver;
403-
eigen_solver.compute (covariance_matrix);
402+
const Eigen::SelfAdjointEigenSolver<Eigen::Matrix<float, 3, 3>> eigen_solver(covariance_matrix);
404403

405-
Eigen::EigenSolver <Eigen::Matrix <float, 3, 3> >::EigenvectorsType eigen_vectors;
406-
Eigen::EigenSolver <Eigen::Matrix <float, 3, 3> >::EigenvalueType eigen_values;
407-
eigen_vectors = eigen_solver.eigenvectors ();
408-
eigen_values = eigen_solver.eigenvalues ();
404+
const Eigen::SelfAdjointEigenSolver <Eigen::Matrix <float, 3, 3> >::EigenvectorsType& eigen_vectors = eigen_solver.eigenvectors ();
405+
const Eigen::SelfAdjointEigenSolver <Eigen::Matrix <float, 3, 3> >::RealVectorType& eigen_values = eigen_solver.eigenvalues ();
409406

410407
unsigned int temp = 0;
411408
unsigned int major_index = 0;
412409
unsigned int middle_index = 1;
413410
unsigned int minor_index = 2;
414411

415-
if (eigen_values.real () (major_index) < eigen_values.real () (middle_index))
412+
if (eigen_values (major_index) < eigen_values (middle_index))
416413
{
417414
temp = major_index;
418415
major_index = middle_index;
419416
middle_index = temp;
420417
}
421418

422-
if (eigen_values.real () (major_index) < eigen_values.real () (minor_index))
419+
if (eigen_values (major_index) < eigen_values (minor_index))
423420
{
424421
temp = major_index;
425422
major_index = minor_index;
426423
minor_index = temp;
427424
}
428425

429-
if (eigen_values.real () (middle_index) < eigen_values.real () (minor_index))
426+
if (eigen_values (middle_index) < eigen_values (minor_index))
430427
{
431428
temp = minor_index;
432429
minor_index = middle_index;
433430
middle_index = temp;
434431
}
435432

436-
major_value = eigen_values.real () (major_index);
437-
middle_value = eigen_values.real () (middle_index);
438-
minor_value = eigen_values.real () (minor_index);
433+
major_value = eigen_values (major_index);
434+
middle_value = eigen_values (middle_index);
435+
minor_value = eigen_values (minor_index);
439436

440-
major_axis = eigen_vectors.col (major_index).real ();
441-
middle_axis = eigen_vectors.col (middle_index).real ();
442-
minor_axis = eigen_vectors.col (minor_index).real ();
437+
major_axis = eigen_vectors.col (major_index);
438+
middle_axis = eigen_vectors.col (middle_index);
439+
minor_axis = eigen_vectors.col (minor_index);
443440

444441
major_axis.normalize ();
445442
middle_axis.normalize ();

Diff for: features/include/pcl/features/impl/our_cvfh.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -260,7 +260,7 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::sgurf (Eigen::Vector3f & c
260260

261261
scatter /= sum_w;
262262

263-
Eigen::JacobiSVD <Eigen::MatrixXf> svd (scatter, Eigen::ComputeFullV);
263+
const Eigen::JacobiSVD <Eigen::Matrix3f> svd (scatter, Eigen::ComputeFullV);
264264
Eigen::Vector3f evx = svd.matrixV ().col (0);
265265
Eigen::Vector3f evy = svd.matrixV ().col (1);
266266
Eigen::Vector3f evz = svd.matrixV ().col (2);

Diff for: features/include/pcl/features/impl/rops_estimation.hpp

+9-12
Original file line numberDiff line numberDiff line change
@@ -343,43 +343,40 @@ template <typename PointInT, typename PointOutT> void
343343
pcl::ROPSEstimation <PointInT, PointOutT>::computeEigenVectors (const Eigen::Matrix3f& matrix,
344344
Eigen::Vector3f& major_axis, Eigen::Vector3f& middle_axis, Eigen::Vector3f& minor_axis) const
345345
{
346-
Eigen::EigenSolver <Eigen::Matrix3f> eigen_solver;
347-
eigen_solver.compute (matrix);
346+
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(matrix, Eigen::ComputeEigenvectors);
348347

349-
Eigen::EigenSolver <Eigen::Matrix3f>::EigenvectorsType eigen_vectors;
350-
Eigen::EigenSolver <Eigen::Matrix3f>::EigenvalueType eigen_values;
351-
eigen_vectors = eigen_solver.eigenvectors ();
352-
eigen_values = eigen_solver.eigenvalues ();
348+
const Eigen::SelfAdjointEigenSolver <Eigen::Matrix3f>::EigenvectorsType& eigen_vectors = eigen_solver.eigenvectors ();
349+
const Eigen::SelfAdjointEigenSolver <Eigen::Matrix3f>::RealVectorType& eigen_values = eigen_solver.eigenvalues ();
353350

354351
unsigned int temp = 0;
355352
unsigned int major_index = 0;
356353
unsigned int middle_index = 1;
357354
unsigned int minor_index = 2;
358355

359-
if (eigen_values.real () (major_index) < eigen_values.real () (middle_index))
356+
if (eigen_values (major_index) < eigen_values (middle_index))
360357
{
361358
temp = major_index;
362359
major_index = middle_index;
363360
middle_index = temp;
364361
}
365362

366-
if (eigen_values.real () (major_index) < eigen_values.real () (minor_index))
363+
if (eigen_values (major_index) < eigen_values (minor_index))
367364
{
368365
temp = major_index;
369366
major_index = minor_index;
370367
minor_index = temp;
371368
}
372369

373-
if (eigen_values.real () (middle_index) < eigen_values.real () (minor_index))
370+
if (eigen_values (middle_index) < eigen_values (minor_index))
374371
{
375372
temp = minor_index;
376373
minor_index = middle_index;
377374
middle_index = temp;
378375
}
379376

380-
major_axis = eigen_vectors.col (major_index).real ();
381-
middle_axis = eigen_vectors.col (middle_index).real ();
382-
minor_axis = eigen_vectors.col (minor_index).real ();
377+
major_axis = eigen_vectors.col (major_index);
378+
middle_axis = eigen_vectors.col (middle_index);
379+
minor_axis = eigen_vectors.col (minor_index);
383380
}
384381

385382
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

Diff for: features/include/pcl/features/impl/shot_lrf_omp.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,8 @@ pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeature (
7474
#pragma omp parallel for \
7575
default(none) \
7676
shared(output) \
77-
num_threads(threads_)
77+
num_threads(threads_) \
78+
schedule(dynamic, 64)
7879
for (std::ptrdiff_t i = 0; i < static_cast<std::ptrdiff_t> (indices_->size ()); ++i)
7980
{
8081
// point result

Diff for: filters/include/pcl/filters/convolution_3d.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ namespace pcl
133133
* \param[in] sigma
134134
*/
135135
inline void
136-
setSigma (float sigma) { sigma_ = sigma; }
136+
setSigma (float sigma) { sigma_ = sigma; sigma_sqr_ = sigma_ * sigma_; }
137137

138138
/** Set the distance threshold relative to a sigma factor i.e. points such as
139139
* ||pi - q|| > sigma_coefficient^2 * sigma^2 are not considered.

Diff for: filters/include/pcl/filters/impl/approximate_voxel_grid.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#define PCL_FILTERS_IMPL_FAST_VOXEL_GRID_H_
4040

4141
#include <pcl/common/io.h>
42+
#include <pcl/common/point_tests.h>
4243
#include <pcl/filters/approximate_voxel_grid.h>
4344
#include <boost/mpl/size.hpp> // for size
4445

@@ -91,6 +92,8 @@ pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
9192
std::size_t op = 0; // output pointer
9293
for (const auto& point: *input_)
9394
{
95+
if(!pcl::isXYZFinite(point))
96+
continue;
9497
int ix = static_cast<int> (std::floor (point.x * inverse_leaf_size_[0]));
9598
int iy = static_cast<int> (std::floor (point.y * inverse_leaf_size_[1]));
9699
int iz = static_cast<int> (std::floor (point.z * inverse_leaf_size_[2]));
@@ -130,7 +133,7 @@ pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
130133
output.resize (op);
131134
output.width = output.size ();
132135
output.height = 1; // downsampling breaks the organized structure
133-
output.is_dense = false; // we filter out invalid points
136+
output.is_dense = true; // we filter out invalid points
134137
}
135138

136139
#define PCL_INSTANTIATE_ApproximateVoxelGrid(T) template class PCL_EXPORTS pcl::ApproximateVoxelGrid<T>;

Diff for: filters/include/pcl/filters/impl/shadowpoints.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,8 @@ pcl::ShadowPoints<PointT, NormalT>::applyFilter (PointCloud &output)
6969
{
7070
PointT &pt_new = output[cp++] = pt;
7171
pt_new.x = pt_new.y = pt_new.z = user_filter_value_;
72+
if(!std::isfinite(user_filter_value_))
73+
output.is_dense = false;
7274
}
7375

7476
}

Diff for: io/src/dinast_grabber.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -353,7 +353,7 @@ pcl::DinastGrabber::USBRxControlData (const unsigned char req_code,
353353
int length)
354354
{
355355
// The direction of the transfer is inferred from the requesttype field of the setup packet.
356-
unsigned char requesttype = (LIBUSB_RECIPIENT_DEVICE | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_ENDPOINT_IN);
356+
const unsigned char requesttype = (static_cast<unsigned char>(LIBUSB_RECIPIENT_DEVICE) | static_cast<unsigned char>(LIBUSB_REQUEST_TYPE_VENDOR) | static_cast<unsigned char>(LIBUSB_ENDPOINT_IN));
357357
// The value field for the setup packet
358358
std::uint16_t value = 0x02;
359359
// The index field for the setup packet
@@ -377,7 +377,7 @@ pcl::DinastGrabber::USBTxControlData (const unsigned char req_code,
377377
int length)
378378
{
379379
// The direction of the transfer is inferred from the requesttype field of the setup packet.
380-
unsigned char requesttype = (LIBUSB_RECIPIENT_DEVICE | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_ENDPOINT_OUT);
380+
const unsigned char requesttype = (static_cast<unsigned char>(LIBUSB_RECIPIENT_DEVICE) | static_cast<unsigned char>(LIBUSB_REQUEST_TYPE_VENDOR) | static_cast<unsigned char>(LIBUSB_ENDPOINT_OUT));
381381
// The value field for the setup packet
382382
std::uint16_t value = 0x01;
383383
// The index field for the setup packet

Diff for: keypoints/include/pcl/keypoints/impl/iss_3d.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -373,7 +373,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
373373
Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero ();
374374
getScatterMatrix (static_cast<int> (index), cov_m);
375375

376-
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver (cov_m);
376+
const Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver (cov_m, Eigen::EigenvaluesOnly);
377377

378378
const double& e1c = solver.eigenvalues ()[2];
379379
const double& e2c = solver.eigenvalues ()[1];

Diff for: octree/include/pcl/octree/impl/octree_pointcloud.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -517,9 +517,9 @@ pcl::octree::OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT>
517517

518518
// octree not empty - we add another tree level and thus increase its size by a
519519
// factor of 2*2*2
520-
child_idx = static_cast<unsigned char>(((bLowerBoundViolationX) << 2) |
521-
((bLowerBoundViolationY) << 1) |
522-
((bLowerBoundViolationZ)));
520+
child_idx = static_cast<unsigned char>((bLowerBoundViolationX ? 4 : 0) |
521+
(bLowerBoundViolationY ? 2 : 0) |
522+
(bLowerBoundViolationZ ? 1 : 0));
523523

524524
BranchNode* newRootBranch;
525525

Diff for: registration/include/pcl/registration/impl/ndt_2d.hpp

+10-11
Original file line numberDiff line numberDiff line change
@@ -437,29 +437,28 @@ NormalDistributionsTransform2D<PointSource, PointTarget>::computeTransformation(
437437

438438
if (score.value != 0) {
439439
// test for positive definiteness, and adjust to ensure it if necessary:
440-
Eigen::EigenSolver<Eigen::Matrix3d> solver;
441-
solver.compute(score.hessian, false);
440+
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver(score.hessian,
441+
Eigen::EigenvaluesOnly);
442442
double min_eigenvalue = 0;
443443
for (int i = 0; i < 3; i++)
444-
if (solver.eigenvalues()[i].real() < min_eigenvalue)
445-
min_eigenvalue = solver.eigenvalues()[i].real();
444+
if (solver.eigenvalues()[i] < min_eigenvalue)
445+
min_eigenvalue = solver.eigenvalues()[i];
446446

447447
// ensure "safe" positive definiteness: this is a detail missing
448448
// from the original paper
449449
if (min_eigenvalue < 0) {
450450
double lambda = 1.1 * min_eigenvalue - 1;
451451
score.hessian += Eigen::Vector3d(-lambda, -lambda, -lambda).asDiagonal();
452-
solver.compute(score.hessian, false);
452+
solver.compute(score.hessian, Eigen::EigenvaluesOnly);
453453
PCL_DEBUG("[pcl::NormalDistributionsTransform2D::computeTransformation] adjust "
454454
"hessian: %f: new eigenvalues:%f %f %f\n",
455455
float(lambda),
456-
solver.eigenvalues()[0].real(),
457-
solver.eigenvalues()[1].real(),
458-
solver.eigenvalues()[2].real());
456+
solver.eigenvalues()[0],
457+
solver.eigenvalues()[1],
458+
solver.eigenvalues()[2]);
459459
}
460-
assert(solver.eigenvalues()[0].real() >= 0 &&
461-
solver.eigenvalues()[1].real() >= 0 &&
462-
solver.eigenvalues()[2].real() >= 0);
460+
assert(solver.eigenvalues()[0] >= 0 && solver.eigenvalues()[1] >= 0 &&
461+
solver.eigenvalues()[2] >= 0);
463462

464463
Eigen::Vector3d delta_transformation(-score.hessian.inverse() * score.grad);
465464
Eigen::Vector3d new_transformation =

Diff for: registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -196,11 +196,11 @@ TransformationEstimationDualQuaternion<PointSource, PointTarget, Scalar>::
196196
const Eigen::Matrix<double, 4, 4> A =
197197
(0.25 / static_cast<double>(npts)) * C2.transpose() * C2 - C1;
198198

199-
const Eigen::EigenSolver<Eigen::Matrix<double, 4, 4>> es(A);
199+
const Eigen::SelfAdjointEigenSolver<Eigen::Matrix<double, 4, 4>> es(A);
200200

201201
ptrdiff_t i;
202-
es.eigenvalues().real().maxCoeff(&i);
203-
const Eigen::Matrix<double, 4, 1> qmat = es.eigenvectors().col(i).real();
202+
es.eigenvalues().maxCoeff(&i);
203+
const Eigen::Matrix<double, 4, 1> qmat = es.eigenvectors().col(i);
204204
const Eigen::Matrix<double, 4, 1> smat =
205205
-(0.5 / static_cast<double>(npts)) * C2 * qmat;
206206

Diff for: sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -243,19 +243,19 @@ pcl::SampleConsensusModelCircle3D<PointT>::countWithinDistance (
243243
return (0);
244244
std::size_t nr_p = 0;
245245

246+
// C : Circle Center
247+
const Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]);
248+
// N : Circle (Plane) Normal
249+
const Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]);
250+
// r : Radius
251+
const double r = model_coefficients[3];
246252
const auto squared_threshold = threshold * threshold;
247253
// Iterate through the 3d points and calculate the distances from them to the sphere
248254
for (std::size_t i = 0; i < indices_->size (); ++i)
249255
{
250256
// what i have:
251257
// P : Sample Point
252258
Eigen::Vector3d P ((*input_)[(*indices_)[i]].x, (*input_)[(*indices_)[i]].y, (*input_)[(*indices_)[i]].z);
253-
// C : Circle Center
254-
Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]);
255-
// N : Circle (Plane) Normal
256-
Eigen::Vector3d N (model_coefficients[4], model_coefficients[5], model_coefficients[6]);
257-
// r : Radius
258-
double r = model_coefficients[3];
259259

260260
Eigen::Vector3d helper_vectorPC = P - C;
261261
// 1.1. get line parameter
@@ -303,7 +303,7 @@ pcl::SampleConsensusModelCircle3D<PointT>::optimizeModelCoefficients (
303303
Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, double> lm (num_diff);
304304
Eigen::VectorXd coeff = optimized_coefficients.cast<double>();
305305
int info = lm.minimize (coeff);
306-
coeff.tail(3).normalize(); // normalize the cylinder axis
306+
coeff.tail<3>().normalize(); // normalize the cylinder axis
307307
for (Eigen::Index i = 0; i < coeff.size (); ++i)
308308
optimized_coefficients[i] = static_cast<float> (coeff[i]);
309309

0 commit comments

Comments
 (0)