diff --git a/apps/in_hand_scanner/src/opengl_viewer.cpp b/apps/in_hand_scanner/src/opengl_viewer.cpp index 784e03f06a1..b339a239113 100644 --- a/apps/in_hand_scanner/src/opengl_viewer.cpp +++ b/apps/in_hand_scanner/src/opengl_viewer.cpp @@ -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 @@ -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); } } } diff --git a/apps/src/ppf_object_recognition.cpp b/apps/src/ppf_object_recognition.cpp index 93b712de5e1..04e60b35cd1 100644 --- a/apps/src/ppf_object_recognition.cpp +++ b/apps/src/ppf_object_recognition.cpp @@ -140,7 +140,7 @@ main (int argc, char** argv) PointCloud::Ptr cloud_output_subsampled_xyz (new PointCloud ()); 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 (); diff --git a/apps/src/pyramid_surface_matching.cpp b/apps/src/pyramid_surface_matching.cpp index 1bb004f3298..2396a1cb0be 100644 --- a/apps/src/pyramid_surface_matching.cpp +++ b/apps/src/pyramid_surface_matching.cpp @@ -83,10 +83,10 @@ main (int argc, char **argv) PCL_INFO ("Finished calculating the features ...\n"); vector > dim_range_input, dim_range_target; - for (size_t i = 0; i < 3; ++i) dim_range_input.push_back (pair (float (-M_PI), float (M_PI))); - dim_range_input.push_back (pair (0.0f, 1.0f)); - for (size_t i = 0; i < 3; ++i) dim_range_target.push_back (pair (float (-M_PI) * 10.0f, float (M_PI) * 10.0f)); - dim_range_target.push_back (pair (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::Ptr pyramid_a (new PyramidFeatureHistogram ()); diff --git a/common/include/pcl/common/impl/file_io.hpp b/common/include/pcl/common/impl/file_io.hpp index a7141ce64ee..5fb53ac93a2 100644 --- a/common/include/pcl/common/impl/file_io.hpp +++ b/common/include/pcl/common/impl/file_io.hpp @@ -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); diff --git a/common/src/parse.cpp b/common/src/parse.cpp index 4139a5c0d23..85204bddc51 100644 --- a/common/src/parse.cpp +++ b/common/src/parse.cpp @@ -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) diff --git a/filters/include/pcl/filters/impl/grid_minimum.hpp b/filters/include/pcl/filters/impl/grid_minimum.hpp index a8b8bf5987a..26d888591d0 100644 --- a/filters/include/pcl/filters/impl/grid_minimum.hpp +++ b/filters/include/pcl/filters/impl/grid_minimum.hpp @@ -131,7 +131,7 @@ pcl::GridMinimum::applyFilterIndices (std::vector &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 (idx), *it)); + index_vector.emplace_back(static_cast (idx), *it); } // Second pass: sort the index_vector vector using value representing target cell as index @@ -156,7 +156,7 @@ pcl::GridMinimum::applyFilterIndices (std::vector &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 (index, i)); + first_and_last_indices_vector.emplace_back(index, i); index = i; } diff --git a/filters/include/pcl/filters/impl/normal_space.hpp b/filters/include/pcl/filters/impl/normal_space.hpp index e3809d703af..109559c8403 100644 --- a/filters/include/pcl/filters/impl/normal_space.hpp +++ b/filters/include/pcl/filters/impl/normal_space.hpp @@ -194,7 +194,7 @@ pcl::NormalSpaceSampling::applyFilter (std::vector &indice std::vector > normals_hg; normals_hg.reserve (n_bins); for (unsigned int i = 0; i < n_bins; i++) - normals_hg.push_back (std::list ()); + normals_hg.emplace_back(); for (std::vector::const_iterator it = indices_->begin (); it != indices_->end (); ++it) { @@ -208,7 +208,7 @@ pcl::NormalSpaceSampling::applyFilter (std::vector &indice std::vector::iterator> > random_access (normals_hg.size ()); for (unsigned int i = 0; i < normals_hg.size (); i++) { - random_access.push_back (std::vector::iterator> ()); + random_access.emplace_back(); random_access[i].resize (normals_hg[i].size ()); unsigned int j = 0; diff --git a/filters/include/pcl/filters/impl/voxel_grid.hpp b/filters/include/pcl/filters/impl/voxel_grid.hpp index 4240308adf2..7709407c223 100644 --- a/filters/include/pcl/filters/impl/voxel_grid.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid.hpp @@ -309,7 +309,7 @@ pcl::VoxelGrid::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 (idx), *it)); + index_vector.emplace_back(static_cast (idx), *it); } } // No distance filtering, process all data @@ -333,7 +333,7 @@ pcl::VoxelGrid::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 (idx), *it)); + index_vector.emplace_back(static_cast (idx), *it); } } @@ -359,7 +359,7 @@ pcl::VoxelGrid::applyFilter (PointCloud &output) if (i - index >= min_points_per_voxel_) { ++total; - first_and_last_indices_vector.push_back (std::pair (index, i)); + first_and_last_indices_vector.emplace_back(index, i); } index = i; } diff --git a/filters/src/voxel_grid.cpp b/filters/src/voxel_grid.cpp index 62552a5312d..f7c156c8371 100644 --- a/filters/src/voxel_grid.cpp +++ b/filters/src/voxel_grid.cpp @@ -340,7 +340,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) int ijk2 = static_cast (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 (cp))); + index_vector.emplace_back(idx, static_cast (cp)); xyz_offset += input_->point_step; } @@ -370,7 +370,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) int ijk2 = static_cast (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 (cp))); + index_vector.emplace_back(idx, static_cast (cp)); xyz_offset += input_->point_step; } } diff --git a/filters/src/voxel_grid_label.cpp b/filters/src/voxel_grid_label.cpp index 36baa57d968..724e3f5d69e 100644 --- a/filters/src/voxel_grid_label.cpp +++ b/filters/src/voxel_grid_label.cpp @@ -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 (idx), cp)); + index_vector.emplace_back(static_cast (idx), cp); } } // No distance filtering, process all data @@ -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 (idx), cp)); + index_vector.emplace_back(static_cast (idx), cp); } } diff --git a/gpu/people/src/bodyparts_detector.cpp b/gpu/people/src/bodyparts_detector.cpp index b63a190d1ff..2a662f8d5f1 100644 --- a/gpu/people/src/bodyparts_detector.cpp +++ b/gpu/people/src/bodyparts_detector.cpp @@ -71,7 +71,7 @@ pcl::gpu::people::RDFBodyPartsDetector::RDFBodyPartsDetector( const vectortrees.push_back(device::CUDATree(height, nodes, leaves)); + impl_->trees.emplace_back(height, nodes, leaves); } allocate_buffers(rows, cols); diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index bc05368edf3..7829106f449 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -423,10 +423,10 @@ int main(int argc, char** argv) //selecting tree files vector 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]); diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 8dd83a88fcd..c89108f5d90 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -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; } @@ -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; @@ -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; @@ -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 (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) @@ -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 ()); - 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::const_iterator mat_it = companions_[i].getMaterial (st[1]); diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index d7addb67482..f6044843d77 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -852,7 +852,7 @@ pcl::io::openni2::OpenNI2VideoMode dummy; for (std::map::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); @@ -867,7 +867,7 @@ pcl::io::openni2::OpenNI2VideoMode dummy; for (std::map::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); diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index 82d58b835ae..4463c9fc971 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -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 (device_context_.size ()); - device_context_.push_back (DeviceContext (*nodeIt)); + device_context_.emplace_back(*nodeIt); } // enumerate depth nodes diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 8fe82dfa4cf..e5532b84d8c 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -860,7 +860,7 @@ pcl::OpenNIGrabber::getAvailableDepthModes () const for (std::map::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); @@ -875,7 +875,7 @@ pcl::OpenNIGrabber::getAvailableImageModes () const for (std::map::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); diff --git a/io/src/ply/ply_parser.cpp b/io/src/ply/ply_parser.cpp index 1f923b1c54d..ba79acc03c4 100644 --- a/io/src/ply/ply_parser.cpp +++ b/io/src/ply/ply_parser.cpp @@ -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_ptr)); + elements.emplace_back(element_ptr); current_element_ = element_ptr.get (); } diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 5759831a787..3afdbf88ca7 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -102,7 +102,7 @@ pcl::PLYReader::endHeaderCallback () template void pcl::PLYReader::appendScalarProperty (const std::string& name, const size_t& size) { - cloud_->fields.push_back (::pcl::PCLPointField ()); + cloud_->fields.emplace_back(); ::pcl::PCLPointField ¤t_field = cloud_->fields.back (); current_field.name = name; current_field.offset = cloud_->point_step; @@ -325,7 +325,7 @@ namespace pcl } else if (element_name == "vertex") { - cloud_->fields.push_back (pcl::PCLPointField ()); + cloud_->fields.emplace_back(); pcl::PCLPointField ¤t_field = cloud_->fields.back (); current_field.name = property_name; current_field.offset = cloud_->point_step; @@ -354,7 +354,7 @@ namespace pcl { if (element_name == "vertex") { - cloud_->fields.push_back (pcl::PCLPointField ()); + cloud_->fields.emplace_back(); pcl::PCLPointField ¤t_field = cloud_->fields.back (); current_field.name = property_name; current_field.offset = cloud_->point_step; diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index 4cf2ab6a892..91d76f48626 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -380,7 +380,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer& 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 > dummy; mesh.tex_coordinates.push_back (dummy); diff --git a/io/tools/converter.cpp b/io/tools/converter.cpp index 64084863435..59d5905681f 100644 --- a/io/tools/converter.cpp +++ b/io/tools/converter.cpp @@ -211,11 +211,11 @@ main (int argc, // Parse all files and options std::vector 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 file_args; for (int i = 1; i < argc; ++i) for (size_t j = 0; j < supported_extensions.size(); ++j) diff --git a/io/tools/ply/ply2raw.cpp b/io/tools/ply/ply2raw.cpp index 5e8b92509fa..949e25bfee5 100644 --- a/io/tools/ply/ply2raw.cpp +++ b/io/tools/ply/ply2raw.cpp @@ -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 (vertex_x_, vertex_y_, vertex_z_)); + vertices_.emplace_back(vertex_x_, vertex_y_, vertex_z_); } void diff --git a/keypoints/include/pcl/keypoints/brisk_2d.h b/keypoints/include/pcl/keypoints/brisk_2d.h index 83db6681438..f1477824793 100644 --- a/keypoints/include/pcl/keypoints/brisk_2d.h +++ b/keypoints/include/pcl/keypoints/brisk_2d.h @@ -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. diff --git a/keypoints/src/brisk_2d.cpp b/keypoints/src/brisk_2d.cpp index 8d4f7446ab6..1449a3c06d2 100644 --- a/keypoints/src/brisk_2d.cpp +++ b/keypoints/src/brisk_2d.cpp @@ -47,6 +47,9 @@ #include #endif +const int pcl::keypoints::brisk::Layer::CommonParams::HALFSAMPLE = 0; +const int pcl::keypoints::brisk::Layer::CommonParams::TWOTHIRDSAMPLE = 1; + ///////////////////////////////////////////////////////////////////////////////////////// // construct telling the octaves number: pcl::keypoints::brisk::ScaleSpace::ScaleSpace (int octaves) @@ -74,15 +77,15 @@ pcl::keypoints::brisk::ScaleSpace::constructPyramid ( pyramid_.clear (); // fill the pyramid - pyramid_.push_back (pcl::keypoints::brisk::Layer (std::vector (image), width, height)); + pyramid_.emplace_back(std::vector (image), width, height); if (layers_ > 1) - pyramid_.push_back (pcl::keypoints::brisk::Layer (pyramid_.back (), pcl::keypoints::brisk::Layer::CommonParams::TWOTHIRDSAMPLE)); + pyramid_.emplace_back(pyramid_.back (), pcl::keypoints::brisk::Layer::CommonParams::TWOTHIRDSAMPLE); const int octaves2 = layers_; for (int i = 2; i < octaves2; i += 2) { - pyramid_.push_back (pcl::keypoints::brisk::Layer (pyramid_[i-2], pcl::keypoints::brisk::Layer::CommonParams::HALFSAMPLE)); - pyramid_.push_back (pcl::keypoints::brisk::Layer (pyramid_[i-1], pcl::keypoints::brisk::Layer::CommonParams::HALFSAMPLE)); + pyramid_.emplace_back(pyramid_[i-2], pcl::keypoints::brisk::Layer::CommonParams::HALFSAMPLE); + pyramid_.emplace_back(pyramid_[i-1], pcl::keypoints::brisk::Layer::CommonParams::HALFSAMPLE); } } @@ -140,7 +143,7 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( delta_x, delta_y); // store: - keypoints.push_back (pcl::PointWithScale (point.u + delta_x, point.v + delta_y, 0.0f, basic_size_, -1, max, 0)); + keypoints.emplace_back(point.u + delta_x, point.v + delta_y, 0.0f, basic_size_, -1, max, 0); } return; } @@ -186,13 +189,13 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( delta_x, delta_y); // store: - keypoints.push_back (pcl::PointWithScale ((point.u + delta_x) * l.getScale () + l.getOffset (), // x - (point.v + delta_y) * l.getScale () + l.getOffset (), // y - 0.0f, // z - basic_size_ * l.getScale (), // size - -1, // angle - max, // response - i)); // octave + keypoints.emplace_back((point.u + delta_x) * l.getScale () + l.getOffset (), // x + (point.v + delta_y) * l.getScale () + l.getOffset (), // y + 0.0f, // z + basic_size_ * l.getScale (), // size + -1, // angle + max, // response + i); // octave } } else @@ -218,7 +221,7 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( // finally store the detected keypoint: if (score > float (threshold_)) { - keypoints.push_back (pcl::PointWithScale (x, y, 0.0f, basic_size_ * scale, -1, score, i)); + keypoints.emplace_back(x, y, 0.0f, basic_size_ * scale, -1, score, i); } } } diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index af4cf90a374..2436a5dbc4c 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -793,7 +793,7 @@ NarfKeypoint::calculateInterestPoints () stop = false; // There is a point in range -> Have to check further distances float interest_value2 = interest_image_[index2]; - sample_points.push_back (Eigen::Vector3d (x2-keypoint_x_int, y2-keypoint_y_int, interest_value2)); + sample_points.emplace_back(x2-keypoint_x_int, y2-keypoint_y_int, interest_value2); } } if (!polynomial_calculations.bivariatePolynomialApproximation (sample_points, 2, polynomial)) diff --git a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp index 118e51493ee..bd278527bb2 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp @@ -670,7 +670,7 @@ void pcl::GlobalHypothesesVerification::computeClutterCue(boost: for (size_t k = 0; k < nn_distances.size (); k++) { if (nn_indices[k] != i) - neighborhood_indices.push_back (std::make_pair (nn_indices[k], i)); + neighborhood_indices.emplace_back (nn_indices[k], i); } } } diff --git a/recognition/src/face_detection/rf_face_detector_trainer.cpp b/recognition/src/face_detection/rf_face_detector_trainer.cpp index ca97053d72e..e9b8cfb6e36 100644 --- a/recognition/src/face_detection/rf_face_detector_trainer.cpp +++ b/recognition/src/face_detection/rf_face_detector_trainer.cpp @@ -193,7 +193,7 @@ void pcl::RFFaceDetectorTrainer::faceVotesClustering() std::vector < std::pair > uncertainty; for (size_t j = 0; j < votes_indices[i].size (); j++) { - uncertainty.push_back (std::make_pair (votes_indices[i][j], uncertainties_[votes_indices[i][j]])); + uncertainty.emplace_back (votes_indices[i][j], uncertainties_[votes_indices[i][j]]); } std::sort (uncertainty.begin (), uncertainty.end (), boost::bind (&std::pair::second, _1) < boost::bind (&std::pair::second, _2)); @@ -402,10 +402,9 @@ void pcl::RFFaceDetectorTrainer::detectFaces() head_center_votes_.push_back (head_center); float mult_fact = 0.0174532925f; - angle_votes_.push_back ( - Eigen::Vector3f (static_cast(leaves[l].rot_mean_[0]) * mult_fact, + angle_votes_.emplace_back(static_cast(leaves[l].rot_mean_[0]) * mult_fact, static_cast(leaves[l].rot_mean_[1]) * mult_fact, - static_cast(leaves[l].rot_mean_[2]) * mult_fact)); + static_cast(leaves[l].rot_mean_[2]) * mult_fact); uncertainties_.push_back (static_cast(leaves[l].covariance_trans_.trace () + leaves[l].covariance_rot_.trace ())); } } diff --git a/recognition/src/ransac_based/obj_rec_ransac.cpp b/recognition/src/ransac_based/obj_rec_ransac.cpp index 6bc9f003b5a..388b32632e0 100644 --- a/recognition/src/ransac_based/obj_rec_ransac.cpp +++ b/recognition/src/ransac_based/obj_rec_ransac.cpp @@ -221,7 +221,7 @@ pcl::recognition::ObjRecRANSAC::sampleOrientedPointPairs (int num_iterations, co } // Save the sampled point pair - output.push_back (OrientedPointPair (p1, n1, p2, n2)); + output.emplace_back(p1, n1, p2, n2); #ifdef OBJ_REC_RANSAC_VERBOSE ++num_of_opps; @@ -598,11 +598,10 @@ pcl::recognition::ObjRecRANSAC::filterGraphOfConflictingHypotheses (ORRGraph::Node*>::iterator it = on_nodes.begin () ; it != on_nodes.end () ; ++it ) { - recognized_objects.push_back ( - ObjRecRANSAC::Output ((*it)->getData ()->obj_model_->getObjectName (), + recognized_objects.emplace_back((*it)->getData ()->obj_model_->getObjectName (), (*it)->getData ()->rigid_transform_, (*it)->getData ()->match_confidence_, - (*it)->getData ()->obj_model_->getUserData ()) + (*it)->getData ()->obj_model_->getUserData () ); } diff --git a/registration/src/ppf_registration.cpp b/registration/src/ppf_registration.cpp index 93b424f18e3..cc1cc884dd4 100644 --- a/registration/src/ppf_registration.cpp +++ b/registration/src/ppf_registration.cpp @@ -97,6 +97,6 @@ pcl::PPFHashMapSearch::nearestNeighborSearch (float &f1, float &f2, float &f3, f HashKeyStruct key = HashKeyStruct (d1, d2, d3, d4); std::pair map_iterator_pair = feature_hash_map_->equal_range (key); for (; map_iterator_pair.first != map_iterator_pair.second; ++ map_iterator_pair.first) - indices.push_back (std::pair (map_iterator_pair.first->second.first, - map_iterator_pair.first->second.second)); + indices.emplace_back(map_iterator_pair.first->second.first, + map_iterator_pair.first->second.second); } diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index f37ea101912..e55132d7604 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -302,10 +302,10 @@ pcl::simulation::RangeLikelihood::RangeLikelihood (int rows, int cols, int row_h likelihood_program_->link (); - vertices_.push_back (Eigen::Vector3f (-1.0, 1.0, 0.0)); - vertices_.push_back (Eigen::Vector3f ( 1.0, 1.0, 0.0)); - vertices_.push_back (Eigen::Vector3f ( 1.0, -1.0, 0.0)); - vertices_.push_back (Eigen::Vector3f (-1.0, -1.0, 0.0)); + vertices_.emplace_back(-1.0, 1.0, 0.0); + vertices_.emplace_back( 1.0, 1.0, 0.0); + vertices_.emplace_back( 1.0, -1.0, 0.0); + vertices_.emplace_back(-1.0, -1.0, 0.0); glGenBuffers (1, &quad_vbo_); glBindBuffer (GL_ARRAY_BUFFER, quad_vbo_); diff --git a/surface/src/on_nurbs/fitting_surface_pdm.cpp b/surface/src/on_nurbs/fitting_surface_pdm.cpp index 46022cd504c..a1efa6f5a03 100644 --- a/surface/src/on_nurbs/fitting_surface_pdm.cpp +++ b/surface/src/on_nurbs/fitting_surface_pdm.cpp @@ -1166,15 +1166,15 @@ FittingSurface::inverseMappingBoundary (const ON_NurbsSurface &nurbs, const Vect // NORTH - SOUTH for (unsigned i = 0; i < (elementsV.size () - 1); i++) { - ini_points.push_back (myvec (WEST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i]))); - ini_points.push_back (myvec (EAST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i]))); + ini_points.emplace_back(WEST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i])); + ini_points.emplace_back(EAST, elementsV[i] + 0.5 * (elementsV[i + 1] - elementsV[i])); } // WEST - EAST for (unsigned i = 0; i < (elementsU.size () - 1); i++) { - ini_points.push_back (myvec (NORTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i]))); - ini_points.push_back (myvec (SOUTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i]))); + ini_points.emplace_back(NORTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i])); + ini_points.emplace_back(SOUTH, elementsU[i] + 0.5 * (elementsU[i + 1] - elementsU[i])); } for (unsigned i = 0; i < ini_points.size (); i++) diff --git a/test/common/test_common.cpp b/test/common/test_common.cpp index 179b7b66e3c..452ef266592 100644 --- a/test/common/test_common.cpp +++ b/test/common/test_common.cpp @@ -187,7 +187,7 @@ TEST (PCL, PointCloud) for (uint32_t i = 0; i < cloud.width*cloud.height; ++i) { float j = static_cast (i); - cloud.points.push_back (PointXYZ (3.0f * j + 0.0f, 3.0f * j + 1.0f, 3.0f * j + 2.0f)); + cloud.points.emplace_back(3.0f * j + 0.0f, 3.0f * j + 1.0f, 3.0f * j + 2.0f); } Eigen::MatrixXf mat_xyz1 = cloud.getMatrixXfMap (); diff --git a/test/common/test_vector_average.cpp b/test/common/test_vector_average.cpp index 06e433eaf6c..54ca7c9ca57 100644 --- a/test/common/test_vector_average.cpp +++ b/test/common/test_vector_average.cpp @@ -47,11 +47,11 @@ TEST (PCL, VectorAverage_mean) { std::vector > points; std::vector > weights; - points.push_back (Eigen::Vector3f (-0.558191f, 0.180822f, -0.809769f)); + points.emplace_back(-0.558191f, 0.180822f, -0.809769f); weights.push_back (0.160842f); - points.push_back (Eigen::Vector3f (-0.510641f, 0.290673f, -0.809169f)); + points.emplace_back(-0.510641f, 0.290673f, -0.809169f); weights.push_back (0.526732f); - points.push_back (Eigen::Vector3f (-0.440713f, 0.385624f, -0.810597f)); + points.emplace_back(-0.440713f, 0.385624f, -0.810597f); weights.push_back (0.312427f); Eigen::Vector3f correct_mean (0.0f, 0.0f, 0.0f); diff --git a/test/common/test_wrappers.cpp b/test/common/test_wrappers.cpp index bfc0792ccea..a4db7ec9351 100644 --- a/test/common/test_wrappers.cpp +++ b/test/common/test_wrappers.cpp @@ -137,7 +137,7 @@ main (int argc, char** argv) cloud.width = 10; cloud.height = 480; for (uint32_t i = 0; i < size; ++i) - cloud.points.push_back (PointXYZ (3.0f * static_cast(i) + 0, 3.0f * static_cast (i) + 1, 3.0f * static_cast (i) + 2)); + cloud.points.emplace_back(3.0f * static_cast(i) + 0, 3.0f * static_cast (i) + 1, 3.0f * static_cast (i) + 2); testing::InitGoogleTest (&argc, argv); return (RUN_ALL_TESTS ()); diff --git a/test/io/test_grabbers.cpp b/test/io/test_grabbers.cpp index 0a3ac4007bd..cdf9c486565 100644 --- a/test/io/test_grabbers.cpp +++ b/test/io/test_grabbers.cpp @@ -550,7 +550,7 @@ int { CloudT::Ptr cloud (new CloudT); pcl::io::loadPCDFile (pcd_files_[i], *cloud); - pcds_.push_back (cloud); + pcds_.emplace_back(cloud); } testing::InitGoogleTest (&argc, argv); diff --git a/test/kdtree/test_kdtree.cpp b/test/kdtree/test_kdtree.cpp index 594a2db7ddf..90915384f67 100644 --- a/test/kdtree/test_kdtree.cpp +++ b/test/kdtree/test_kdtree.cpp @@ -74,7 +74,7 @@ init () for (float z = -0.5f; z <= 0.5f; z += resolution) for (float y = -0.5f; y <= 0.5f; y += resolution) for (float x = -0.5f; x <= 0.5f; x += resolution) - cloud.points.push_back (MyPoint (x, y, z)); + cloud.points.emplace_back(x, y, z); cloud.width = static_cast (cloud.points.size ()); cloud.height = 1; @@ -83,9 +83,9 @@ init () srand (static_cast (time (NULL))); // Randomly create a new point cloud for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i) - cloud_big.points.push_back (MyPoint (static_cast (1024 * rand () / (RAND_MAX + 1.0)), + cloud_big.points.emplace_back(static_cast (1024 * rand () / (RAND_MAX + 1.0)), static_cast (1024 * rand () / (RAND_MAX + 1.0)), - static_cast (1024 * rand () / (RAND_MAX + 1.0)))); + static_cast (1024 * rand () / (RAND_MAX + 1.0))); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -226,16 +226,16 @@ class MyPointRepresentationXY : public PointRepresentation TEST (PCL, KdTreeFLANN_setPointRepresentation) { PointCloud::Ptr random_cloud (new PointCloud ()); - random_cloud->points.push_back (MyPoint (86.6f, 42.1f, 92.4f)); - random_cloud->points.push_back (MyPoint (63.1f, 18.4f, 22.3f)); - random_cloud->points.push_back (MyPoint (35.5f, 72.5f, 37.3f)); - random_cloud->points.push_back (MyPoint (99.7f, 37.0f, 8.7f)); - random_cloud->points.push_back (MyPoint (22.4f, 84.1f, 64.0f)); - random_cloud->points.push_back (MyPoint (65.2f, 73.4f, 18.0f)); - random_cloud->points.push_back (MyPoint (60.4f, 57.1f, 4.5f)); - random_cloud->points.push_back (MyPoint (38.7f, 17.6f, 72.3f)); - random_cloud->points.push_back (MyPoint (14.2f, 95.7f, 34.7f)); - random_cloud->points.push_back (MyPoint ( 2.5f, 26.5f, 66.0f)); + random_cloud->points.emplace_back(86.6f, 42.1f, 92.4f); + random_cloud->points.emplace_back(63.1f, 18.4f, 22.3f); + random_cloud->points.emplace_back(35.5f, 72.5f, 37.3f); + random_cloud->points.emplace_back(99.7f, 37.0f, 8.7f); + random_cloud->points.emplace_back(22.4f, 84.1f, 64.0f); + random_cloud->points.emplace_back(65.2f, 73.4f, 18.0f); + random_cloud->points.emplace_back(60.4f, 57.1f, 4.5f); + random_cloud->points.emplace_back(38.7f, 17.6f, 72.3f); + random_cloud->points.emplace_back(14.2f, 95.7f, 34.7f); + random_cloud->points.emplace_back( 2.5f, 26.5f, 66.0f); KdTreeFLANN kdtree; kdtree.setInputCloud (random_cloud); diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index 3aca0ed7b7b..fcee97dfe46 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -1499,7 +1499,7 @@ struct OctreePointCloudSierpinskiTest float y = y_min + (rand () / ((float)(RAND_MAX) + 1)) * (y_max - y_min); float z = z_min + (rand () / ((float)(RAND_MAX) + 1)) * (z_max - z_min); - cloud->points.push_back (PointT (x, y, z)); + cloud->points.emplace_back(x, y, z); } } diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index 24aa4affdff..756488af376 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -755,7 +755,7 @@ TEST_F (OutofcoreTest, PointCloud2_Insertion) point_cloud.height = 1; for (size_t i=0; i < numPts; i++) - point_cloud.points.push_back (PointT (static_cast(rand () % 10), static_cast(rand () % 10), static_cast(rand () % 10))); + point_cloud.points.emplace_back(static_cast(rand () % 10), static_cast(rand () % 10), static_cast(rand () % 10)); pcl::PCLPointCloud2::Ptr input_cloud (new pcl::PCLPointCloud2 ()); diff --git a/test/registration/test_correspondence_estimation.cpp b/test/registration/test_correspondence_estimation.cpp index 05e5bea838c..447856df2ba 100644 --- a/test/registration/test_correspondence_estimation.cpp +++ b/test/registration/test_correspondence_estimation.cpp @@ -52,8 +52,8 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting) { for (float z = 0.0f; z < 5.0f; z += 0.2f) { - cloud1->points.push_back (pcl::PointXYZ (i, 0, z)); - cloud2->points.push_back (pcl::PointXYZ (i, 2, z)); // Ideally this should be the corresponding point to the point defined in the previous line + cloud1->points.emplace_back(i, 0, z); + cloud2->points.emplace_back(i, 2, z); // Ideally this should be the corresponding point to the point defined in the previous line } } @@ -90,8 +90,8 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationSetSearchMethod) pcl::PointCloud::Ptr cloud2 (new pcl::PointCloud ()); for ( size_t i = 0; i < 50; i++ ) { - cloud1->points.push_back(pcl::PointXYZ(float (rand()), float (rand()), float (rand()))); - cloud2->points.push_back(pcl::PointXYZ(float (rand()), float (rand()), float (rand()))); + cloud1->points.emplace_back(float (rand()), float (rand()), float (rand())); + cloud2->points.emplace_back(float (rand()), float (rand()), float (rand())); } // Build a KdTree for each pcl::search::KdTree::Ptr tree1 (new pcl::search::KdTree ()); diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index e999d0b153c..fe98f430830 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -623,10 +623,10 @@ TEST (PCL, PyramidFeatureHistogram) vector > dim_range_input, dim_range_target; - for (size_t i = 0; i < 3; ++i) dim_range_input.push_back (pair (static_cast (-M_PI), static_cast (M_PI))); - dim_range_input.push_back (pair (0.0f, 1.0f)); - for (size_t i = 0; i < 3; ++i) dim_range_target.push_back (pair (static_cast (-M_PI) * 10.0f, static_cast (M_PI) * 10.0f)); - dim_range_target.push_back (pair (0.0f, 50.0f)); + for (size_t i = 0; i < 3; ++i) dim_range_input.emplace_back(static_cast (-M_PI), static_cast (M_PI)); + dim_range_input.emplace_back(0.0f, 1.0f); + for (size_t i = 0; i < 3; ++i) dim_range_target.emplace_back(static_cast (-M_PI) * 10.0f, static_cast (M_PI) * 10.0f); + dim_range_target.emplace_back(0.0f, 50.0f); PyramidFeatureHistogram::Ptr pyramid_source (new PyramidFeatureHistogram ()), @@ -645,8 +645,8 @@ TEST (PCL, PyramidFeatureHistogram) EXPECT_NEAR (similarity_value, 0.74101555347442627, 1e-4); vector > dim_range_target2; - for (size_t i = 0; i < 3; ++i) dim_range_target2.push_back (pair (static_cast (-M_PI) * 5.0f, static_cast (M_PI) * 5.0f)); - dim_range_target2.push_back (pair (0.0f, 20.0f)); + for (size_t i = 0; i < 3; ++i) dim_range_target2.emplace_back(static_cast (-M_PI) * 5.0f, static_cast (M_PI) * 5.0f); + dim_range_target2.emplace_back(0.0f, 20.0f); pyramid_source->setTargetDimensionRange (dim_range_target2); pyramid_source->compute (); @@ -659,8 +659,8 @@ TEST (PCL, PyramidFeatureHistogram) vector > dim_range_target3; - for (size_t i = 0; i < 3; ++i) dim_range_target3.push_back (pair (static_cast (-M_PI) * 2.0f, static_cast (M_PI) * 2.0f)); - dim_range_target3.push_back (pair (0.0f, 10.0f)); + for (size_t i = 0; i < 3; ++i) dim_range_target3.emplace_back(static_cast (-M_PI) * 2.0f, static_cast (M_PI) * 2.0f); + dim_range_target3.emplace_back(0.0f, 10.0f); pyramid_source->setTargetDimensionRange (dim_range_target3); pyramid_source->compute (); diff --git a/test/search/test_flann_search.cpp b/test/search/test_flann_search.cpp index 9d9c752c79b..0f6fdefa50b 100644 --- a/test/search/test_flann_search.cpp +++ b/test/search/test_flann_search.cpp @@ -58,7 +58,7 @@ init () for (float z = -0.5f; z <= 0.5f; z += resolution) for (float y = -0.5f; y <= 0.5f; y += resolution) for (float x = -0.5f; x <= 0.5f; x += resolution) - cloud.points.push_back (PointXYZ (x, y, z)); + cloud.points.emplace_back(x, y, z); cloud.width = int (cloud.points.size ()); cloud.height = 1; @@ -67,11 +67,10 @@ init () srand (int (time (NULL))); // Randomly create a new point cloud for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i) - cloud_big.points.push_back ( - PointXYZ ( + cloud_big.points.emplace_back( float (1024 * rand () / (RAND_MAX + 1.0)), float (1024 * rand () / (RAND_MAX + 1.0)), - float (1024 * rand () / (RAND_MAX + 1.0)))); + float (1024 * rand () / (RAND_MAX + 1.0))); } diff --git a/test/search/test_kdtree.cpp b/test/search/test_kdtree.cpp index b2c85b9fe8d..879b008e9e1 100644 --- a/test/search/test_kdtree.cpp +++ b/test/search/test_kdtree.cpp @@ -55,7 +55,7 @@ init () for (float z = -0.5f; z <= 0.5f; z += resolution) for (float y = -0.5f; y <= 0.5f; y += resolution) for (float x = -0.5f; x <= 0.5f; x += resolution) - cloud.points.push_back (PointXYZ (x, y, z)); + cloud.points.emplace_back(x, y, z); cloud.width = static_cast (cloud.points.size ()); cloud.height = 1; @@ -64,9 +64,9 @@ init () srand (static_cast (time (NULL))); // Randomly create a new point cloud for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i) - cloud_big.points.push_back (PointXYZ (static_cast (1024 * rand () / (RAND_MAX + 1.0)), + cloud_big.points.emplace_back(static_cast (1024 * rand () / (RAND_MAX + 1.0)), static_cast (1024 * rand () / (RAND_MAX + 1.0)), - static_cast (1024 * rand () / (RAND_MAX + 1.0)))); + static_cast (1024 * rand () / (RAND_MAX + 1.0))); } /* Test for KdTree nearestKSearch */TEST (PCL, KdTree_nearestKSearch) diff --git a/test/search/test_organized.cpp b/test/search/test_organized.cpp index 4795e7df225..6d577f27ba1 100644 --- a/test/search/test_organized.cpp +++ b/test/search/test_organized.cpp @@ -129,7 +129,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) y = double (ypos * oneOverFocalLength * z); x = double (xpos * oneOverFocalLength * z); - cloudIn->points.push_back (PointXYZ (float (x), float (y), float (z))); + cloudIn->points.emplace_back(float (x), float (y), float (z)); } unsigned int searchIdx = rand()%(cloudIn->width * cloudIn->height); diff --git a/test/surface/test_convex_hull.cpp b/test/surface/test_convex_hull.cpp index 2eee9714ad8..e895fd8afac 100644 --- a/test/surface/test_convex_hull.cpp +++ b/test/surface/test_convex_hull.cpp @@ -348,10 +348,10 @@ TEST (PCL, ConvexHull_2dsquare) //Make sure they're actually near some edge std::vector > facets; - facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, 1.0)); - facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, -1.0)); - facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, 1.0)); - facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, -1.0)); + facets.emplace_back(-1.0, 0.0, 0.0, 1.0); + facets.emplace_back(-1.0, 0.0, 0.0, -1.0); + facets.emplace_back(0.0, -1.0, 0.0, 1.0); + facets.emplace_back(0.0, -1.0, 0.0, -1.0); //Make sure they're in the plane for (size_t i = 0; i < hull.points.size (); i++) @@ -404,12 +404,12 @@ TEST (PCL, ConvexHull_3dcube) //Make sure they're actually near some edge std::vector > facets; - facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, 1.0f)); - facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, -1.0f)); - facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, 1.0f)); - facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, -1.0f)); - facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, 1.0f)); - facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, -1.0f)); + facets.emplace_back(-1.0f, 0.0f, 0.0f, 1.0f); + facets.emplace_back(-1.0f, 0.0f, 0.0f, -1.0f); + facets.emplace_back(0.0f, -1.0f, 0.0f, 1.0f); + facets.emplace_back(0.0f, -1.0f, 0.0f, -1.0f); + facets.emplace_back(0.0f, 0.0f, -1.0f, 1.0f); + facets.emplace_back(0.0f, 0.0f, -1.0f, -1.0f); //Make sure they're near a facet for (size_t i = 0; i < hull.points.size (); i++) diff --git a/test/surface/test_ear_clipping.cpp b/test/surface/test_ear_clipping.cpp index 744ecb41bd3..97521682079 100644 --- a/test/surface/test_ear_clipping.cpp +++ b/test/surface/test_ear_clipping.cpp @@ -66,12 +66,12 @@ TEST (PCL, EarClipping) { PointCloud::Ptr cloud (new PointCloud()); cloud->height = 1; - cloud->points.push_back (PointXYZ ( 0.f, 0.f, 0.5f)); - cloud->points.push_back (PointXYZ ( 5.f, 0.f, 0.6f)); - cloud->points.push_back (PointXYZ ( 9.f, 4.f, 0.5f)); - cloud->points.push_back (PointXYZ ( 4.f, 7.f, 0.5f)); - cloud->points.push_back (PointXYZ ( 2.f, 5.f, 0.5f)); - cloud->points.push_back (PointXYZ (-1.f, 8.f, 0.5f)); + cloud->points.emplace_back( 0.f, 0.f, 0.5f); + cloud->points.emplace_back( 5.f, 0.f, 0.6f); + cloud->points.emplace_back( 9.f, 4.f, 0.5f); + cloud->points.emplace_back( 4.f, 7.f, 0.5f); + cloud->points.emplace_back( 2.f, 5.f, 0.5f); + cloud->points.emplace_back(-1.f, 8.f, 0.5f); cloud->width = static_cast (cloud->points.size ()); Vertices vertices; @@ -111,15 +111,15 @@ TEST (PCL, EarClippingCubeTest) PointCloud::Ptr cloud (new PointCloud()); cloud->height = 1; //bottom of cube (z=0) - cloud->points.push_back (PointXYZ ( 0.f, 0.f, 0.f)); - cloud->points.push_back (PointXYZ ( 1.f, 0.f, 0.f)); - cloud->points.push_back (PointXYZ ( 1.f, 1.f, 0.f)); - cloud->points.push_back (PointXYZ ( 0.f, 1.f, 0.f)); + cloud->points.emplace_back( 0.f, 0.f, 0.f); + cloud->points.emplace_back( 1.f, 0.f, 0.f); + cloud->points.emplace_back( 1.f, 1.f, 0.f); + cloud->points.emplace_back( 0.f, 1.f, 0.f); //top of cube (z=1.0) - cloud->points.push_back (PointXYZ ( 0.f, 0.f, 1.f)); - cloud->points.push_back (PointXYZ ( 1.f, 0.f, 1.f)); - cloud->points.push_back (PointXYZ ( 1.f, 1.f, 1.f)); - cloud->points.push_back (PointXYZ ( 0.f, 1.f, 1.f)); + cloud->points.emplace_back( 0.f, 0.f, 1.f); + cloud->points.emplace_back( 1.f, 0.f, 1.f); + cloud->points.emplace_back( 1.f, 1.f, 1.f); + cloud->points.emplace_back( 0.f, 1.f, 1.f); cloud->width = static_cast (cloud->points.size ()); Vertices vertices; diff --git a/test/surface/test_gp3.cpp b/test/surface/test_gp3.cpp index 032a5668597..f609f605b0a 100644 --- a/test/surface/test_gp3.cpp +++ b/test/surface/test_gp3.cpp @@ -184,7 +184,7 @@ TEST (PCL, UpdateMesh_With_TextureMapping) // update with texture mapping // set 2 texture for 2 mesh std::vector tex_files; - tex_files.push_back("tex4.jpg"); + tex_files.emplace_back("tex4.jpg"); // initialize texture mesh TextureMesh tex_mesh; diff --git a/tools/ndt2d.cpp b/tools/ndt2d.cpp index 6e6c636a5be..be3a2897ae7 100644 --- a/tools/ndt2d.cpp +++ b/tools/ndt2d.cpp @@ -56,19 +56,19 @@ void selfTest () { CloudPtr model (new Cloud); - model->points.push_back (PointType (1,1,0)); - model->points.push_back (PointType (4,4,0)); - model->points.push_back (PointType (5,6,0)); - model->points.push_back (PointType (3,3,0)); - model->points.push_back (PointType (6,7,0)); - model->points.push_back (PointType (7,11,0)); - model->points.push_back (PointType (12,15,0)); - model->points.push_back (PointType (7,12,0)); + model->points.emplace_back(1,1,0); + model->points.emplace_back(4,4,0); + model->points.emplace_back(5,6,0); + model->points.emplace_back(3,3,0); + model->points.emplace_back(6,7,0); + model->points.emplace_back(7,11,0); + model->points.emplace_back(12,15,0); + model->points.emplace_back(7,12,0); CloudPtr data (new Cloud); - data->points.push_back (PointType (3,1,0)); - data->points.push_back (PointType (7,4,0)); - data->points.push_back (PointType (9,6,0)); + data->points.emplace_back(3,1,0); + data->points.emplace_back(7,4,0); + data->points.emplace_back(9,6,0); pcl::console::setVerbosityLevel (pcl::console::L_DEBUG); diff --git a/tools/obj_rec_ransac_result.cpp b/tools/obj_rec_ransac_result.cpp index 915ae7d7b12..fb9e4436e5b 100644 --- a/tools/obj_rec_ransac_result.cpp +++ b/tools/obj_rec_ransac_result.cpp @@ -142,9 +142,9 @@ run (float pair_width, float voxel_size, float max_coplanarity_angle) // The models to be loaded list model_names; - model_names.push_back (string ("tum_amicelli_box")); - model_names.push_back (string ("tum_rusk_box")); - model_names.push_back (string ("tum_soda_bottle")); + model_names.emplace_back("tum_amicelli_box"); + model_names.emplace_back("tum_rusk_box"); + model_names.emplace_back("tum_soda_bottle"); list::Ptr> model_points_list; list::Ptr> model_normals_list; diff --git a/tools/uniform_sampling.cpp b/tools/uniform_sampling.cpp index 60caacc38da..a93e52b4f76 100644 --- a/tools/uniform_sampling.cpp +++ b/tools/uniform_sampling.cpp @@ -153,9 +153,9 @@ main (int argc, char** argv) // Parse the command line arguments for .pcd files vector p_file_indices; vector extension; - extension.push_back (".pcd"); - extension.push_back (".ply"); - extension.push_back (".vtk"); + extension.emplace_back(".pcd"); + extension.emplace_back(".ply"); + extension.emplace_back(".vtk"); p_file_indices = parse_file_extension_argument (argc, argv, extension); if (p_file_indices.size () != 2) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index cecea5888c5..de99e37cfe5 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -2044,7 +2044,7 @@ pcl::visualization::PCLVisualizer::getCameras (std::vectorGetNextItem ()) != NULL) { - cameras.push_back (Camera ()); + cameras.emplace_back(); cameras.back ().pos[0] = renderer->GetActiveCamera ()->GetPosition ()[0]; cameras.back ().pos[1] = renderer->GetActiveCamera ()->GetPosition ()[1]; cameras.back ().pos[2] = renderer->GetActiveCamera ()->GetPosition ()[2]; diff --git a/visualization/tools/pcd_viewer.cpp b/visualization/tools/pcd_viewer.cpp index 4fc9cb47f03..85dcdf37529 100644 --- a/visualization/tools/pcd_viewer.cpp +++ b/visualization/tools/pcd_viewer.cpp @@ -329,7 +329,7 @@ main (int argc, char** argv) if (shadings.size () != p_file_indices.size () && shadings.size () > 0) for (size_t i = shadings.size (); i < p_file_indices.size (); ++i) - shadings.push_back ("flat"); + shadings.emplace_back("flat"); // Create the PCLVisualizer object boost::shared_ptr ph;