Skip to content

Commit

Permalink
Fixed most variableScope hints by CppCheck 1.86. Includes additional …
Browse files Browse the repository at this point in the history
…fixes, which are not detected by CppCheck (variableScope check seems to ignore loops and HPP files)
  • Loading branch information
Heiko Thiel committed Feb 1, 2019
1 parent ee3fe6f commit 2187ec0
Show file tree
Hide file tree
Showing 149 changed files with 1,323 additions and 2,474 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -128,13 +128,12 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
first_nn_category_ = flann_models_[indices_scores[0].idx_models_].first.class_;

std::map<std::string, int> category_map;
std::map<std::string, int>::iterator it;
int num_n = std::min (NN_, static_cast<int> (indices_scores.size ()));

for (int i = 0; i < num_n; ++i)
{
std::string cat = flann_models_[indices_scores[i].idx_models_].first.class_;
it = category_map.find (cat);
auto it = category_map.find (cat);
if (it == category_map.end ())
{
category_map[cat] = 1;
Expand All @@ -145,7 +144,7 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
}
}

for (it = category_map.begin (); it != category_map.end (); it++)
for (auto it = category_map.cbegin (); it != category_map.cend (); it++)
{
float prob = static_cast<float> (it->second) / static_cast<float> (num_n);
categories_.push_back (it->first);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -190,14 +190,12 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
//single categories...
if (use_single_categories_)
{
std::map<std::string, boost::shared_ptr<std::vector<int> > >::iterator it;

single_categories_data_.resize (single_categories.size ());
single_categories_index_.resize (single_categories.size ());
single_categories_pointers_to_models_.resize (single_categories.size ());

int kk = 0;
for (it = single_categories.begin (); it != single_categories.end (); it++)
for (auto it = single_categories.begin (); it != single_categories.end (); it++)
{
//create index and flann data
convertToFLANN (flann_models_, it->second, single_categories_data_[kk]);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -298,13 +298,9 @@ template<template<class > class Distance, typename PointInT, typename FeatureT>
}
}

typename std::map<std::string, ObjectHypothesis>::iterator it_map;

std::vector<float> feature_distance_avg;

{
//pcl::ScopeTime t("Geometric verification, RANSAC and transform estimation");
for (it_map = object_hypotheses.begin (); it_map != object_hypotheses.end (); it_map++)
for (auto it_map = object_hypotheses.cbegin (); it_map != object_hypotheses.cend (); it_map++)
{
std::vector < pcl::Correspondences > corresp_clusters;
cg_algorithm_->setSceneCloud (keypoints_pointcloud);
Expand Down
4 changes: 1 addition & 3 deletions apps/cloud_composer/src/items/cloud_item.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,10 +113,8 @@ pcl::cloud_composer::CloudItem::setTemplateCloudFromBlob ()
{
if (! template_cloud_set_ )
{
std::vector<pcl::PCLPointField>::iterator end = cloud_blob_ptr_->fields.end ();
std::vector<pcl::PCLPointField>::iterator itr = cloud_blob_ptr_->fields.begin ();
QStringList field_names;
for ( itr = cloud_blob_ptr_->fields.begin () ; itr != end; ++itr)
for (auto itr = cloud_blob_ptr_->fields.cbegin (), end = cloud_blob_ptr_->fields.cend (); itr != end; ++itr)
{
field_names.append (QString::fromStdString ( itr->name ));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,10 @@ pcl::cloud_composer::RectangularFrustumSelector::OnLeftButtonUp ()

vtkSmartPointer<vtkAppendPolyData> append = vtkAppendPolyData::New ();

pcl::visualization::CloudActorMap::iterator it;
it = actors_->begin ();
QMap < QString, vtkPolyData* > id_selected_data_map;
for (it = actors_->begin (); it != actors_->end (); ++it)
for (auto it = actors_->cbegin (); it != actors_->cend (); ++it)
{
pcl::visualization::CloudActor *act = &(*it).second;
const pcl::visualization::CloudActor *act = &(*it).second;
vtkMapper* mapper = act->actor->GetMapper ();
vtkDataSet* data = mapper->GetInput ();
vtkPolyData* poly_data = vtkPolyData::SafeDownCast (data);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,7 @@ pcl::cloud_composer::SelectedTrackballStyleInteractor::setSelectedActors ()
selected_cloud_ids.append (cloud_item->getId ());
}

pcl::visualization::CloudActorMap::iterator it;
for (it = actors_->begin (); it != actors_->end (); ++it)
for (auto it = actors_->cbegin (); it != actors_->cend (); ++it)
{
QString id = QString::fromStdString (it->first);
if (selected_cloud_ids.contains (id))
Expand Down
5 changes: 2 additions & 3 deletions apps/cloud_composer/src/signal_multiplexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,11 +109,10 @@ pcl::cloud_composer::SignalMultiplexer::setCurrentObject (QObject* newObject)
if (newObject == object)
return;

QList<Connection>::ConstIterator it;
for (it = connections.begin (); it != connections.end (); ++it)
for (auto it = connections.cbegin (); it != connections.cend (); ++it)
disconnect (*it);
object = newObject;
for (it = connections.begin (); it != connections.end (); ++it)
for (auto it = connections.cbegin (); it != connections.cend (); ++it)
connect (*it);

ProjectModel* model = dynamic_cast<ProjectModel*> (newObject);
Expand Down
6 changes: 2 additions & 4 deletions apps/in_hand_scanner/src/icp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,8 +404,7 @@ pcl::ihs::ICP::selectDataPoints (const CloudXYZRGBNormalConstPtr& cloud_data) co
const CloudNormalPtr cloud_data_out (new CloudNormal ());
cloud_data_out->reserve (cloud_data->size ());

CloudXYZRGBNormal::const_iterator it_in = cloud_data->begin ();
for (; it_in!=cloud_data->end (); ++it_in)
for (auto it_in = cloud_data->begin (); it_in!=cloud_data->end (); ++it_in)
{
if (!boost::math::isnan (it_in->x))
{
Expand Down Expand Up @@ -500,7 +499,6 @@ pcl::ihs::ICP::minimizePointPlane (const CloudNormal& cloud_source,
Vec4Xf::const_iterator it_nor_t = nor_t.begin ();

Eigen::Vector4f cross;
float dot;
for (; it_xyz_s!=xyz_s.end (); ++it_xyz_s, ++it_xyz_t, ++it_nor_t)
{
cross = it_xyz_s->cross3 (*it_nor_t);
Expand All @@ -509,7 +507,7 @@ pcl::ihs::ICP::minimizePointPlane (const CloudNormal& cloud_source,
C_tr_bl += cross * it_nor_t->transpose ();
C_br += *it_nor_t * it_nor_t->transpose ();

dot = (*it_xyz_t-*it_xyz_s).dot (*it_nor_t);
float dot = (*it_xyz_t-*it_xyz_s).dot (*it_nor_t);

b_t += cross * dot;
b_b += *it_nor_t * dot;
Expand Down
3 changes: 1 addition & 2 deletions apps/in_hand_scanner/src/input_data_processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,6 @@ pcl::ihs::InputDataProcessing::calculateNormals (const CloudXYZRGBAConstPtr& clo
cloud_out->height = cloud_in->height;
cloud_out->is_dense = false;

CloudXYZRGBA::const_iterator it_in = cloud_in->begin ();
CloudNormals::const_iterator it_n = cloud_normals->begin ();
CloudXYZRGBNormal::iterator it_out = cloud_out->begin ();

Expand All @@ -244,7 +243,7 @@ pcl::ihs::InputDataProcessing::calculateNormals (const CloudXYZRGBAConstPtr& clo
invalid_pt.data [3] = 1.f;
invalid_pt.data_n [3] = 0.f;

for (; it_in!=cloud_in->end (); ++it_in, ++it_n, ++it_out)
for (auto it_in = cloud_in->begin (); it_in!=cloud_in->end (); ++it_in, ++it_n, ++it_out)
{
if (!boost::math::isnan (it_n->getNormalVector4fMap ()))
{
Expand Down
3 changes: 1 addition & 2 deletions apps/include/pcl/apps/impl/dominant_plane_segmentation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -514,9 +514,8 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_fast (std::vector<Cloud

clusters.resize (clusters_map.size ());

std::map<float, pcl::PointIndices>::iterator it_indices;
int k = 0;
for (it_indices = clusters_map.begin (); it_indices != clusters_map.end (); it_indices++)
for (auto it_indices = clusters_map.cbegin (); it_indices != clusters_map.cend (); it_indices++)
{

if (int ((*it_indices).second.indices.size ()) >= object_cluster_min_size_)
Expand Down
9 changes: 3 additions & 6 deletions apps/point_cloud_editor/src/cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,9 +193,8 @@ Cloud::setSelection (SelectionPtr selection_ptr)
partitioned_indices_.resize(cloud_.size());
std::generate(partitioned_indices_.begin(), partitioned_indices_.end(), inc);
unsigned int pos = 0;
Selection::const_iterator it;
// assumes selection is sorted small to large
for (it = selection_ptr->begin(); it != selection_ptr->end(); ++it, ++pos)
for (auto it = selection_ptr->begin(); it != selection_ptr->end(); ++it, ++pos)
{
std::swap(partitioned_indices_[pos], partitioned_indices_[*it]);
}
Expand Down Expand Up @@ -330,8 +329,7 @@ void
Cloud::remove(const Selection& selection)
{
unsigned int pos = cloud_.size();
Selection::const_reverse_iterator rit;
for (rit = selection.rbegin(); rit != selection.rend(); ++rit)
for (auto rit = selection.rbegin(); rit != selection.rend(); ++rit)
std::swap(cloud_.points[--pos], cloud_.points[*rit]);
resize(cloud_.size()-selection.size());
}
Expand Down Expand Up @@ -442,8 +440,7 @@ Cloud::restore (const CopyBuffer& copy_buffer, const Selection& selection)

append(copied_cloud);
unsigned int pos = cloud_.size();
Selection::const_reverse_iterator rit;
for (rit = selection.rbegin(); rit != selection.rend(); ++rit)
for (auto rit = selection.rbegin(); rit != selection.rend(); ++rit)
std::swap(cloud_.points[--pos], cloud_.points[*rit]);
}

Expand Down
3 changes: 1 addition & 2 deletions apps/point_cloud_editor/src/copyBuffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,7 @@ CopyBuffer::set (ConstCloudPtr cloud_ptr, const Selection& selection)
clean();
if (!cloud_ptr)
return;
Selection::const_iterator s_it;
for(s_it = selection.begin(); s_it != selection.end(); ++s_it)
for(auto s_it = selection.begin(); s_it != selection.end(); ++s_it)
buffer_.append( (*cloud_ptr)[*s_it] );
}

Expand Down
3 changes: 1 addition & 2 deletions apps/point_cloud_editor/src/denoiseCommand.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,7 @@ DenoiseCommand::execute ()
filter.filter(temp_cloud);
// back up the removed indices.
pcl::IndicesConstPtr indices_ptr = filter.getRemovedIndices();
std::vector<int>::const_iterator it;
for(it = indices_ptr->begin(); it != indices_ptr->end(); ++it)
for(auto it = indices_ptr->cbegin(); it != indices_ptr->cend(); ++it)
removed_indices_.addIndex(static_cast<unsigned int>(*it));
// back up the removed points.
removed_points_.set(cloud_ptr_, removed_indices_);
Expand Down
3 changes: 1 addition & 2 deletions apps/point_cloud_editor/src/selection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,7 @@ Selection::addIndex (const IndexVector &indices)
void
Selection::removeIndex (const IndexVector &indices)
{
IndexVector::const_iterator it;
for(it = indices.begin(); it != indices.end(); ++it)
for(auto it = indices.cbegin(); it != indices.cend(); ++it)
removeIndex(*it);
}

Expand Down
3 changes: 1 addition & 2 deletions apps/point_cloud_editor/src/statistics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,7 @@ std::string
Statistics::getStats()
{
std::string result;
std::vector<Statistics*>::const_iterator stat_vec_it;
for(stat_vec_it = stat_vec_.begin(); stat_vec_it != stat_vec_.end(); ++stat_vec_it)
for(auto stat_vec_it = stat_vec_.cbegin(); stat_vec_it != stat_vec_.cend(); ++stat_vec_it)
{
std::string stat_string = (*stat_vec_it) -> getStat();
if (stat_string != "")
Expand Down
17 changes: 7 additions & 10 deletions apps/point_cloud_editor/src/transformCommand.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,18 +76,16 @@ TransformCommand::undo()
return;
float transform_matrix_inv[MATRIX_SIZE];
invertMatrix(transform_matrix_, transform_matrix_inv);
float x,y,z;
unsigned int index = 0;
Selection::const_iterator it;
for(it = internal_selection_ptr_ -> begin();
for(auto it = internal_selection_ptr_ -> begin();
it != internal_selection_ptr_-> end(); ++it)
{
Point3D pt;
index = *it;
unsigned int index = *it;
pt.x = (*cloud_ptr_)[index].x - cloud_center_[X];
pt.y = (*cloud_ptr_)[index].y - cloud_center_[Y];
pt.z = (*cloud_ptr_)[index].z - cloud_center_[Z];

float x,y,z;
x = pt.x * cloud_matrix_[0] +
pt.y * cloud_matrix_[4] +
pt.z * cloud_matrix_[8] + cloud_matrix_[12];
Expand Down Expand Up @@ -131,14 +129,13 @@ TransformCommand::undo()
void
TransformCommand::applyTransform(ConstSelectionPtr sel_ptr)
{
float x,y,z;
unsigned int index = 0;
// now modify the selected points' coordinates
Selection::const_iterator it;
for(it = sel_ptr -> begin(); it != sel_ptr-> end(); ++it)
for(auto it = sel_ptr -> begin(); it != sel_ptr-> end(); ++it)
{
index = *it;
unsigned int index = *it;
Point3D pt = cloud_ptr_->getObjectSpacePoint(index);

float x,y,z;
x = pt.x * transform_matrix_[0] +
pt.y * transform_matrix_[4] +
pt.z * transform_matrix_[8] + transform_matrix_[12];
Expand Down
5 changes: 2 additions & 3 deletions apps/src/ni_trajkovic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,6 @@ class TrajkovicDemo

if (cloud)
{
int w (cloud->width);
if (!cloud_init)
{
cloud_viewer_.setPosition (0, 0);
Expand Down Expand Up @@ -179,8 +178,8 @@ class TrajkovicDemo
id != keypoints_indices_->indices.end ();
++id)
{
int u (*id % w);
int v (*id / w);
int u (*id % cloud->width);
int v (*id / cloud->width);
image_viewer_.markPoint (u, v, visualization::red_color, visualization::blue_color, 5, getStrBool (!keypts), 0.5);
}
keypts = !keypts;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_color_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,11 +187,11 @@ main (int argc, char ** argv)
unsigned char red = 0, green = 0, blue = 0;
int rr, gg, bb;
unsigned char radius = 442; // all colors!
int rad;

if (pcl::console::parse_3x_arguments (argc, argv, "-rgb", rr, gg, bb, true) != -1 )
{
cout << "-rgb present" << endl;
int rad;
int idx = pcl::console::parse_argument (argc, argv, "-radius", rad);
if (idx != -1)
{
Expand Down
6 changes: 3 additions & 3 deletions apps/src/openni_grab_images.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,14 +122,14 @@ class OpenNIGrabFrame
depth_image.swap (depth_image_);
image_mutex_.unlock ();

static unsigned char* rgb_data = 0;
static unsigned rgb_data_size = 0;

if (image)
{
const void* data;
if (image->getEncoding() != openni_wrapper::Image::RGB)
{
static unsigned char* rgb_data = 0;
static unsigned rgb_data_size = 0;

if (rgb_data_size < image->getWidth () * image->getHeight ())
{
if (rgb_data)
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_organized_edge_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,9 +98,9 @@ class OpenNIOrganizedEdgeDetection
void
keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
{
double opacity;
if (event.keyUp())
{
double opacity;
switch (event.getKeyCode())
{
case '1':
Expand Down
13 changes: 5 additions & 8 deletions apps/src/openni_shift_to_depth_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,11 +158,8 @@ class SimpleOpenNIViewer
float focalLength_arg,
pcl::PointCloud<PointXYZRGB>& cloud_arg) const
{
size_t i;
size_t cloud_size = width_arg * height_arg;

int x, y, centerX, centerY;

// Reset point cloud
cloud_arg.points.clear ();
cloud_arg.points.reserve (cloud_size);
Expand All @@ -173,15 +170,15 @@ class SimpleOpenNIViewer
cloud_arg.is_dense = false;

// Calculate center of disparity image
centerX = static_cast<int> (width_arg / 2);
centerY = static_cast<int> (height_arg / 2);
int centerX = static_cast<int> (width_arg / 2);
int centerY = static_cast<int> (height_arg / 2);

const float fl_const = 1.0f / focalLength_arg;
static const float bad_point = std::numeric_limits<float>::quiet_NaN ();

i = 0;
for (y = -centerY; y < +centerY; ++y)
for (x = -centerX; x < +centerX; ++x)
size_t i = 0;
for (int y = -centerY; y < +centerY; ++y)
for (int x = -centerX; x < +centerX; ++x)
{
PointXYZRGB newPoint;

Expand Down
2 changes: 1 addition & 1 deletion apps/src/pcd_organized_edge_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,9 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
void
keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
{
double opacity;
if (event.keyUp())
{
double opacity;
switch (event.getKeyCode())
{
case '1':
Expand Down
Loading

0 comments on commit 2187ec0

Please sign in to comment.