Skip to content

Commit

Permalink
preincrement iterators to avoid the temporary
Browse files Browse the repository at this point in the history
this suppress some cppcheck warnings
  • Loading branch information
soyersoyer committed Jan 20, 2015
1 parent b61e088 commit a0a3284
Show file tree
Hide file tree
Showing 15 changed files with 35 additions and 35 deletions.
8 changes: 4 additions & 4 deletions apps/modeler/src/scene_tree.cpp
Expand Up @@ -480,7 +480,7 @@ pcl::modeler::SceneTree::dropEvent(QDropEvent * event)
std::set<RenderWindowItem*> previous_parents; std::set<RenderWindowItem*> previous_parents;
for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin(); for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin();
selected_cloud_meshes_it != selected_cloud_meshes.end(); selected_cloud_meshes_it != selected_cloud_meshes.end();
selected_cloud_meshes_it ++) ++ selected_cloud_meshes_it)
{ {
CloudMeshItem* cloud_mesh_item = *selected_cloud_meshes_it; CloudMeshItem* cloud_mesh_item = *selected_cloud_meshes_it;
RenderWindowItem* render_window_item = dynamic_cast<RenderWindowItem*>(cloud_mesh_item->parent()); RenderWindowItem* render_window_item = dynamic_cast<RenderWindowItem*>(cloud_mesh_item->parent());
Expand All @@ -493,7 +493,7 @@ pcl::modeler::SceneTree::dropEvent(QDropEvent * event)
std::vector<CloudMeshItem*> cloud_mesh_items; std::vector<CloudMeshItem*> cloud_mesh_items;
for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin(); for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin();
selected_cloud_meshes_it != selected_cloud_meshes.end(); selected_cloud_meshes_it != selected_cloud_meshes.end();
selected_cloud_meshes_it ++) ++ selected_cloud_meshes_it)
{ {
CloudMeshItem* cloud_mesh_item = *selected_cloud_meshes_it; CloudMeshItem* cloud_mesh_item = *selected_cloud_meshes_it;
if (dynamic_cast<RenderWindowItem*>(cloud_mesh_item->parent()) == NULL) if (dynamic_cast<RenderWindowItem*>(cloud_mesh_item->parent()) == NULL)
Expand All @@ -515,7 +515,7 @@ pcl::modeler::SceneTree::dropEvent(QDropEvent * event)


for (std::set<RenderWindowItem*>::iterator previous_parents_it = previous_parents.begin(); for (std::set<RenderWindowItem*>::iterator previous_parents_it = previous_parents.begin();
previous_parents_it != previous_parents.end(); previous_parents_it != previous_parents.end();
previous_parents_it ++) ++ previous_parents_it)
{ {
(*previous_parents_it)->getRenderWindow()->updateAxes(); (*previous_parents_it)->getRenderWindow()->updateAxes();
(*previous_parents_it)->getRenderWindow()->render(); (*previous_parents_it)->getRenderWindow()->render();
Expand All @@ -535,7 +535,7 @@ pcl::modeler::SceneTree::dropMimeData(QTreeWidgetItem * parent, int, const QMime


for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin(); for (QList<CloudMeshItem*>::iterator selected_cloud_meshes_it = selected_cloud_meshes.begin();
selected_cloud_meshes_it != selected_cloud_meshes.end(); selected_cloud_meshes_it != selected_cloud_meshes.end();
selected_cloud_meshes_it ++) ++ selected_cloud_meshes_it)
{ {
CloudMeshItem* cloud_mesh_item_copy = new CloudMeshItem(render_window_item, *(*selected_cloud_meshes_it)); CloudMeshItem* cloud_mesh_item_copy = new CloudMeshItem(render_window_item, *(*selected_cloud_meshes_it));
render_window_item->addChild(cloud_mesh_item_copy); render_window_item->addChild(cloud_mesh_item_copy);
Expand Down
4 changes: 2 additions & 2 deletions apps/src/openni_change_viewer.cpp
Expand Up @@ -89,7 +89,7 @@ class OpenNIChangeViewer
filtered_cloud.reset (new pcl::PointCloud<pcl::PointXYZRGBA> (*cloud)); filtered_cloud.reset (new pcl::PointCloud<pcl::PointXYZRGBA> (*cloud));
filtered_cloud->points.reserve(newPointIdxVector->size()); filtered_cloud->points.reserve(newPointIdxVector->size());


for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++) for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); ++it)
filtered_cloud->points[*it].rgba = 255<<16; filtered_cloud->points[*it].rgba = 255<<16;


if (!viewer.wasStopped()) if (!viewer.wasStopped())
Expand All @@ -101,7 +101,7 @@ class OpenNIChangeViewer


filtered_cloud->points.reserve(newPointIdxVector->size()); filtered_cloud->points.reserve(newPointIdxVector->size());


for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); it++) for (std::vector<int>::iterator it = newPointIdxVector->begin (); it != newPointIdxVector->end (); ++it)
filtered_cloud->points.push_back(cloud->points[*it]); filtered_cloud->points.push_back(cloud->points[*it]);




Expand Down
Expand Up @@ -85,7 +85,7 @@ main (int argc, char** argv)
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
{ {
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
cloud_cluster->points.push_back (cloud_filtered->points[*pit]); //* cloud_cluster->points.push_back (cloud_filtered->points[*pit]); //*
cloud_cluster->width = cloud_cluster->points.size (); cloud_cluster->width = cloud_cluster->points.size ();
cloud_cluster->height = 1; cloud_cluster->height = 1;
Expand Down
Expand Up @@ -171,7 +171,7 @@ main (int argc, char *argv[])
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it, j++) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it, j++)
{ {
pcl::PointCloud<PointNormal>::Ptr cloud_cluster_don (new pcl::PointCloud<PointNormal>); pcl::PointCloud<PointNormal>::Ptr cloud_cluster_don (new pcl::PointCloud<PointNormal>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
{ {
cloud_cluster_don->points.push_back (doncloud->points[*pit]); cloud_cluster_don->points.push_back (doncloud->points[*pit]);
} }
Expand Down
2 changes: 1 addition & 1 deletion examples/features/example_difference_of_normals.cpp
Expand Up @@ -215,7 +215,7 @@ int main (int argc, char *argv[])
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it, j++) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it, j++)
{ {
pcl::PointCloud<PointOutT>::Ptr cloud_cluster_don (new pcl::PointCloud<PointOutT>); pcl::PointCloud<PointOutT>::Ptr cloud_cluster_don (new pcl::PointCloud<PointOutT>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++){ for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit){
cloud_cluster_don->points.push_back (doncloud->points[*pit]); cloud_cluster_don->points.push_back (doncloud->points[*pit]);
} }


Expand Down
2 changes: 1 addition & 1 deletion examples/segmentation/example_extract_clusters_normals.cpp
Expand Up @@ -95,7 +95,7 @@ main (int, char **argv)
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
{ {
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
cloud_cluster->points.push_back (cloud_ptr->points[*pit]); cloud_cluster->points.push_back (cloud_ptr->points[*pit]);
cloud_cluster->width = static_cast<uint32_t> (cloud_cluster->points.size ()); cloud_cluster->width = static_cast<uint32_t> (cloud_cluster->points.size ());
cloud_cluster->height = 1; cloud_cluster->height = 1;
Expand Down
2 changes: 1 addition & 1 deletion filters/src/voxel_grid_label.cpp
Expand Up @@ -337,7 +337,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
int label = it->first; int label = it->first;
if (it != labels.end ()) if (it != labels.end ())
{ {
for (it = labels.begin (); it != labels.end (); it++) for (it = labels.begin (); it != labels.end (); ++it)
{ {
if (n_occurrence < it->second) if (n_occurrence < it->second)
{ {
Expand Down
4 changes: 2 additions & 2 deletions gpu/examples/segmentation/src/seg.cpp
Expand Up @@ -52,7 +52,7 @@ main (int argc, char** argv)
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
{ {
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZ>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
cloud_cluster->points.push_back (cloud_filtered->points[*pit]); //* cloud_cluster->points.push_back (cloud_filtered->points[*pit]); //*
cloud_cluster->width = cloud_cluster->points.size (); cloud_cluster->width = cloud_cluster->points.size ();
cloud_cluster->height = 1; cloud_cluster->height = 1;
Expand Down Expand Up @@ -97,7 +97,7 @@ main (int argc, char** argv)
for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices_gpu.begin (); it != cluster_indices_gpu.end (); ++it) for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices_gpu.begin (); it != cluster_indices_gpu.end (); ++it)
{ {
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster_gpu (new pcl::PointCloud<pcl::PointXYZ>); pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster_gpu (new pcl::PointCloud<pcl::PointXYZ>);
for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++) for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
cloud_cluster_gpu->points.push_back (cloud_filtered->points[*pit]); //* cloud_cluster_gpu->points.push_back (cloud_filtered->points[*pit]); //*
cloud_cluster_gpu->width = cloud_cluster_gpu->points.size (); cloud_cluster_gpu->width = cloud_cluster_gpu->points.size ();
cloud_cluster_gpu->height = 1; cloud_cluster_gpu->height = 1;
Expand Down
6 changes: 3 additions & 3 deletions io/src/openni2/openni2_device.cpp
Expand Up @@ -536,7 +536,7 @@ pcl::io::openni2::OpenNI2Device::getDefaultIRMode () const
{ {
// Search for and return VGA@30 Hz mode // Search for and return VGA@30 Hz mode
vector<OpenNI2VideoMode> modeList = getSupportedIRVideoModes (); vector<OpenNI2VideoMode> modeList = getSupportedIRVideoModes ();
for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); modeItr++) for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); ++modeItr)
{ {
OpenNI2VideoMode mode = *modeItr; OpenNI2VideoMode mode = *modeItr;
if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) ) if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) )
Expand All @@ -550,7 +550,7 @@ pcl::io::openni2::OpenNI2Device::getDefaultColorMode () const
{ {
// Search for and return VGA@30 Hz mode // Search for and return VGA@30 Hz mode
vector<OpenNI2VideoMode> modeList = getSupportedColorVideoModes (); vector<OpenNI2VideoMode> modeList = getSupportedColorVideoModes ();
for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); modeItr++) for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); ++modeItr)
{ {
OpenNI2VideoMode mode = *modeItr; OpenNI2VideoMode mode = *modeItr;
if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) ) if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) )
Expand All @@ -564,7 +564,7 @@ pcl::io::openni2::OpenNI2Device::getDefaultDepthMode () const
{ {
// Search for and return VGA@30 Hz mode // Search for and return VGA@30 Hz mode
vector<OpenNI2VideoMode> modeList = getSupportedDepthVideoModes (); vector<OpenNI2VideoMode> modeList = getSupportedDepthVideoModes ();
for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); modeItr++) for (vector<OpenNI2VideoMode>::iterator modeItr = modeList.begin (); modeItr != modeList.end (); ++modeItr)
{ {
OpenNI2VideoMode mode = *modeItr; OpenNI2VideoMode mode = *modeItr;
if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) ) if ( (mode.x_resolution_ == 640) && (mode.y_resolution_ == 480) && (mode.frame_rate_ == 30.0) )
Expand Down
4 changes: 2 additions & 2 deletions io/src/openni_camera/openni_driver.cpp
Expand Up @@ -421,8 +421,8 @@ openni_wrapper::OpenNIDriver::getSerialNumber (unsigned index) const throw ()
boost::char_separator<char> sep ("#"); boost::char_separator<char> sep ("#");
boost::tokenizer<boost::char_separator<char> > tokens (info, sep); boost::tokenizer<boost::char_separator<char> > tokens (info, sep);
boost::tokenizer<boost::char_separator<char> >::iterator itr = tokens.begin (); boost::tokenizer<boost::char_separator<char> >::iterator itr = tokens.begin ();
itr++; ++itr;
itr++; ++itr;
std::string sn = *itr; std::string sn = *itr;
device_context_[index].device_node.SetInstanceName(sn.c_str ()); device_context_[index].device_node.SetInstanceName(sn.c_str ());
return (device_context_[index].device_node.GetInstanceName ()); return (device_context_[index].device_node.GetInstanceName ());
Expand Down
2 changes: 1 addition & 1 deletion keypoints/src/agast_2d.cpp
Expand Up @@ -224,7 +224,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression (
} }
} }


curr_corner++; ++curr_corner;
} }


// collecting maximum corners // collecting maximum corners
Expand Down
4 changes: 2 additions & 2 deletions ml/src/permutohedral.cpp
Expand Up @@ -170,12 +170,12 @@ pcl::Permutohedral::init (const std::vector<float> &feature, const int feature_d
// check if key is the right one // check if key is the right one
int tmp_key_index = -1; int tmp_key_index = -1;
//for (int ii = key_index; ii < keys.size (); ii++) //for (int ii = key_index; ii < keys.size (); ii++)
for (it = hash_table.find (hash_key); it != hash_table.end (); it++) for (it = hash_table.find (hash_key); it != hash_table.end (); ++it)
{ {
int ii = it->second; int ii = it->second;
bool same = true; bool same = true;
std::vector<short> k = keys[ii]; std::vector<short> k = keys[ii];
for (int i_k = 0; i_k < static_cast<int> (k.size ()); i_k++) for (size_t i_k = 0; i_k < k.size (); i_k++)
{ {
if (key[i_k] != k[i_k]) if (key[i_k] != k[i_k])
{ {
Expand Down
2 changes: 1 addition & 1 deletion outofcore/src/visualization/object.cpp
Expand Up @@ -110,7 +110,7 @@ Object::removeActor (vtkActor *actor)
{ {
std::set<vtkRenderer*>::iterator renderer_it; std::set<vtkRenderer*>::iterator renderer_it;
for (renderer_it = associated_renderers_[actor].begin (); renderer_it != associated_renderers_[actor].end (); for (renderer_it = associated_renderers_[actor].begin (); renderer_it != associated_renderers_[actor].end ();
renderer_it++) ++renderer_it)
{ {
(*renderer_it)->RemoveActor (actor); (*renderer_it)->RemoveActor (actor);
} }
Expand Down
8 changes: 4 additions & 4 deletions segmentation/src/grabcut_segmentation.cpp
Expand Up @@ -96,7 +96,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths ()
if (source_edges_[u] == 0.0) continue; if (source_edges_[u] == 0.0) continue;


// augment s-u-v-t paths // augment s-u-v-t paths
for (std::map<int, double>::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++) for (std::map<int, double>::iterator it = nodes_[u].begin (); it != nodes_[u].end (); ++it)
{ {
const int v = it->first; const int v = it->first;
if ((it->second == 0.0) || (target_edges_[v] == 0.0)) continue; if ((it->second == 0.0) || (target_edges_[v] == 0.0)) continue;
Expand Down Expand Up @@ -227,7 +227,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::reset ()
std::fill (target_edges_.begin (), target_edges_.end (), 0.0); std::fill (target_edges_.begin (), target_edges_.end (), 0.0);
for (int u = 0; u < (int)nodes_.size (); u++) for (int u = 0; u < (int)nodes_.size (); u++)
{ {
for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++) for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); ++it)
{ {
it->second = 0.0; it->second = 0.0;
} }
Expand Down Expand Up @@ -311,7 +311,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::expandTrees ()
const int u = active_head_; const int u = active_head_;


if (cut_[u] == SOURCE) { if (cut_[u] == SOURCE) {
for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++) for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); ++it)
{ {
if (it->second > 0.0) if (it->second > 0.0)
{ {
Expand All @@ -334,7 +334,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::expandTrees ()
} }
else else
{ {
for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++) for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); ++it)
{ {
if (cut_[it->first] == TARGET) continue; if (cut_[it->first] == TARGET) continue;
if (nodes_[it->first][u] > 0.0) if (nodes_[it->first][u] > 0.0)
Expand Down
18 changes: 9 additions & 9 deletions surface/src/on_nurbs/sparse_mat.cpp
Expand Up @@ -59,9 +59,9 @@ SparseMat::get (std::vector<int> &i, std::vector<int> &j, std::vector<double> &v
i.push_back (it_row->first); i.push_back (it_row->first);
j.push_back (it_col->first); j.push_back (it_col->first);
v.push_back (it_col->second); v.push_back (it_col->second);
it_col++; ++it_col;
} }
it_row++; ++it_row;
} }


} }
Expand Down Expand Up @@ -148,7 +148,7 @@ SparseMat::deleteColumn (int j)
it_col = it_row->second.find (j); it_col = it_row->second.find (j);
if (it_col != it_row->second.end ()) if (it_col != it_row->second.end ())
it_row->second.erase (it_col); it_row->second.erase (it_col);
it_row++; ++it_row;
} }


} }
Expand All @@ -173,15 +173,15 @@ SparseMat::size (int &si, int &sj)
while (it_row != m_mat.end ()) while (it_row != m_mat.end ())
{ {
it_col = it_row->second.end (); it_col = it_row->second.end ();
it_col--; --it_col;
if (sj < ((*it_col).first + 1)) if (sj < ((*it_col).first + 1))
sj = (*it_col).first + 1; sj = (*it_col).first + 1;


it_row++; ++it_row;
} }


it_row = m_mat.end (); it_row = m_mat.end ();
it_row--; --it_row;
si = (*it_row).first + 1; si = (*it_row).first + 1;


} }
Expand All @@ -197,7 +197,7 @@ SparseMat::nonzeros ()
{ {
s += int (it_row->second.size ()); s += int (it_row->second.size ());


it_row++; ++it_row;
} }


return s; return s;
Expand Down Expand Up @@ -236,10 +236,10 @@ SparseMat::print ()
while (it_col != it_row->second.end ()) while (it_col != it_row->second.end ())
{ {
printf ("[%d,%d] %f ", it_row->first, it_col->first, it_col->second); printf ("[%d,%d] %f ", it_row->first, it_col->first, it_col->second);
it_col++; ++it_col;
} }
printf ("\n"); printf ("\n");
it_row++; ++it_row;
} }
} }


0 comments on commit a0a3284

Please sign in to comment.