Skip to content

Commit d3769b1

Browse files
authored
Merge pull request #6277 from mvieth/noalias
Use noalias() where possible
2 parents 0dec791 + eee7805 commit d3769b1

File tree

24 files changed

+50
-50
lines changed

24 files changed

+50
-50
lines changed

common/include/pcl/common/impl/centroid.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -696,7 +696,7 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
696696
//[0 , 1 ]
697697
Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
698698
transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
699-
transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;
699+
transform.template topRightCorner<3, 1>().noalias() =-transform.template topLeftCorner<3, 3>()*centroid;
700700

701701
//when Scalar==double on a Windows 10 machine and MSVS:
702702
//if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
@@ -786,7 +786,7 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
786786
obb_dimensions(1) = obb_max_pointy - obb_min_pointy;
787787
obb_dimensions(2) = obb_max_pointz - obb_min_pointz;
788788

789-
obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
789+
obb_center.noalias() = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
790790

791791
return (point_count);
792792
}
@@ -830,7 +830,7 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
830830
//[0 , 1 ]
831831
Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
832832
transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
833-
transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;
833+
transform.template topRightCorner<3, 1>().noalias() =-transform.template topLeftCorner<3, 3>()*centroid;
834834

835835
//when Scalar==double on a Windows 10 machine and MSVS:
836836
//if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
@@ -922,7 +922,7 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
922922
obb_dimensions(1) = obb_max_pointy - obb_min_pointy;
923923
obb_dimensions(2) = obb_max_pointz - obb_min_pointz;
924924

925-
obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
925+
obb_center.noalias() = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud
926926

927927
return (point_count);
928928
}

common/include/pcl/common/impl/eigen.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -912,8 +912,8 @@ transformBetween2CoordinateSystems (const Eigen::Matrix<Scalar, Eigen::Dynamic,
912912
// Identity matrix = transform to CS2 to CS3
913913
// Note: if CS1 == CS2 --> transformation = T3
914914
transformation = Eigen::Transform<Scalar, 3, Eigen::Affine>::Identity ();
915-
transformation.linear () = T3.linear () * T2.linear ().inverse ();
916-
transformation.translation () = to0 - (transformation.linear () * fr0);
915+
transformation.linear ().noalias () = T3.linear () * T2.linear ().inverse ();
916+
transformation.translation ().noalias () = to0 - (transformation.linear () * fr0);
917917
return (true);
918918
}
919919

common/include/pcl/common/impl/pca.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ PCA<PointT>::initCompute ()
8686
eigenvectors_.col(2) = eigenvectors_.col(0).cross(eigenvectors_.col(1));
8787
// If not basis only then compute the coefficients
8888
if (!basis_only_)
89-
coefficients_ = eigenvectors_.transpose() * cloud_demean.topRows<3> ();
89+
coefficients_.noalias() = eigenvectors_.transpose() * cloud_demean.topRows<3> ();
9090
compute_done_ = true;
9191
return (true);
9292
}
@@ -171,7 +171,7 @@ PCA<PointT>::project (const PointT& input, PointT& projection)
171171
PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::project] PCA initCompute failed");
172172

173173
Eigen::Vector3f demean_input = input.getVector3fMap () - mean_.head<3> ();
174-
projection.getVector3fMap () = eigenvectors_.transpose() * demean_input;
174+
projection.getVector3fMap ().noalias () = eigenvectors_.transpose() * demean_input;
175175
}
176176

177177

common/include/pcl/common/impl/polynomial_calculations.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -482,7 +482,7 @@ PolynomialCalculationsT<real>::bivariatePolynomialApproximation (
482482
//std::cout << "Cholesky took "<< (choleskyStartTime+get_time ())*1000<<"ms.\n";
483483

484484
//double invStartTime=-get_time ();
485-
parameters = A.inverse () * b;
485+
parameters.noalias() = A.inverse () * b;
486486
//std::cout << "Inverse took "<< (invStartTime+get_time ())*1000<<"ms.\n";
487487

488488
//std::cout << PVARC (A)<<PVARC (b)<<PVARN (parameters);

features/include/pcl/features/impl/intensity_gradient.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -136,7 +136,7 @@ pcl::IntensityGradientEstimation <PointInT, PointNT, PointOutT, IntensitySelecto
136136
// std::cout << A << "\n*\n" << bb << "\n=\n" << x << "\nvs.\n" << x2 << "\n\n";
137137
// std::cout << A * x << "\nvs.\n" << A * x2 << "\n\n------\n";
138138
// Project the gradient vector, x, onto the tangent plane
139-
gradient = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x;
139+
gradient.noalias() = (Eigen::Matrix3f::Identity () - normal*normal.transpose ()) * x;
140140
}
141141

142142
//////////////////////////////////////////////////////////////////////////////////////////////

features/include/pcl/features/impl/moment_of_inertia_estimation.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -266,7 +266,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeOBB ()
266266
obb_max_point_.y -= shift (1);
267267
obb_max_point_.z -= shift (2);
268268

269-
obb_position_ = mean_value_ + obb_rotational_matrix_ * shift;
269+
obb_position_.noalias() = mean_value_ + obb_rotational_matrix_ * shift;
270270
}
271271

272272
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
@@ -366,7 +366,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeCovarianceMatrix (Eigen::Matrix <
366366
current_point (1) = (*input_)[(*indices_)[i_point]].y - mean_value_ (1);
367367
current_point (2) = (*input_)[(*indices_)[i_point]].z - mean_value_ (2);
368368

369-
covariance_matrix += current_point * current_point.transpose ();
369+
covariance_matrix.noalias() += current_point * current_point.transpose ();
370370
}
371371

372372
covariance_matrix *= factor;
@@ -387,7 +387,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeCovarianceMatrix (PointCloudConst
387387
current_point (1) = (*cloud)[i_point].y - mean_value_ (1);
388388
current_point (2) = (*cloud)[i_point].z - mean_value_ (2);
389389

390-
covariance_matrix += current_point * current_point.transpose ();
390+
covariance_matrix.noalias() += current_point * current_point.transpose ();
391391
}
392392

393393
covariance_matrix *= factor;

features/include/pcl/features/impl/principal_curvatures.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computePointPr
7878
for (std::size_t idx = 0; idx < indices.size(); ++idx)
7979
{
8080
const auto normal = normals[indices[idx]].getNormalVector3fMap();
81-
projected_normals[idx] = M * normal;
81+
projected_normals[idx].noalias() = M * normal;
8282
xyz_centroid += projected_normals[idx];
8383
}
8484

features/include/pcl/features/impl/rops_estimation.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -275,9 +275,9 @@ pcl::ROPSEstimation <PointInT, PointOutT>::computeLRF (const PointInT& point, co
275275
for (const auto &i_pt : pt)
276276
{
277277
Eigen::Vector3f vec = i_pt - feature_point;
278-
curr_scatter_matrix += vec * (vec.transpose ());
278+
curr_scatter_matrix.noalias() += vec * (vec.transpose ());
279279
for (const auto &j_pt : pt)
280-
curr_scatter_matrix += vec * ((j_pt - feature_point).transpose ());
280+
curr_scatter_matrix.noalias() += vec * ((j_pt - feature_point).transpose ());
281281
}
282282
scatter_matrices.emplace_back (coeff * curr_scatter_matrix);
283283
}

features/include/pcl/features/impl/shot_lrf.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::getLocalRF (const i
7777
distance = search_parameter_ - sqrt (n_sqr_distances[i_idx]);
7878

7979
// Multiply vij * vij'
80-
cov_m += distance * (vij.row (valid_nn_points).head<3> ().transpose () * vij.row (valid_nn_points).head<3> ());
80+
cov_m.noalias() += distance * (vij.row (valid_nn_points).head<3> ().transpose () * vij.row (valid_nn_points).head<3> ());
8181

8282
sum += distance;
8383
valid_nn_points++;

features/include/pcl/features/our_cvfh.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,7 @@ namespace pcl
114114
homMatrix = transformPC.matrix ();
115115

116116
Eigen::Matrix4f trans_copy = trans.inverse ();
117-
trans = trans_copy * center_mat * homMatrix;
117+
trans.noalias() = trans_copy * center_mat * homMatrix;
118118
return trans;
119119
}
120120

0 commit comments

Comments
 (0)