Skip to content

Commit

Permalink
Merge pull request #2784 from SunBlack/modernize-use-emplace
Browse files Browse the repository at this point in the history
Use emplace_back instead of push_back, if possible
  • Loading branch information
SergioRAgostinho committed Jan 24, 2019
2 parents 3a71c5c + c274d1f commit f7a62ac
Show file tree
Hide file tree
Showing 50 changed files with 168 additions and 168 deletions.
4 changes: 2 additions & 2 deletions apps/in_hand_scanner/src/opengl_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -549,7 +549,7 @@ pcl::ihs::OpenGLViewer::addMesh (const CloudXYZRGBNormalConstPtr& cloud, const s
ind_v_2 = addVertex (pt_2, vertices, indices [ind_o_2]);
ind_v_3 = addVertex (pt_3, vertices, indices [ind_o_3]);

triangles.push_back (FaceVertexMesh::Triangle (ind_v_1, ind_v_2, ind_v_3));
triangles.emplace_back(ind_v_1, ind_v_2, ind_v_3);
}
}
if (!boost::math::isnan (pt_0.x)) // 0-1-3 is valid
Expand All @@ -562,7 +562,7 @@ pcl::ihs::OpenGLViewer::addMesh (const CloudXYZRGBNormalConstPtr& cloud, const s
ind_v_3 = addVertex (pt_3, vertices, indices [ind_o_3]);
ind_v_0 = addVertex (pt_0, vertices, indices [ind_o_0]);

triangles.push_back (FaceVertexMesh::Triangle (ind_v_1, ind_v_3, ind_v_0));
triangles.emplace_back(ind_v_1, ind_v_3, ind_v_0);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion apps/src/ppf_object_recognition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ main (int argc, char** argv)

PointCloud<PointXYZ>::Ptr cloud_output_subsampled_xyz (new PointCloud<PointXYZ> ());
for (size_t i = 0; i < cloud_output_subsampled.points.size (); ++i)
cloud_output_subsampled_xyz->points.push_back ( PointXYZ (cloud_output_subsampled.points[i].x, cloud_output_subsampled.points[i].y, cloud_output_subsampled.points[i].z));
cloud_output_subsampled_xyz->points.emplace_back(cloud_output_subsampled.points[i].x, cloud_output_subsampled.points[i].y, cloud_output_subsampled.points[i].z);


Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
Expand Down
8 changes: 4 additions & 4 deletions apps/src/pyramid_surface_matching.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,10 +83,10 @@ main (int argc, char **argv)

PCL_INFO ("Finished calculating the features ...\n");
vector<pair<float, float> > dim_range_input, dim_range_target;
for (size_t i = 0; i < 3; ++i) dim_range_input.push_back (pair<float, float> (float (-M_PI), float (M_PI)));
dim_range_input.push_back (pair<float, float> (0.0f, 1.0f));
for (size_t i = 0; i < 3; ++i) dim_range_target.push_back (pair<float, float> (float (-M_PI) * 10.0f, float (M_PI) * 10.0f));
dim_range_target.push_back (pair<float, float> (0.0f, 50.0f));
for (size_t i = 0; i < 3; ++i) dim_range_input.emplace_back(float (-M_PI), float (M_PI));
dim_range_input.emplace_back(0.0f, 1.0f);
for (size_t i = 0; i < 3; ++i) dim_range_target.emplace_back(float (-M_PI) * 10.0f, float (M_PI) * 10.0f);
dim_range_target.emplace_back(0.0f, 50.0f);


PyramidFeatureHistogram<PPFSignature>::Ptr pyramid_a (new PyramidFeatureHistogram<PPFSignature> ());
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/common/impl/file_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace pcl
{
std::string file_name = dirp->d_name;
if (file_name.substr(file_name.size()-4, 4)==".pcd")
file_names.push_back(dirp->d_name);
file_names.emplace_back(dirp->d_name);
}
}
closedir(dp);
Expand Down
2 changes: 1 addition & 1 deletion common/src/parse.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -482,7 +482,7 @@ pcl::console::parse_multiple_arguments (int argc, const char * const * argv, con
// Search for the string
if ((strcmp (argv[i], str) == 0) && (++i < argc))
{
values.push_back (std::string (argv[i]));
values.emplace_back(argv[i]);
}
}
if (values.size () == 0)
Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/impl/grid_minimum.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ pcl::GridMinimum<PointT>::applyFilterIndices (std::vector<int> &indices)

// Compute the grid cell index
int idx = ijk0 * divb_mul[0] + ijk1 * divb_mul[1];
index_vector.push_back (point_index_idx (static_cast<unsigned int> (idx), *it));
index_vector.emplace_back(static_cast<unsigned int> (idx), *it);
}

// Second pass: sort the index_vector vector using value representing target cell as index
Expand All @@ -156,7 +156,7 @@ pcl::GridMinimum<PointT>::applyFilterIndices (std::vector<int> &indices)
while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx)
++i;
++total;
first_and_last_indices_vector.push_back (std::pair<unsigned int, unsigned int> (index, i));
first_and_last_indices_vector.emplace_back(index, i);
index = i;
}

Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/impl/normal_space.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (std::vector<int> &indice
std::vector<std::list <int> > normals_hg;
normals_hg.reserve (n_bins);
for (unsigned int i = 0; i < n_bins; i++)
normals_hg.push_back (std::list<int> ());
normals_hg.emplace_back();

for (std::vector<int>::const_iterator it = indices_->begin (); it != indices_->end (); ++it)
{
Expand All @@ -208,7 +208,7 @@ pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (std::vector<int> &indice
std::vector<std::vector<std::list<int>::iterator> > random_access (normals_hg.size ());
for (unsigned int i = 0; i < normals_hg.size (); i++)
{
random_access.push_back (std::vector<std::list<int>::iterator> ());
random_access.emplace_back();
random_access[i].resize (normals_hg[i].size ());

unsigned int j = 0;
Expand Down
6 changes: 3 additions & 3 deletions filters/include/pcl/filters/impl/voxel_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)

// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), *it));
index_vector.emplace_back(static_cast<unsigned int> (idx), *it);
}
}
// No distance filtering, process all data
Expand All @@ -333,7 +333,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)

// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), *it));
index_vector.emplace_back(static_cast<unsigned int> (idx), *it);
}
}

Expand All @@ -359,7 +359,7 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
if (i - index >= min_points_per_voxel_)
{
++total;
first_and_last_indices_vector.push_back (std::pair<unsigned int, unsigned int> (index, i));
first_and_last_indices_vector.emplace_back(index, i);
}
index = i;
}
Expand Down
4 changes: 2 additions & 2 deletions filters/src/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,7 +340,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
int ijk2 = static_cast<int> (floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (idx, static_cast<unsigned int> (cp)));
index_vector.emplace_back(idx, static_cast<unsigned int> (cp));

xyz_offset += input_->point_step;
}
Expand Down Expand Up @@ -370,7 +370,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
int ijk2 = static_cast<int> (floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (idx, static_cast<unsigned int> (cp)));
index_vector.emplace_back(idx, static_cast<unsigned int> (cp));
xyz_offset += input_->point_step;
}
}
Expand Down
4 changes: 2 additions & 2 deletions filters/src/voxel_grid_label.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)

// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
index_vector.emplace_back(static_cast<unsigned int> (idx), cp);
}
}
// No distance filtering, process all data
Expand All @@ -184,7 +184,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)

// Compute the centroid leaf index
int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
index_vector.push_back (cloud_point_index_idx (static_cast<unsigned int> (idx), cp));
index_vector.emplace_back(static_cast<unsigned int> (idx), cp);
}
}

Expand Down
2 changes: 1 addition & 1 deletion gpu/people/src/bodyparts_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ pcl::gpu::people::RDFBodyPartsDetector::RDFBodyPartsDetector( const vector<strin

// this might throw but we haven't done any malloc yet
int height = loadTree (tree_files[i], nodes, leaves );
impl_->trees.push_back(device::CUDATree(height, nodes, leaves));
impl_->trees.emplace_back(height, nodes, leaves);
}

allocate_buffers(rows, cols);
Expand Down
8 changes: 4 additions & 4 deletions gpu/people/tools/people_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -423,10 +423,10 @@ int main(int argc, char** argv)

//selecting tree files
vector<string> tree_files;
tree_files.push_back("Data/forest1/tree_20.txt");
tree_files.push_back("Data/forest2/tree_20.txt");
tree_files.push_back("Data/forest3/tree_20.txt");
tree_files.push_back("Data/forest4/tree_20.txt");
tree_files.emplace_back("Data/forest1/tree_20.txt");
tree_files.emplace_back("Data/forest2/tree_20.txt");
tree_files.emplace_back("Data/forest3/tree_20.txt");
tree_files.emplace_back("Data/forest4/tree_20.txt");

pc::parse_argument (argc, argv, "-tree0", tree_files[0]);
pc::parse_argument (argc, argv, "-tree1", tree_files[1]);
Expand Down
14 changes: 7 additions & 7 deletions io/src/obj_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ pcl::MTLReader::read (const std::string& mtl_file_path)

if (st[0] == "newmtl")
{
materials_.push_back (pcl::TexMaterial ());
materials_.emplace_back();
materials_.back ().tex_name = st[1];
continue;
}
Expand Down Expand Up @@ -441,7 +441,7 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
int field_offset = 0;
for (int i = 0; i < 3; ++i, field_offset += 4)
{
cloud.fields.push_back (pcl::PCLPointField ());
cloud.fields.emplace_back();
cloud.fields[i].offset = field_offset;
cloud.fields[i].datatype = pcl::PCLPointField::FLOAT32;
cloud.fields[i].count = 1;
Expand All @@ -456,7 +456,7 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c
std::string normals_names[3] = { "normal_x", "normal_y", "normal_z" };
for (int i = 0; i < 3; ++i, field_offset += 4)
{
cloud.fields.push_back (pcl::PCLPointField ());
cloud.fields.emplace_back();
pcl::PCLPointField& last = cloud.fields.back ();
last.name = normals_names[i];
last.offset = field_offset;
Expand Down Expand Up @@ -755,9 +755,9 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
for (std::size_t i = 1; i < st.size (); ++i)
c[i-1] = boost::lexical_cast<float> (st[i]);
if (c[2] == 0)
coordinates.push_back (Eigen::Vector2f (c[0], c[1]));
coordinates.emplace_back(c[0], c[1]);
else
coordinates.push_back (Eigen::Vector2f (c[0]/c[2], c[1]/c[2]));
coordinates.emplace_back(c[0]/c[2], c[1]/c[2]);
++vt_idx;
}
catch (const boost::bad_lexical_cast &e)
Expand All @@ -770,8 +770,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh,
// Material
if (st[0] == "usemtl")
{
mesh.tex_polygons.push_back (std::vector<pcl::Vertices> ());
mesh.tex_materials.push_back (pcl::TexMaterial ());
mesh.tex_polygons.emplace_back();
mesh.tex_materials.emplace_back();
for (std::size_t i = 0; i < companions_.size (); ++i)
{
std::vector<pcl::TexMaterial>::const_iterator mat_it = companions_[i].getMaterial (st[1]);
Expand Down
4 changes: 2 additions & 2 deletions io/src/openni2_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -852,7 +852,7 @@ pcl::io::openni2::OpenNI2VideoMode dummy;
for (std::map<int, pcl::io::openni2::OpenNI2VideoMode>::const_iterator it = config2oni_map_.begin (); it != config2oni_map_.end (); ++it)
{
if (device_->findCompatibleDepthMode (it->second, dummy))
result.push_back (*it);
result.emplace_back(*it);
}

return (result);
Expand All @@ -867,7 +867,7 @@ pcl::io::openni2::OpenNI2VideoMode dummy;
for (std::map<int, pcl::io::openni2::OpenNI2VideoMode>::const_iterator it = config2oni_map_.begin (); it != config2oni_map_.end (); ++it)
{
if (device_->findCompatibleColorMode (it->second, dummy))
result.push_back (*it);
result.emplace_back(*it);
}

return (result);
Expand Down
2 changes: 1 addition & 1 deletion io/src/openni_camera/openni_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList ()
for (xn::NodeInfoList::Iterator nodeIt = node_info_list.Begin (); nodeIt != node_info_list.End (); ++nodeIt)
{
connection_string_map_[(*nodeIt).GetCreationInfo ()] = static_cast<unsigned int> (device_context_.size ());
device_context_.push_back (DeviceContext (*nodeIt));
device_context_.emplace_back(*nodeIt);
}

// enumerate depth nodes
Expand Down
4 changes: 2 additions & 2 deletions io/src/openni_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -860,7 +860,7 @@ pcl::OpenNIGrabber::getAvailableDepthModes () const
for (std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.begin (); it != config2xn_map_.end (); ++it)
{
if (device_->findCompatibleDepthMode (it->second, dummy))
result.push_back (*it);
result.emplace_back(*it);
}

return (result);
Expand All @@ -875,7 +875,7 @@ pcl::OpenNIGrabber::getAvailableImageModes () const
for (std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.begin (); it != config2xn_map_.end (); ++it)
{
if (device_->findCompatibleImageMode (it->second, dummy))
result.push_back (*it);
result.emplace_back(*it);
}

return (result);
Expand Down
2 changes: 1 addition & 1 deletion io/src/ply/ply_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename)
count,
boost::get<0>(element_callbacks),
boost::get<1>(element_callbacks)));
elements.push_back (boost::shared_ptr<element>(element_ptr));
elements.emplace_back(element_ptr);
current_element_ = element_ptr.get ();
}

Expand Down
6 changes: 3 additions & 3 deletions io/src/ply_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ pcl::PLYReader::endHeaderCallback ()
template<typename Scalar> void
pcl::PLYReader::appendScalarProperty (const std::string& name, const size_t& size)
{
cloud_->fields.push_back (::pcl::PCLPointField ());
cloud_->fields.emplace_back();
::pcl::PCLPointField &current_field = cloud_->fields.back ();
current_field.name = name;
current_field.offset = cloud_->point_step;
Expand Down Expand Up @@ -325,7 +325,7 @@ namespace pcl
}
else if (element_name == "vertex")
{
cloud_->fields.push_back (pcl::PCLPointField ());
cloud_->fields.emplace_back();
pcl::PCLPointField &current_field = cloud_->fields.back ();
current_field.name = property_name;
current_field.offset = cloud_->point_step;
Expand Down Expand Up @@ -354,7 +354,7 @@ namespace pcl
{
if (element_name == "vertex")
{
cloud_->fields.push_back (pcl::PCLPointField ());
cloud_->fields.emplace_back();
pcl::PCLPointField &current_field = cloud_->fields.back ();
current_field.name = property_name;
current_field.offset = cloud_->point_step;
Expand Down
2 changes: 1 addition & 1 deletion io/src/vtk_lib_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -380,7 +380,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer<vtkPolyData>& poly_data, pcl::TextureMe
mesh.tex_polygons.push_back (polygon_mesh.polygons);

// Add dummy material
mesh.tex_materials.push_back (pcl::TexMaterial ());
mesh.tex_materials.emplace_back();
std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > dummy;
mesh.tex_coordinates.push_back (dummy);

Expand Down
10 changes: 5 additions & 5 deletions io/tools/converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,11 +211,11 @@ main (int argc,

// Parse all files and options
std::vector<std::string> supported_extensions;
supported_extensions.push_back("obj");
supported_extensions.push_back("pcd");
supported_extensions.push_back("ply");
supported_extensions.push_back("stl");
supported_extensions.push_back("vtk");
supported_extensions.emplace_back("obj");
supported_extensions.emplace_back("pcd");
supported_extensions.emplace_back("ply");
supported_extensions.emplace_back("stl");
supported_extensions.emplace_back("vtk");
std::vector<int> file_args;
for (int i = 1; i < argc; ++i)
for (size_t j = 0; j < supported_extensions.size(); ++j)
Expand Down
2 changes: 1 addition & 1 deletion io/tools/ply/ply2raw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ ply_to_raw_converter::vertex_z (pcl::io::ply::float32 z)
void
ply_to_raw_converter::vertex_end ()
{
vertices_.push_back (boost::tuple<pcl::io::ply::float32, pcl::io::ply::float32, pcl::io::ply::float32 > (vertex_x_, vertex_y_, vertex_z_));
vertices_.emplace_back(vertex_x_, vertex_y_, vertex_z_);
}

void
Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/brisk_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -249,8 +249,8 @@ namespace pcl
// constructor arguments
struct CommonParams
{
static const int HALFSAMPLE = 0;
static const int TWOTHIRDSAMPLE = 1;
static const int HALFSAMPLE;
static const int TWOTHIRDSAMPLE;
};

/** \brief Constructor.
Expand Down
Loading

0 comments on commit f7a62ac

Please sign in to comment.