Skip to content

Commit a8b8501

Browse files
committed
Use PointCloud::operator [] instead of PointCloud::points::operator []
1 parent 5b3bc8c commit a8b8501

File tree

447 files changed

+4618
-4626
lines changed

Some content is hidden

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

447 files changed

+4618
-4626
lines changed

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -138,7 +138,7 @@ namespace pcl
138138
{
139139
pcl::PointCloud<FeatureT> vfh_signature (1);
140140
for (int d = 0; d < 308; ++d)
141-
vfh_signature.points[0].histogram[d] = cvfh_signatures.points[i].histogram[d];
141+
vfh_signature[0].histogram[d] = cvfh_signatures[i].histogram[d];
142142

143143
signatures.push_back (vfh_signature);
144144
}

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,7 @@ namespace pcl
170170
{
171171
pcl::PointCloud<FeatureT> vfh_signature (1);
172172
for (int d = 0; d < 308; ++d)
173-
vfh_signature.points[0].histogram[d] = cvfh_signatures.points[i].histogram[d];
173+
vfh_signature[0].histogram[d] = cvfh_signatures[i].histogram[d];
174174

175175
signatures.push_back (vfh_signature);
176176
}

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -77,11 +77,11 @@ namespace pcl
7777
signatures->width = static_cast<int> (shots->size ());
7878
signatures->height = 1;
7979

80-
int size_feat = sizeof(signatures->points[0].histogram) / sizeof(float);
80+
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
8181

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

8686
return true;
8787

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ namespace pcl
8080
int size_feat = 33;
8181
for (size_t k = 0; k < fpfhs->size (); k++)
8282
for (int i = 0; i < size_feat; i++)
83-
signatures->points[k].histogram[i] = fpfhs->points[k].histogram[i];
83+
(*signatures)[k].histogram[i] = (*fpfhs)[k].histogram[i];
8484

8585
return true;
8686

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ namespace pcl
8282
int size_feat = 33;
8383
for (size_t k = 0; k < fpfhs->size (); k++)
8484
for (int i = 0; i < size_feat; i++)
85-
signatures->points[k].histogram[i] = fpfhs->points[k].histogram[i];
85+
(*signatures)[k].histogram[i] = (*fpfhs)[k].histogram[i];
8686

8787
return true;
8888

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ namespace pcl
126126
if ((fabs (eigenValues[0] - eigenValues[1]) < 1.5e-4) || (eigsum != 0 && fabs (eigenValues[0] / eigsum) > 1.e-2))
127127
{
128128
//region is not planar, add to filtered keypoint
129-
keypoints_cloud->points[good] = keypoints_cloud->points[i];
129+
(*keypoints_cloud)[good] = (*keypoints_cloud)[i];
130130
good++;
131131
}
132132
}
@@ -227,8 +227,8 @@ namespace pcl
227227
typename pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud (new pcl::PointCloud<pcl::PointNormal> (input_->width, input_->height));
228228
for (size_t i = 0; i < input_->size (); i++)
229229
{
230-
input_cloud->points[i].getVector3fMap () = input_->points[i].getVector3fMap ();
231-
input_cloud->points[i].getNormalVector3fMap () = normals_->points[i].getNormalVector3fMap ();
230+
(*input_cloud)[i].getVector3fMap () = (*input_)[i].getVector3fMap ();
231+
(*input_cloud)[i].getNormalVector3fMap () = (*normals_)[i].getNormalVector3fMap ();
232232
}
233233

234234
typename pcl::PointCloud<pcl::PointXYZI>::Ptr intensity_keypoints (new pcl::PointCloud<pcl::PointXYZI>);
@@ -501,7 +501,7 @@ namespace pcl
501501
if ((fabs (eigenValues[0] - eigenValues[1]) < 1.5e-4) || (eigsum != 0 && fabs (eigenValues[0] / eigsum) > 1.e-2))
502502
{
503503
//region is not planar, add to filtered keypoint
504-
keypoints_cloud.points[good] = keypoints_cloud.points[i];
504+
keypoints_cloud[good] = keypoints_cloud[i];
505505
good++;
506506
}
507507
}

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -124,11 +124,11 @@ namespace pcl
124124
signatures->width = static_cast<int> (shots->size ());
125125
signatures->height = 1;
126126

127-
int size_feat = sizeof(signatures->points[0].histogram) / sizeof(float);
127+
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
128128

129129
for (size_t k = 0; k < shots->size (); k++)
130130
for (int i = 0; i < size_feat; i++)
131-
signatures->points[k].histogram[i] = shots->points[k].descriptor[i];
131+
(*signatures)[k].histogram[i] = (*shots)[k].descriptor[i];
132132

133133
return true;
134134

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ namespace pcl
118118
signatures->width = static_cast<int> (shots->size ());
119119
signatures->height = 1;
120120

121-
int size_feat = sizeof(signatures->points[0].histogram) / sizeof(float);
121+
int size_feat = sizeof((*signatures)[0].histogram) / sizeof(float);
122122

123123
int good = 0;
124124
for (size_t k = 0; k < shots->size (); k++)
@@ -127,15 +127,15 @@ namespace pcl
127127
int NaNs = 0;
128128
for (int i = 0; i < size_feat; i++)
129129
{
130-
if (!pcl_isfinite(shots->points[k].descriptor[i]))
130+
if (!pcl_isfinite((*shots)[k].descriptor[i]))
131131
NaNs++;
132132
}
133133

134134
if (NaNs == 0)
135135
{
136136
for (int i = 0; i < size_feat; i++)
137137
{
138-
signatures->points[good].histogram[i] = shots->points[k].descriptor[i];
138+
(*signatures)[good].histogram[i] = (*shots)[k].descriptor[i];
139139
}
140140

141141
good++;

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

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ namespace pcl
4040
// Iterate through the source data set
4141
for (size_t i = 0; i < input->size (); ++i)
4242
{
43-
tree->nearestKSearch (input->points[i], 9, nn_indices, nn_distances);
43+
tree->nearestKSearch ((*input)[i], 9, nn_indices, nn_distances);
4444

4545
float avg_dist_neighbours = 0.0;
4646
for (size_t j = 1; j < nn_indices.size (); j++)
@@ -207,10 +207,10 @@ namespace pcl
207207
int j = 0;
208208
for (size_t i = 0; i < out->size (); ++i)
209209
{
210-
if (!pcl_isfinite (out->points[i].x) || !pcl_isfinite (out->points[i].y) || !pcl_isfinite (out->points[i].z))
210+
if (!pcl_isfinite ((*out)[i].x) || !pcl_isfinite ((*out)[i].y) || !pcl_isfinite ((*out)[i].z))
211211
continue;
212212

213-
out->points[j] = out->points[i];
213+
(*out)[j] = (*out)[i];
214214
j++;
215215
}
216216

@@ -242,12 +242,12 @@ namespace pcl
242242
int j = 0;
243243
for (size_t i = 0; i < normals->size (); ++i)
244244
{
245-
if (!pcl_isfinite (normals->points[i].normal_x) || !pcl_isfinite (normals->points[i].normal_y)
246-
|| !pcl_isfinite (normals->points[i].normal_z))
245+
if (!pcl_isfinite ((*normals)[i].normal_x) || !pcl_isfinite ((*normals)[i].normal_y)
246+
|| !pcl_isfinite ((*normals)[i].normal_z))
247247
continue;
248248

249-
normals->points[j] = normals->points[i];
250-
out->points[j] = out->points[i];
249+
(*normals)[j] = (*normals)[i];
250+
(*out)[j] = (*out)[i];
251251
j++;
252252
}
253253

@@ -261,13 +261,13 @@ namespace pcl
261261
bool NaNs = false;
262262
for (size_t i = 0; i < normals->size (); ++i)
263263
{
264-
if (pcl_isfinite (normals->points[i].normal_x) && pcl_isfinite (normals->points[i].normal_y)
265-
&& pcl_isfinite (normals->points[i].normal_z))
264+
if (pcl_isfinite ((*normals)[i].normal_x) && pcl_isfinite ((*normals)[i].normal_y)
265+
&& pcl_isfinite ((*normals)[i].normal_z))
266266
continue;
267267

268268
NaNs = true;
269269

270-
out->points[i].x = out->points[i].y = out->points[i].z = std::numeric_limits<float>::quiet_NaN ();
270+
(*out)[i].x = (*out)[i].y = (*out)[i].z = std::numeric_limits<float>::quiet_NaN ();
271271
}
272272

273273
if (NaNs)
@@ -280,9 +280,9 @@ namespace pcl
280280
/*for (size_t i = 0; i < out->size (); i++)
281281
{
282282
int r, g, b;
283-
r = static_cast<int> (out->points[i].r);
284-
g = static_cast<int> (out->points[i].g);
285-
b = static_cast<int> (out->points[i].b);
283+
r = static_cast<int> ((*out)[i].r);
284+
g = static_cast<int> ((*out)[i].g);
285+
b = static_cast<int> ((*out)[i].b);
286286
std::cout << "in normal estimator:" << r << " " << g << " " << b << std::endl;
287287
}*/
288288
}

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,9 +40,9 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
4040

4141
flann_model descr_model;
4242
descr_model.first = models->at (i);
43-
int size_feat = sizeof(signature->points[0].histogram) / sizeof(float);
43+
int size_feat = sizeof((*signature)[0].histogram) / sizeof(float);
4444
descr_model.second.resize (size_feat);
45-
memcpy (&descr_model.second[0], &signature->points[0].histogram[0], size_feat * sizeof(float));
45+
memcpy (&descr_model.second[0], &(*signature)[0].histogram[0], size_feat * sizeof(float));
4646

4747
flann_models_.push_back (descr_model);
4848
}
@@ -101,8 +101,8 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
101101
{
102102
for (size_t idx = 0; idx < signatures.size (); idx++)
103103
{
104-
float* hist = signatures[idx].points[0].histogram;
105-
int size_feat = sizeof(signatures[idx].points[0].histogram) / sizeof(float);
104+
float* hist = signatures[idx][0].histogram;
105+
int size_feat = sizeof(signatures[idx][0].histogram) / sizeof(float);
106106
std::vector<float> std_hist (hist, hist + size_feat);
107107
ModelT empty;
108108

0 commit comments

Comments
 (0)