Skip to content

Commit 009d73d

Browse files
authored
Change points.size() to size() to make transition to index_t easier (#4190)
* sed -i 's/\([^a-zA-Z0-9_]\)points.size/\1size/g' * Replace all casts for `width = EXPR size()` * Format string changes * Auto * Range based for loop * OpenMP doesn't like range for loop
1 parent 6eaa806 commit 009d73d

File tree

374 files changed

+2205
-2083
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

374 files changed

+2205
-2083
lines changed

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/cvfh_estimator.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ class CVFHEstimation : public GlobalEstimator<PointInT, FeatureT> {
131131

132132
cvfh.compute(cvfh_signatures);
133133

134-
for (std::size_t i = 0; i < cvfh_signatures.points.size(); i++) {
134+
for (std::size_t i = 0; i < cvfh_signatures.size(); i++) {
135135
pcl::PointCloud<FeatureT> vfh_signature;
136136
vfh_signature.points.resize(1);
137137
vfh_signature.width = vfh_signature.height = 1;
@@ -155,7 +155,7 @@ class CVFHEstimation : public GlobalEstimator<PointInT, FeatureT> {
155155
{
156156
normalize_bins_ = b;
157157
}
158-
};
158+
}; // namespace rec_3d_framework
159159

160160
} // namespace rec_3d_framework
161161
} // namespace pcl

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/colorshot_local_estimator.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ class ColorSHOTLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
5555
// compute keypoints
5656
computeKeypoints(processed, keypoints, normals);
5757

58-
if (keypoints->points.size() == 0) {
58+
if (keypoints->size() == 0) {
5959
PCL_WARN("ColorSHOTLocalEstimation :: No keypoints were found\n");
6060
return false;
6161
}
@@ -73,13 +73,13 @@ class ColorSHOTLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
7373
shot_estimate.setSearchSurface(processed);
7474
shot_estimate.setRadiusSearch(support_radius_);
7575
shot_estimate.compute(*shots);
76-
signatures->resize(shots->points.size());
77-
signatures->width = static_cast<int>(shots->points.size());
76+
signatures->resize(shots->size());
77+
signatures->width = shots->size();
7878
signatures->height = 1;
7979

8080
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
8181

82-
for (std::size_t k = 0; k < shots->points.size(); k++)
82+
for (std::size_t k = 0; k < shots->size(); k++)
8383
for (int i = 0; i < size_feat; i++)
8484
(*signatures)[k].histogram[i] = (*shots)[k].descriptor[i];
8585

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/fpfh_local_estimator.h

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -50,15 +50,14 @@ class FPFHLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
5050
normal_estimator_->estimate(in, processed, normals);
5151

5252
this->computeKeypoints(processed, keypoints, normals);
53-
std::cout << " " << normals->points.size() << " " << processed->points.size()
54-
<< std::endl;
53+
std::cout << " " << normals->size() << " " << processed->size() << std::endl;
5554

5655
if (keypoints->points.empty()) {
5756
PCL_WARN("FPFHLocalEstimation :: No keypoints were found\n");
5857
return false;
5958
}
6059

61-
assert(processed->points.size() == normals->points.size());
60+
assert(processed->size() == normals->size());
6261

6362
// compute signatures
6463
using FPFHEstimator =
@@ -75,12 +74,12 @@ class FPFHLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
7574
fpfh_estimate.setRadiusSearch(support_radius_);
7675
fpfh_estimate.compute(*fpfhs);
7776

78-
signatures->resize(fpfhs->points.size());
79-
signatures->width = static_cast<int>(fpfhs->points.size());
77+
signatures->resize(fpfhs->size());
78+
signatures->width = fpfhs->size();
8079
signatures->height = 1;
8180

8281
int size_feat = 33;
83-
for (std::size_t k = 0; k < fpfhs->points.size(); k++)
82+
for (std::size_t k = 0; k < fpfhs->size(); k++)
8483
for (int i = 0; i < size_feat; i++)
8584
(*signatures)[k].histogram[i] = (*fpfhs)[k].histogram[i];
8685

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/fpfh_local_estimator_omp.h

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -51,15 +51,14 @@ class FPFHLocalEstimationOMP : public LocalEstimator<PointInT, FeatureT> {
5151

5252
// compute keypoints
5353
computeKeypoints(processed, keypoints, normals);
54-
std::cout << " " << normals->points.size() << " " << processed->points.size()
55-
<< std::endl;
54+
std::cout << " " << normals->size() << " " << processed->size() << std::endl;
5655

57-
if (keypoints->points.size() == 0) {
56+
if (keypoints->size() == 0) {
5857
PCL_WARN("FPFHLocalEstimation :: No keypoints were found\n");
5958
return false;
6059
}
6160

62-
assert(processed->points.size() == normals->points.size());
61+
assert(processed->size() == normals->size());
6362

6463
// compute signatures
6564
using FPFHEstimator =
@@ -77,12 +76,12 @@ class FPFHLocalEstimationOMP : public LocalEstimator<PointInT, FeatureT> {
7776
fpfh_estimate.setRadiusSearch(support_radius_);
7877
fpfh_estimate.compute(*fpfhs);
7978

80-
signatures->resize(fpfhs->points.size());
81-
signatures->width = static_cast<int>(fpfhs->points.size());
79+
signatures->resize(fpfhs->size());
80+
signatures->width = fpfhs->size();
8281
signatures->height = 1;
8382

8483
int size_feat = 33;
85-
for (std::size_t k = 0; k < fpfhs->points.size(); k++)
84+
for (std::size_t k = 0; k < fpfhs->size(); k++)
8685
for (int i = 0; i < size_feat; i++)
8786
(*signatures)[k].histogram[i] = (*fpfhs)[k].histogram[i];
8887

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/local_estimator.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -93,14 +93,14 @@ class UniformSamplingExtractor : public KeypointExtractor<PointInT> {
9393
tree->setInputCloud(input);
9494

9595
neighborhood_indices_.reset(new std::vector<std::vector<int>>);
96-
neighborhood_indices_->resize(keypoints_cloud->points.size());
96+
neighborhood_indices_->resize(keypoints_cloud->size());
9797
neighborhood_dist_.reset(new std::vector<std::vector<float>>);
98-
neighborhood_dist_->resize(keypoints_cloud->points.size());
98+
neighborhood_dist_->resize(keypoints_cloud->size());
9999

100-
filtered_keypoints.points.resize(keypoints_cloud->points.size());
100+
filtered_keypoints.points.resize(keypoints_cloud->size());
101101
int good = 0;
102102

103-
for (std::size_t i = 0; i < keypoints_cloud->points.size(); i++) {
103+
for (std::size_t i = 0; i < keypoints_cloud->size(); i++) {
104104

105105
if (tree->radiusSearch((*keypoints_cloud)[i],
106106
radius_,
@@ -215,7 +215,7 @@ class SIFTSurfaceKeypointExtractor : public KeypointExtractor<PointInT> {
215215
void
216216
compute(PointInTPtr& keypoints)
217217
{
218-
if (normals_ == 0 || (normals_->points.size() != input_->points.size()))
218+
if (normals_ == 0 || (normals_->size() != input_->size()))
219219
PCL_WARN("SIFTSurfaceKeypointExtractor -- Normals are not valid\n");
220220

221221
keypoints.reset(new pcl::PointCloud<PointInT>);
@@ -297,7 +297,7 @@ class HarrisKeypointExtractor : public KeypointExtractor<PointInT> {
297297
{
298298
keypoints.reset(new pcl::PointCloud<PointInT>);
299299

300-
if (normals_ == 0 || (normals_->points.size() != input_->points.size()))
300+
if (normals_ == 0 || (normals_->size() != input_->size()))
301301
PCL_WARN("HarrisKeypointExtractor -- Normals are not valid\n");
302302

303303
typename pcl::PointCloud<pcl::PointXYZI>::Ptr intensity_keypoints(
@@ -346,7 +346,7 @@ class SUSANKeypointExtractor : public KeypointExtractor<PointInT> {
346346
{
347347
keypoints.reset(new pcl::PointCloud<PointInT>);
348348

349-
if (normals_ == 0 || (normals_->points.size() != input_->points.size()))
349+
if (normals_ == 0 || (normals_->size() != input_->size()))
350350
PCL_WARN("SUSANKeypointExtractor -- Normals are not valid\n");
351351

352352
typename pcl::PointCloud<pcl::PointXYZI>::Ptr intensity_keypoints(

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/shot_local_estimator.h

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -84,16 +84,15 @@ class SHOTLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
8484

8585
// compute keypoints
8686
this->computeKeypoints(processed, keypoints, normals);
87-
std::cout << " " << normals->points.size() << " " << processed->points.size()
88-
<< std::endl;
87+
std::cout << " " << normals->size() << " " << processed->size() << std::endl;
8988

9089
if (keypoints->points.empty()) {
9190
PCL_WARN("SHOTLocalEstimation :: No keypoints were found\n");
9291
return false;
9392
}
9493

95-
std::cout << keypoints->points.size() << " " << normals->points.size() << " "
96-
<< processed->points.size() << std::endl;
94+
std::cout << keypoints->size() << " " << normals->size() << " " << processed->size()
95+
<< std::endl;
9796
// compute signatures
9897
using SHOTEstimator = pcl::SHOTEstimation<PointInT, pcl::Normal, pcl::SHOT352>;
9998
typename pcl::search::KdTree<PointInT>::Ptr tree(new pcl::search::KdTree<PointInT>);
@@ -107,13 +106,13 @@ class SHOTLocalEstimation : public LocalEstimator<PointInT, FeatureT> {
107106
shot_estimate.setInputNormals(normals);
108107
shot_estimate.setRadiusSearch(support_radius_);
109108
shot_estimate.compute(*shots);
110-
signatures->resize(shots->points.size());
111-
signatures->width = static_cast<int>(shots->points.size());
109+
signatures->resize(shots->size());
110+
signatures->width = shots->size();
112111
signatures->height = 1;
113112

114113
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
115114

116-
for (std::size_t k = 0; k < shots->points.size(); k++)
115+
for (std::size_t k = 0; k < shots->size(); k++)
117116
for (int i = 0; i < size_feat; i++)
118117
(*signatures)[k].histogram[i] = (*shots)[k].descriptor[i];
119118

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/local/shot_local_estimator_omp.h

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -85,8 +85,7 @@ class SHOTLocalEstimationOMP : public LocalEstimator<PointInT, FeatureT> {
8585
}
8686

8787
this->computeKeypoints(processed, keypoints, normals);
88-
std::cout << " " << normals->points.size() << " " << processed->points.size()
89-
<< std::endl;
88+
std::cout << " " << normals->size() << " " << processed->size() << std::endl;
9089

9190
if (keypoints->points.empty()) {
9291
PCL_WARN("SHOTLocalEstimationOMP :: No keypoints were found\n");
@@ -112,8 +111,8 @@ class SHOTLocalEstimationOMP : public LocalEstimator<PointInT, FeatureT> {
112111
shot_estimate.compute(*shots);
113112
}
114113

115-
signatures->resize(shots->points.size());
116-
signatures->width = static_cast<int>(shots->points.size());
114+
signatures->resize(shots->size());
115+
signatures->width = shots->size();
117116
signatures->height = 1;
118117

119118
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
@@ -135,7 +134,6 @@ class SHOTLocalEstimationOMP : public LocalEstimator<PointInT, FeatureT> {
135134
good++;
136135
}
137136
}
138-
139137
signatures->resize(good);
140138
signatures->width = good;
141139

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h

Lines changed: 11 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ class PreProcessorAndNormalEstimator {
3434
std::vector<int> src_indices;
3535

3636
float sum_distances = 0.0;
37-
std::vector<float> avg_distances(input->points.size());
37+
std::vector<float> avg_distances(input->size());
3838
// Iterate through the source data set
39-
for (std::size_t i = 0; i < input->points.size(); ++i) {
39+
for (std::size_t i = 0; i < input->size(); ++i) {
4040
tree->nearestKSearch((*input)[i], 9, nn_indices, nn_distances);
4141

4242
float avg_dist_neighbours = 0.0;
@@ -187,17 +187,16 @@ class PreProcessorAndNormalEstimator {
187187
// check nans before computing normals
188188
{
189189
pcl::ScopeTime t("check nans...");
190-
int j = 0;
191-
for (std::size_t i = 0; i < out->points.size(); ++i) {
192-
if (!std::isfinite((*out)[i].x) || !std::isfinite((*out)[i].y) ||
193-
!std::isfinite((*out)[i].z))
190+
std::size_t j = 0;
191+
for (const auto& point : *out) {
192+
if (!isXYZFinite(point))
194193
continue;
195194

196-
(*out)[j] = (*out)[i];
195+
(*out)[j] = point;
197196
j++;
198197
}
199198

200-
if (j != static_cast<int>(out->points.size())) {
199+
if (j != static_cast<int>(out->size())) {
201200
PCL_ERROR("Contain nans...");
202201
}
203202

@@ -223,10 +222,8 @@ class PreProcessorAndNormalEstimator {
223222
if (!out->isOrganized()) {
224223
pcl::ScopeTime t("check nans...");
225224
int j = 0;
226-
for (std::size_t i = 0; i < normals->points.size(); ++i) {
227-
if (!std::isfinite((*normals)[i].normal_x) ||
228-
!std::isfinite((*normals)[i].normal_y) ||
229-
!std::isfinite((*normals)[i].normal_z))
225+
for (std::size_t i = 0; i < normals->size(); ++i) {
226+
if (!isNormalFinite((*normals)[i]))
230227
continue;
231228

232229
(*normals)[j] = (*normals)[i];
@@ -246,10 +243,8 @@ class PreProcessorAndNormalEstimator {
246243
// is is organized, we set the xyz points to NaN
247244
pcl::ScopeTime t("check nans organized...");
248245
bool NaNs = false;
249-
for (std::size_t i = 0; i < normals->points.size(); ++i) {
250-
if (std::isfinite((*normals)[i].normal_x) &&
251-
std::isfinite((*normals)[i].normal_y) &&
252-
std::isfinite((*normals)[i].normal_z))
246+
for (std::size_t i = 0; i < normals->size(); ++i) {
247+
if (!isNormalFinite((*normals)[i]))
253248
continue;
254249

255250
NaNs = true;

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -396,7 +396,7 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::init
396396
std::mt19937 rng(rd());
397397
std::normal_distribution<float> nd(0.0f, noise_);
398398
// Noisify each point in the dataset
399-
for (std::size_t cp = 0; cp < view->points.size(); ++cp)
399+
for (std::size_t cp = 0; cp < view->size(); ++cp)
400400
(*view)[cp].z += nd(rng);
401401
}
402402

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -591,7 +591,7 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::ini
591591
std::mt19937 rng(rd());
592592
std::normal_distribution<float> nd(0.0f, noise_);
593593
// Noisify each point in the dataset
594-
for (std::size_t cp = 0; cp < view->points.size(); ++cp)
594+
for (std::size_t cp = 0; cp < view->size(); ++cp)
595595
(*view)[cp].z += nd(rng);
596596
}
597597

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
6767

6868
int size_feat = sizeof((*signature)[0].histogram) / sizeof(float);
6969

70-
for (std::size_t dd = 0; dd < signature->points.size(); dd++) {
70+
for (std::size_t dd = 0; dd < signature->size(); dd++) {
7171
descr_model.keypoint_id = static_cast<int>(dd);
7272
descr_model.descr.resize(size_feat);
7373

@@ -208,7 +208,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
208208
PointInTPtr keypoints_pointcloud;
209209

210210
if (signatures_ != nullptr && processed_ != nullptr &&
211-
(signatures_->size() == keypoints_pointcloud->points.size())) {
211+
(signatures_->size() == keypoints_pointcloud->size())) {
212212
keypoints_pointcloud = keypoints_input_;
213213
signatures = signatures_;
214214
processed = processed_;
@@ -228,15 +228,14 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
228228
processed_ = processed;
229229
}
230230

231-
std::cout << "Number of keypoints:" << keypoints_pointcloud->points.size()
232-
<< std::endl;
231+
std::cout << "Number of keypoints:" << keypoints_pointcloud->size() << std::endl;
233232

234233
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
235234

236235
// feature matching and object hypotheses
237236
std::map<std::string, ObjectHypothesis> object_hypotheses;
238237
{
239-
for (std::size_t idx = 0; idx < signatures->points.size(); idx++) {
238+
for (std::size_t idx = 0; idx < signatures->size(); idx++) {
240239
float* hist = (*signatures)[idx].histogram;
241240
std::vector<float> std_hist(hist, hist + size_feat);
242241
flann_model histogram;
@@ -271,7 +270,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
271270
ObjectHypothesis oh = (*it_map).second;
272271
oh.correspondences_pointcloud->points.push_back(model_keypoint);
273272
oh.correspondences_to_inputcloud->push_back(pcl::Correspondence(
274-
static_cast<int>(oh.correspondences_pointcloud->points.size() - 1),
273+
static_cast<int>(oh.correspondences_pointcloud->size() - 1),
275274
static_cast<int>(idx),
276275
distances[0][0]));
277276
oh.feature_distances_->push_back(distances[0][0]);

apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -107,8 +107,8 @@ uniform_sampling(const vtkSmartPointer<vtkPolyData>& polydata,
107107
cumulativeAreas[i] = totalArea;
108108
}
109109

110-
cloud_out.points.resize(n_samples);
111-
cloud_out.width = static_cast<int>(n_samples);
110+
cloud_out.resize(n_samples);
111+
cloud_out.width = n_samples;
112112
cloud_out.height = 1;
113113

114114
for (auto& point : cloud_out) {
@@ -157,8 +157,8 @@ getVerticesAsPointCloud(const vtkSmartPointer<vtkPolyData>& polydata,
157157
pcl::PointCloud<pcl::PointXYZ>& cloud_out)
158158
{
159159
vtkPoints* points = polydata->GetPoints();
160-
cloud_out.points.resize(points->GetNumberOfPoints());
161-
cloud_out.width = static_cast<int>(cloud_out.points.size());
160+
cloud_out.resize(points->GetNumberOfPoints());
161+
cloud_out.width = cloud_out.size();
162162
cloud_out.height = 1;
163163
cloud_out.is_dense = false;
164164

0 commit comments

Comments
 (0)