Skip to content

Commit

Permalink
Merge pull request #3426 from kunaltyagi/std_size
Browse files Browse the repository at this point in the history
Replace `size_t` with `std::size_t`
  • Loading branch information
SergioRAgostinho authored Oct 21, 2019
2 parents 436697c + 009d649 commit 8eb4768
Show file tree
Hide file tree
Showing 758 changed files with 4,742 additions and 4,692 deletions.
10 changes: 5 additions & 5 deletions 2d/include/pcl/2d/impl/edge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ pcl::Edge<PointInT, PointOutT>::detectEdgeSobel(pcl::PointCloud<PointOutT>& outp
output.height = height;
output.width = width;

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
output[i].magnitude_x = (*magnitude_x)[i].intensity;
output[i].magnitude_y = (*magnitude_y)[i].intensity;
output[i].magnitude =
Expand Down Expand Up @@ -110,7 +110,7 @@ pcl::Edge<PointInT, PointOutT>::sobelMagnitudeDirection(
output.height = height;
output.width = width;

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
output[i].magnitude_x = (*magnitude_x)[i].intensity;
output[i].magnitude_y = (*magnitude_y)[i].intensity;
output[i].magnitude =
Expand Down Expand Up @@ -149,7 +149,7 @@ pcl::Edge<PointInT, PointOutT>::detectEdgePrewitt(pcl::PointCloud<PointOutT>& ou
output.height = height;
output.width = width;

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
output[i].magnitude_x = (*magnitude_x)[i].intensity;
output[i].magnitude_y = (*magnitude_y)[i].intensity;
output[i].magnitude =
Expand Down Expand Up @@ -188,7 +188,7 @@ pcl::Edge<PointInT, PointOutT>::detectEdgeRoberts(pcl::PointCloud<PointOutT>& ou
output.height = height;
output.width = width;

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
output[i].magnitude_x = (*magnitude_x)[i].intensity;
output[i].magnitude_y = (*magnitude_y)[i].intensity;
output[i].magnitude =
Expand Down Expand Up @@ -369,7 +369,7 @@ pcl::Edge<PointInT, PointOutT>::detectEdgeCanny(pcl::PointCloud<PointOutT>& outp
}

// Final thresholding
for (size_t i = 0; i < input_->size(); ++i) {
for (std::size_t i = 0; i < input_->size(); ++i) {
if ((*maxima)[i].intensity == std::numeric_limits<float>::max())
output[i].magnitude = 255;
else
Expand Down
4 changes: 2 additions & 2 deletions 2d/include/pcl/2d/impl/kernel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ pcl::kernel<PointT>::gaussianKernel(pcl::PointCloud<PointT>& kernel)
}

// Normalizing the kernel
for (size_t i = 0; i < kernel.size(); ++i)
for (std::size_t i = 0; i < kernel.size(); ++i)
kernel[i].intensity /= sum;
}

Expand Down Expand Up @@ -140,7 +140,7 @@ pcl::kernel<PointT>::loGKernel(pcl::PointCloud<PointT>& kernel)
}

// Normalizing the kernel
for (size_t i = 0; i < kernel.size(); ++i)
for (std::size_t i = 0; i < kernel.size(); ++i)
kernel[i].intensity /= sum;
}

Expand Down
40 changes: 20 additions & 20 deletions 2d/include/pcl/2d/impl/keypoint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,12 +84,12 @@ pcl::keypoint::harrisCorner(ImageType& output,
conv_2d.convolve(M11, kernel_i, I_y2);

/*harris function*/
const size_t height = input.size();
const size_t width = input[0].size();
const std::size_t height = input.size();
const std::size_t width = input[0].size();
output.resize(height);
for (size_t i = 0; i < height; i++) {
for (std::size_t i = 0; i < height; i++) {
output[i].resize(width);
for (size_t j = 0; j < width; j++) {
for (std::size_t j = 0; j < width; j++) {
output[i][j] = M00[i][j] * M11[i][j] - (M10[i][j] * M10[i][j]) -
alpha * ((M00[i][j] + M11[i][j]) * (M00[i][j] + M11[i][j]));
if (thresh != 0) {
Expand All @@ -102,8 +102,8 @@ pcl::keypoint::harrisCorner(ImageType& output,
}

/*local maxima*/
for (size_t i = 1; i < height - 1; i++) {
for (size_t j = 1; j < width - 1; j++) {
for (std::size_t i = 1; i < height - 1; i++) {
for (std::size_t j = 1; j < width - 1; j++) {
if (output[i][j] > output[i - 1][j - 1] && output[i][j] > output[i - 1][j] &&
output[i][j] > output[i - 1][j + 1] && output[i][j] > output[i][j - 1] &&
output[i][j] > output[i][j + 1] && output[i][j] > output[i + 1][j - 1] &&
Expand Down Expand Up @@ -141,14 +141,14 @@ pcl::keypoint::hessianBlob(ImageType& output,
edge_detection.ComputeDerivativeYCentral(I_xy, I_x);
edge_detection.ComputeDerivativeYCentral(I_yy, I_y);
/*Determinant of Hessian*/
const size_t height = input.size();
const size_t width = input[0].size();
const std::size_t height = input.size();
const std::size_t width = input[0].size();
float min = std::numeric_limits<float>::max();
float max = std::numeric_limits<float>::min();
cornerness.resize(height);
for (size_t i = 0; i < height; i++) {
for (std::size_t i = 0; i < height; i++) {
cornerness[i].resize(width);
for (size_t j = 0; j < width; j++) {
for (std::size_t j = 0; j < width; j++) {
cornerness[i][j] =
sigma * sigma * (I_xx[i][j] + I_yy[i][j] - I_xy[i][j] * I_xy[i][j]);
if (SCALED) {
Expand All @@ -163,9 +163,9 @@ pcl::keypoint::hessianBlob(ImageType& output,
output.resize(height);
output[0].resize(width);
output[height - 1].resize(width);
for (size_t i = 1; i < height - 1; i++) {
for (std::size_t i = 1; i < height - 1; i++) {
output[i].resize(width);
for (size_t j = 1; j < width - 1; j++) {
for (std::size_t j = 1; j < width - 1; j++) {
if (SCALED)
output[i][j] = ((cornerness[i][j] - min) / (max - min));
else
Expand All @@ -183,8 +183,8 @@ pcl::keypoint::hessianBlob(ImageType& output,
const float scaling_factor,
const int num_scales)
{
const size_t height = input.size();
const size_t width = input[0].size();
const std::size_t height = input.size();
const std::size_t width = input[0].size();
const int local_search_radius = 1;
float scale = start_scale;
std::vector<ImageType> cornerness;
Expand All @@ -195,8 +195,8 @@ pcl::keypoint::hessianBlob(ImageType& output,
}
bool non_max_flag = false;
float scale_max, local_max;
for (size_t i = 0; i < height; i++) {
for (size_t j = 0; j < width; j++) {
for (std::size_t i = 0; i < height; i++) {
for (std::size_t j = 0; j < width; j++) {
scale_max = std::numeric_limits<float>::min();
/*default output in case of no blob at the current point is 0*/
output[i][j] = 0;
Expand Down Expand Up @@ -245,12 +245,12 @@ pcl::keypoint::imageElementMultiply(ImageType& output,
ImageType& input1,
ImageType& input2)
{
const size_t height = input1.size();
const size_t width = input1[0].size();
const std::size_t height = input1.size();
const std::size_t width = input1[0].size();
output.resize(height);
for (size_t i = 0; i < height; i++) {
for (std::size_t i = 0; i < height; i++) {
output[i].resize(width);
for (size_t j = 0; j < width; j++) {
for (std::size_t j = 0; j < width; j++) {
output[i][j] = input1[i][j] * input2[i][j];
}
}
Expand Down
8 changes: 4 additions & 4 deletions 2d/include/pcl/2d/impl/morphology.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ pcl::Morphology<PointT>::subtractionBinary(pcl::PointCloud<PointT>& output,
output.height = height;
output.resize(height * width);

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
if (input1[i].intensity == 1 && input2[i].intensity == 0)
output[i].intensity = 1;
else
Expand All @@ -303,7 +303,7 @@ pcl::Morphology<PointT>::unionBinary(pcl::PointCloud<PointT>& output,
output.height = height;
output.resize(height * width);

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
if (input1[i].intensity == 1 || input2[i].intensity == 1)
output[i].intensity = 1;
else
Expand All @@ -324,7 +324,7 @@ pcl::Morphology<PointT>::intersectionBinary(pcl::PointCloud<PointT>& output,
output.height = height;
output.resize(height * width);

for (size_t i = 0; i < output.size(); ++i) {
for (std::size_t i = 0; i < output.size(); ++i) {
if (input1[i].intensity == 1 && input2[i].intensity == 1)
output[i].intensity = 1;
else
Expand Down Expand Up @@ -363,7 +363,7 @@ pcl::Morphology<PointT>::structuringElementRectangle(pcl::PointCloud<PointT>& ke
kernel.height = height;
kernel.width = width;
kernel.resize(height * width);
for (size_t i = 0; i < kernel.size(); ++i)
for (std::size_t i = 0; i < kernel.size(); ++i)
kernel[i].intensity = 1;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ namespace pcl
crh.setInputCloud(processed);
crh.setInputNormals(normals_);

for (size_t idx = 0; idx < signatures.size (); idx++)
for (std::size_t idx = 0; idx < signatures.size (); idx++)
{
Eigen::Vector4f centroid4f(centroids[idx][0],centroids[idx][1],centroids[idx][2],0);
crh.setCentroid(centroid4f);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ namespace pcl

cvfh.compute (cvfh_signatures);

for (size_t i = 0; i < cvfh_signatures.points.size (); i++)
for (std::size_t i = 0; i < cvfh_signatures.points.size (); i++)
{
pcl::PointCloud<FeatureT> vfh_signature;
vfh_signature.points.resize (1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ namespace pcl

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

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ namespace pcl
signatures->height = 1;

int size_feat = 33;
for (size_t k = 0; k < fpfhs->points.size (); k++)
for (std::size_t k = 0; k < fpfhs->points.size (); k++)
for (int i = 0; i < size_feat; i++)
signatures->points[k].histogram[i] = fpfhs->points[k].histogram[i];

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ namespace pcl
signatures->height = 1;

int size_feat = 33;
for (size_t k = 0; k < fpfhs->points.size (); k++)
for (std::size_t k = 0; k < fpfhs->points.size (); k++)
for (int i = 0; i < size_feat; i++)
signatures->points[k].histogram[i] = fpfhs->points[k].histogram[i];

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ namespace pcl
filtered_keypoints.points.resize (keypoints_cloud->points.size ());
int good = 0;

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

if (tree->radiusSearch (keypoints_cloud->points[i], radius_, (*neighborhood_indices_)[good], (*neighborhood_dist_)[good]))
Expand Down Expand Up @@ -232,7 +232,7 @@ namespace pcl
input_cloud->width = input_->width;
input_cloud->height = input_->height;
input_cloud->points.resize (input_->width * input_->height);
for (size_t i = 0; i < input_->points.size (); i++)
for (std::size_t i = 0; i < input_->points.size (); i++)
{
input_cloud->points[i].getVector3fMap () = input_->points[i].getVector3fMap ();
input_cloud->points[i].getNormalVector3fMap () = normals_->points[i].getNormalVector3fMap ();
Expand Down Expand Up @@ -398,7 +398,7 @@ namespace pcl
computeKeypoints (PointInTPtr & cloud, PointInTPtr & keypoints, pcl::PointCloud<pcl::Normal>::Ptr & normals)
{
keypoints.reset (new pcl::PointCloud<PointInT>);
for (size_t i = 0; i < keypoint_extractor_.size (); i++)
for (std::size_t i = 0; i < keypoint_extractor_.size (); i++)
{
keypoint_extractor_[i]->setInputCloud (cloud);
if (keypoint_extractor_[i]->needNormals ())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ namespace pcl

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

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,12 @@ namespace pcl
float sum_distances = 0.0;
std::vector<float> avg_distances (input->points.size ());
// Iterate through the source data set
for (size_t i = 0; i < input->points.size (); ++i)
for (std::size_t i = 0; i < input->points.size (); ++i)
{
tree->nearestKSearch (input->points[i], 9, nn_indices, nn_distances);

float avg_dist_neighbours = 0.0;
for (size_t j = 1; j < nn_indices.size (); j++)
for (std::size_t j = 1; j < nn_indices.size (); j++)
avg_dist_neighbours += std::sqrt (nn_distances[j]);

avg_dist_neighbours /= static_cast<float> (nn_indices.size ());
Expand Down Expand Up @@ -203,7 +203,7 @@ namespace pcl
{
pcl::ScopeTime t ("check nans...");
int j = 0;
for (size_t i = 0; i < out->points.size (); ++i)
for (std::size_t i = 0; i < out->points.size (); ++i)
{
if (!std::isfinite (out->points[i].x) || !std::isfinite (out->points[i].y) || !std::isfinite (out->points[i].z))
continue;
Expand Down Expand Up @@ -239,7 +239,7 @@ namespace pcl
{
pcl::ScopeTime t ("check nans...");
int j = 0;
for (size_t i = 0; i < normals->points.size (); ++i)
for (std::size_t i = 0; i < normals->points.size (); ++i)
{
if (!std::isfinite (normals->points[i].normal_x) || !std::isfinite (normals->points[i].normal_y)
|| !std::isfinite (normals->points[i].normal_z))
Expand All @@ -263,7 +263,7 @@ namespace pcl
//is is organized, we set the xyz points to NaN
pcl::ScopeTime t ("check nans organized...");
bool NaNs = false;
for (size_t i = 0; i < normals->points.size (); ++i)
for (std::size_t i = 0; i < normals->points.size (); ++i)
{
if (std::isfinite (normals->points[i].normal_x) && std::isfinite (normals->points[i].normal_y)
&& std::isfinite (normals->points[i].normal_z))
Expand All @@ -281,7 +281,7 @@ namespace pcl
}
}

/*for (size_t i = 0; i < out->points.size (); i++)
/*for (std::size_t i = 0; i < out->points.size (); i++)
{
int r, g, b;
r = static_cast<int> (out->points[i].r);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,7 @@ namespace pcl
model.poses_.reset (new std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > ());
model.self_occlusions_.reset (new std::vector<float> ());

for (size_t i = 0; i < views_xyz_orig.size (); i++)
for (std::size_t i = 0; i < views_xyz_orig.size (); i++)
{
model.views_->push_back (views_xyz_orig[i]);
model.poses_->push_back (poses[i]);
Expand All @@ -222,7 +222,7 @@ namespace pcl
direc << dir << "/" << model.class_ << "/" << model.id_;
this->createClassAndModelDirectories (dir, model.class_, model.id_);

for (size_t i = 0; i < model.views_->size (); i++)
for (std::size_t i = 0; i < model.views_->size (); i++)
{
//save generated model for future use
std::stringstream path_view;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ namespace pcl

void
assembleModelFromViewsAndPoses(ModelT & model, std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > & poses) {
for(size_t i=0; i < model.views_->size(); i++) {
for(std::size_t i=0; i < model.views_->size(); i++) {
Eigen::Matrix4f inv = poses[i];
typename pcl::PointCloud<PointInT>::Ptr global_cloud(new pcl::PointCloud<PointInT>);
pcl::transformPointCloud(*(model.views_->at(i)),*global_cloud, inv);
Expand Down Expand Up @@ -143,7 +143,7 @@ namespace pcl

std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > poses_to_assemble_;

for (size_t i = 0; i < view_filenames.size (); i++)
for (std::size_t i = 0; i < view_filenames.size (); i++)
{
std::stringstream view_file;
view_file << pathmodel.str () << "/" << view_filenames[i];
Expand Down Expand Up @@ -214,7 +214,7 @@ namespace pcl
getViewsFilenames (model_dir, view_filenames);
std::cout << view_filenames.size () << std::endl;

for (size_t i = 0; i < view_filenames.size (); i++)
for (std::size_t i = 0; i < view_filenames.size (); i++)
{
std::stringstream view_file;
view_file << model_path << "/" << view_filenames[i];
Expand Down Expand Up @@ -312,7 +312,7 @@ namespace pcl

models_.reset (new std::vector<ModelT>);

for (size_t i = 0; i < files.size (); i++)
for (std::size_t i = 0; i < files.size (); i++)
{
ModelT m;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ namespace pcl
void
voxelizeAllModels (float resolution)
{
for (size_t i = 0; i < models_->size (); i++)
for (std::size_t i = 0; i < models_->size (); i++)
{
models_->at (i).getAssembled (resolution);
}
Expand Down
Loading

0 comments on commit 8eb4768

Please sign in to comment.