diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/crh_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/crh_estimator.h index 0669a4f0e01..9cb2799d206 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/crh_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/crh_estimator.h @@ -43,7 +43,7 @@ namespace pcl void estimate (PointInTPtr & in, PointInTPtr & processed, std::vector, Eigen::aligned_allocator > > & signatures, - std::vector & centroids) + std::vector > & centroids) { if (!feature_estimator_) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/cvfh_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/cvfh_estimator.h index 97d0695923c..ec72062df84 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/cvfh_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/cvfh_estimator.h @@ -53,7 +53,7 @@ namespace pcl void estimate (PointInTPtr & in, PointInTPtr & processed, typename pcl::PointCloud::CloudVectorType & signatures, - std::vector & centroids) + std::vector > & centroids) { if (!normal_estimator_) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/esf_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/esf_estimator.h index 6a7c2a1cc04..2811f31c280 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/esf_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/esf_estimator.h @@ -25,7 +25,7 @@ namespace pcl void estimate (PointInTPtr & in, PointInTPtr & processed, typename pcl::PointCloud::CloudVectorType & signatures, - std::vector & centroids) + std::vector > & centroids) { typedef typename pcl::ESFEstimation ESFEstimation; diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/global_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/global_estimator.h index faee876b1bc..6bc63044949 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/global_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/global_estimator.h @@ -28,7 +28,7 @@ namespace pcl public: virtual void estimate (PointInTPtr & in, PointInTPtr & processed, std::vector, Eigen::aligned_allocator< - pcl::PointCloud > > & signatures, std::vector & centroids)=0; + pcl::PointCloud > > & signatures, std::vector > & centroids)=0; virtual bool computedNormals() = 0; diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/ourcvfh_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/ourcvfh_estimator.h index e7c36511b52..c9b7ef2d8f7 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/ourcvfh_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/ourcvfh_estimator.h @@ -81,7 +81,7 @@ namespace pcl virtual void estimate (PointInTPtr & in, PointInTPtr & processed, typename pcl::PointCloud::CloudVectorType & signatures, - std::vector & centroids) + std::vector > & centroids) { valid_roll_transforms_.clear (); diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/vfh_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/vfh_estimator.h index 660ac461158..e3efc962eeb 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/vfh_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/global/vfh_estimator.h @@ -28,7 +28,7 @@ namespace pcl void estimate (PointInTPtr & in, PointInTPtr & processed, typename pcl::PointCloud::CloudVectorType & signatures, - std::vector & centroids) + std::vector > & centroids) { if (!normal_estimator_) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h index b84e5800b11..f6759c0d349 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h @@ -100,7 +100,7 @@ namespace pcl } void - assembleModelFromViewsAndPoses(ModelT & model, std::vector & poses) { + assembleModelFromViewsAndPoses(ModelT & model, std::vector > & poses) { for(size_t i=0; i < model.views_->size(); i++) { Eigen::Matrix4f inv = poses[i]; typename pcl::PointCloud::Ptr global_cloud(new pcl::PointCloud); @@ -159,7 +159,7 @@ namespace pcl } } - std::vector poses_to_assemble_; + std::vector > poses_to_assemble_; for (size_t i = 0; i < view_filenames.size (); i++) { diff --git a/apps/src/render_views_tesselated_sphere.cpp b/apps/src/render_views_tesselated_sphere.cpp index 48e7dfe8ab5..ccf3f20191e 100644 --- a/apps/src/render_views_tesselated_sphere.cpp +++ b/apps/src/render_views_tesselated_sphere.cpp @@ -121,7 +121,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() { // Get camera positions vtkPolyData *sphere = subdivide->GetOutput (); - std::vector cam_positions; + std::vector > cam_positions; if (!use_vertices_) { vtkSmartPointer cells_sphere = sphere->GetPolys (); diff --git a/common/include/pcl/TextureMesh.h b/common/include/pcl/TextureMesh.h index 4a7f673bc05..2fd1233d64a 100644 --- a/common/include/pcl/TextureMesh.h +++ b/common/include/pcl/TextureMesh.h @@ -98,7 +98,7 @@ namespace pcl std::vector > tex_polygons; // polygon which is mapped with specific texture defined in TexMaterial - std::vector > tex_coordinates; // UV coordinates + std::vector > > tex_coordinates; // UV coordinates std::vector tex_materials; // define texture material public: diff --git a/common/include/pcl/common/impl/polynomial_calculations.hpp b/common/include/pcl/common/impl/polynomial_calculations.hpp index 4b6a4958628..49c886925a9 100644 --- a/common/include/pcl/common/impl/polynomial_calculations.hpp +++ b/common/include/pcl/common/impl/polynomial_calculations.hpp @@ -372,7 +372,7 @@ inline void template inline pcl::BivariatePolynomialT pcl::PolynomialCalculationsT::bivariatePolynomialApproximation ( - std::vector >& samplePoints, unsigned int polynomial_degree, bool& error) const + std::vector, Eigen::aligned_allocator > >& samplePoints, unsigned int polynomial_degree, bool& error) const { pcl::BivariatePolynomialT ret; error = bivariatePolynomialApproximation (samplePoints, polynomial_degree, ret); @@ -384,7 +384,7 @@ inline pcl::BivariatePolynomialT template inline bool pcl::PolynomialCalculationsT::bivariatePolynomialApproximation ( - std::vector >& samplePoints, unsigned int polynomial_degree, + std::vector, Eigen::aligned_allocator > >& samplePoints, unsigned int polynomial_degree, pcl::BivariatePolynomialT& ret) const { //MEASURE_FUNCTION_TIME; @@ -415,7 +415,7 @@ inline bool real tmpX, tmpY; real *tmpC = new real[parameters_size]; real* tmpCEndPtr = &tmpC[parameters_size-1]; - for (typename std::vector >::const_iterator it=samplePoints.begin (); + for (typename std::vector, Eigen::aligned_allocator > >::const_iterator it=samplePoints.begin (); it!=samplePoints.end (); ++it) { currentX= (*it)[0]; currentY= (*it)[1]; currentZ= (*it)[2]; @@ -465,7 +465,7 @@ inline bool //unsigned int posInC; //real tmpX, tmpY; //DVector tmpC (parameters_size); - //for (typename std::vector >::const_iterator it=samplePoints.begin (); + //for (typename std::vector, Eigen::aligned_allocator > >::const_iterator it=samplePoints.begin (); // it!=samplePoints.end (); ++it) //{ //currentX= (*it)[0]; currentY= (*it)[1]; currentZ= (*it)[2]; diff --git a/common/include/pcl/common/polynomial_calculations.h b/common/include/pcl/common/polynomial_calculations.h index 9312731d244..111d41fe30b 100644 --- a/common/include/pcl/common/polynomial_calculations.h +++ b/common/include/pcl/common/polynomial_calculations.h @@ -93,12 +93,12 @@ namespace pcl * error is set to true if the approximation did not work for any reason * (not enough points, matrix not invertible, etc.) */ inline BivariatePolynomialT - bivariatePolynomialApproximation (std::vector >& samplePoints, + bivariatePolynomialApproximation (std::vector, Eigen::aligned_allocator > >& samplePoints, unsigned int polynomial_degree, bool& error) const; //! Same as above, using a reference for the return value inline bool - bivariatePolynomialApproximation (std::vector >& samplePoints, + bivariatePolynomialApproximation (std::vector, Eigen::aligned_allocator > >& samplePoints, unsigned int polynomial_degree, BivariatePolynomialT& ret) const; //! Set the minimum value under which values are considered zero diff --git a/features/include/pcl/features/cvfh.h b/features/include/pcl/features/cvfh.h index 95334dec6ce..1e2dfc6df6b 100644 --- a/features/include/pcl/features/cvfh.h +++ b/features/include/pcl/features/cvfh.h @@ -148,7 +148,7 @@ namespace pcl * \param[out] centroids vector to hold the centroids */ inline void - getCentroidClusters (std::vector & centroids) + getCentroidClusters (std::vector > & centroids) { for (size_t i = 0; i < centroids_dominant_orientations_.size (); ++i) centroids.push_back (centroids_dominant_orientations_[i]); @@ -158,7 +158,7 @@ namespace pcl * \param[out] centroids vector to hold the normal centroids */ inline void - getCentroidNormalClusters (std::vector & centroids) + getCentroidNormalClusters (std::vector > & centroids) { for (size_t i = 0; i < dominant_normals_.size (); ++i) centroids.push_back (dominant_normals_[i]); @@ -280,9 +280,9 @@ namespace pcl protected: /** \brief Centroids that were used to compute different CVFH descriptors */ - std::vector centroids_dominant_orientations_; + std::vector > centroids_dominant_orientations_; /** \brief Normal centroids that were used to compute different CVFH descriptors */ - std::vector dominant_normals_; + std::vector > dominant_normals_; }; } diff --git a/features/include/pcl/features/impl/rops_estimation.hpp b/features/include/pcl/features/impl/rops_estimation.hpp index f573a2693de..dadcb31893a 100644 --- a/features/include/pcl/features/impl/rops_estimation.hpp +++ b/features/include/pcl/features/impl/rops_estimation.hpp @@ -237,7 +237,7 @@ pcl::ROPSEstimation ::computeLRF (const PointInT& point, co { const unsigned int number_of_triangles = static_cast (local_triangles.size ()); - std::vector scatter_matrices (number_of_triangles); + std::vector > scatter_matrices (number_of_triangles); std::vector triangle_area (number_of_triangles); std::vector distance_weight (number_of_triangles); diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index 5d5bc150639..39a9333263d 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -192,7 +192,7 @@ namespace pcl * \param[out] centroids vector to hold the centroids */ inline void - getCentroidClusters (std::vector & centroids) + getCentroidClusters (std::vector > & centroids) { for (size_t i = 0; i < centroids_dominant_orientations_.size (); ++i) centroids.push_back (centroids_dominant_orientations_[i]); @@ -202,7 +202,7 @@ namespace pcl * \param[out] centroids vector to hold the normal centroids */ inline void - getCentroidNormalClusters (std::vector & centroids) + getCentroidNormalClusters (std::vector > & centroids) { for (size_t i = 0; i < dominant_normals_.size (); ++i) centroids.push_back (dominant_normals_[i]); @@ -395,9 +395,9 @@ namespace pcl protected: /** \brief Centroids that were used to compute different OUR-CVFH descriptors */ - std::vector centroids_dominant_orientations_; + std::vector > centroids_dominant_orientations_; /** \brief Normal centroids that were used to compute different OUR-CVFH descriptors */ - std::vector dominant_normals_; + std::vector > dominant_normals_; /** \brief Indices to the points representing the stable clusters */ std::vector clusters_; /** \brief Mapping from clusters to OUR-CVFH descriptors */ diff --git a/features/include/pcl/features/principal_curvatures.h b/features/include/pcl/features/principal_curvatures.h index 73c089237a9..8f682039786 100644 --- a/features/include/pcl/features/principal_curvatures.h +++ b/features/include/pcl/features/principal_curvatures.h @@ -116,7 +116,7 @@ namespace pcl private: /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */ - std::vector projected_normals_; + std::vector > projected_normals_; /** \brief SSE aligned placeholder for the XYZ centroid of a surface patch. */ Eigen::Vector3f xyz_centroid_; diff --git a/filters/include/pcl/filters/covariance_sampling.h b/filters/include/pcl/filters/covariance_sampling.h index 6d41efc5f3e..a3f651fc358 100644 --- a/filters/include/pcl/filters/covariance_sampling.h +++ b/filters/include/pcl/filters/covariance_sampling.h @@ -137,7 +137,7 @@ namespace pcl /** \brief The normals computed at each point in the input cloud */ NormalsConstPtr input_normals_; - std::vector scaled_points_; + std::vector > scaled_points_; bool initCompute (); diff --git a/filters/include/pcl/filters/fast_bilateral.h b/filters/include/pcl/filters/fast_bilateral.h index 84f818ce458..e6bdf8046c1 100644 --- a/filters/include/pcl/filters/fast_bilateral.h +++ b/filters/include/pcl/filters/fast_bilateral.h @@ -122,7 +122,7 @@ namespace pcl x_dim_ = width; y_dim_ = height; z_dim_ = depth; - v_ = std::vector (width*height*depth, Eigen::Vector2f (0.0f, 0.0f)); + v_ = std::vector > (width*height*depth, Eigen::Vector2f (0.0f, 0.0f)); } inline Eigen::Vector2f& @@ -164,24 +164,24 @@ namespace pcl z_size () const { return z_dim_; } - inline std::vector::iterator + inline std::vector >::iterator begin () { return v_.begin (); } - inline std::vector::iterator + inline std::vector >::iterator end () { return v_.end (); } - inline std::vector::const_iterator + inline std::vector >::const_iterator begin () const { return v_.begin (); } - inline std::vector::const_iterator + inline std::vector >::const_iterator end () const { return v_.end (); } private: - std::vector v_; + std::vector > v_; size_t x_dim_, y_dim_, z_dim_; }; diff --git a/filters/include/pcl/filters/impl/fast_bilateral.hpp b/filters/include/pcl/filters/impl/fast_bilateral.hpp index c5dbc5c9459..44601ec3cd2 100644 --- a/filters/include/pcl/filters/impl/fast_bilateral.hpp +++ b/filters/include/pcl/filters/impl/fast_bilateral.hpp @@ -136,7 +136,7 @@ pcl::FastBilateralFilter::applyFilter (PointCloud &output) if (early_division_) { - for (std::vector::iterator d = data.begin (); d != data.end (); ++d) + for (std::vector >::iterator d = data.begin (); d != data.end (); ++d) *d /= ((*d)[0] != 0) ? (*d)[1] : 1; for (size_t x = 0; x < input_->width; x++) diff --git a/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp b/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp index aae2c518687..ee72418401b 100644 --- a/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp +++ b/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp @@ -158,7 +158,7 @@ pcl::FastBilateralFilterOMP::applyFilter (PointCloud &output) if (early_division_) { - for (std::vector::iterator d = data.begin (); d != data.end (); ++d) + for (std::vector >::iterator d = data.begin (); d != data.end (); ++d) *d /= ((*d)[0] != 0) ? (*d)[1] : 1; #ifdef _OPENMP diff --git a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp index 5e409aae3ce..d50a3871f5a 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp @@ -99,7 +99,7 @@ pcl::VoxelGridOcclusionEstimation::occlusionEstimation (int& out_state, ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template int pcl::VoxelGridOcclusionEstimation::occlusionEstimation (int& out_state, - std::vector& out_ray, + std::vector >& out_ray, const Eigen::Vector3i& in_target_voxel) { if (!initialized_) @@ -130,7 +130,7 @@ pcl::VoxelGridOcclusionEstimation::occlusionEstimation (int& out_state, ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template int -pcl::VoxelGridOcclusionEstimation::occlusionEstimationAll (std::vector& occluded_voxels) +pcl::VoxelGridOcclusionEstimation::occlusionEstimationAll (std::vector >& occluded_voxels) { if (!initialized_) { @@ -334,7 +334,7 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (const Eigen::Vector3i& ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template int -pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector & out_ray, +pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector >& out_ray, const Eigen::Vector3i& target_voxel, const Eigen::Vector4f& origin, const Eigen::Vector4f& direction, diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 2d2c464f29d..5b3f03f074b 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -689,12 +689,12 @@ namespace pcl * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed */ inline std::vector - getNeighborCentroidIndices (float x, float y, float z, const std::vector &relative_coordinates) + getNeighborCentroidIndices (float x, float y, float z, const std::vector > &relative_coordinates) { Eigen::Vector4i ijk (static_cast (floorf (x * inverse_leaf_size_[0])), static_cast (floorf (y * inverse_leaf_size_[1])), static_cast (floorf (z * inverse_leaf_size_[2])), 0); std::vector neighbors; neighbors.reserve (relative_coordinates.size ()); - for (std::vector::const_iterator it = relative_coordinates.begin (); it != relative_coordinates.end (); it++) + for (std::vector >::const_iterator it = relative_coordinates.begin (); it != relative_coordinates.end (); it++) neighbors.push_back (leaf_layout_[(ijk + (Eigen::Vector4i() << *it, 0).finished() - min_b_).dot (divb_mul_)]); return (neighbors); } diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index 90e46b06270..8b34edb5a0b 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -109,7 +109,7 @@ namespace pcl */ int occlusionEstimation (int& out_state, - std::vector& out_ray, + std::vector >& out_ray, const Eigen::Vector3i& in_target_voxel); /** \brief Returns the voxel coordinates (i, j, k) of all occluded @@ -118,7 +118,7 @@ namespace pcl * \return the voxel coordinates (i, j, k) */ int - occlusionEstimationAll (std::vector& occluded_voxels); + occlusionEstimationAll (std::vector >& occluded_voxels); /** \brief Returns the voxel grid filtered point cloud * \return The voxel grid filtered point cloud @@ -202,7 +202,7 @@ namespace pcl * \return The estimated voxel state. */ int - rayTraversal (std::vector & out_ray, + rayTraversal (std::vector >& out_ray, const Eigen::Vector3i& target_voxel, const Eigen::Vector4f& origin, const Eigen::Vector4f& direction, diff --git a/geometry/include/pcl/geometry/impl/polygon_operations.hpp b/geometry/include/pcl/geometry/impl/polygon_operations.hpp index 64a3d435de1..f595139c33e 100644 --- a/geometry/include/pcl/geometry/impl/polygon_operations.hpp +++ b/geometry/include/pcl/geometry/impl/polygon_operations.hpp @@ -180,7 +180,7 @@ pcl::approximatePolygon2D (const typename pcl::PointCloud::VectorType &p approx_polygon.reserve (result.size ()); if (refine) { - std::vector lines (result.size ()); + std::vector > lines (result.size ()); std::reverse (result.begin (), result.end ()); for (unsigned rIdx = 0; rIdx < result.size (); ++rIdx) { diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/standalone_marching_cubes.hpp b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/standalone_marching_cubes.hpp index 721c72f5421..5b7637592c9 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/standalone_marching_cubes.hpp +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/standalone_marching_cubes.hpp @@ -92,7 +92,7 @@ pcl::gpu::kinfuLS::StandaloneMarchingCubes::getMeshFromTSDFCloud (const //template std::vector< typename pcl::gpu::StandaloneMarchingCubes::MeshPtr > template void -pcl::gpu::kinfuLS::StandaloneMarchingCubes::getMeshesFromTSDFVector (const std::vector &tsdf_clouds, const std::vector &tsdf_offsets) +pcl::gpu::kinfuLS::StandaloneMarchingCubes::getMeshesFromTSDFVector (const std::vector &tsdf_clouds, const std::vector > &tsdf_offsets) { std::vector< MeshPtr > meshes_vector; diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/world_model.hpp b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/world_model.hpp index c4bbe606290..d5727463832 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/world_model.hpp +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/impl/world_model.hpp @@ -130,7 +130,7 @@ pcl::kinfuLS::WorldModel::getExistingData(const double previous_origin_x template void -pcl::kinfuLS::WorldModel::getWorldAsCubes (const double size, std::vector::PointCloudPtr> &cubes, std::vector &transforms, double overlap) +pcl::kinfuLS::WorldModel::getWorldAsCubes (const double size, std::vector::PointCloudPtr> &cubes, std::vector > &transforms, double overlap) { if(world_->points.size () == 0) diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h index 74ccbbb8d2e..8e42e3c4b5a 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/standalone_marching_cubes.h @@ -102,7 +102,7 @@ namespace pcl * \param[in] tsdf_offsets Vector of the offsets for every pointcloud in TsdfClouds. This offset (in indices) indicates the position of the cloud with respect to the absolute origin of the world model */ void - getMeshesFromTSDFVector (const std::vector &tsdf_clouds, const std::vector &tsdf_offsets); + getMeshesFromTSDFVector (const std::vector &tsdf_clouds, const std::vector > &tsdf_offsets); /** \brief Returns the associated Tsdf Volume buffer in GPU * \return pointer to the Tsdf Volume buffer in GPU diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h index 82522cd71b4..9f3f396623c 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/world_model.h @@ -165,7 +165,7 @@ namespace pcl * \param[out] transforms a vector containing the xyz position of each cube in world coordinates. * \param[in] overlap optional overlap (in percent) between each cube (usefull to create overlapped meshes). */ - void getWorldAsCubes (double size, std::vector &cubes, std::vector &transforms, double overlap = 0.0); + void getWorldAsCubes (double size, std::vector &cubes, std::vector > &transforms, double overlap = 0.0); private: diff --git a/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp b/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp index f284d3ccf45..bdacee225f8 100644 --- a/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp +++ b/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp @@ -87,7 +87,7 @@ main (int argc, char** argv) wm.addSlice (cloud); std::vector::Ptr> clouds; - std::vector transforms; + std::vector > transforms; //Get world as a vector of cubes wm.getWorldAsCubes (pcl::device::kinfuLS::VOLUME_X, clouds, transforms, 0.025); // 2.5% overlapp (12 cells with a 512-wide cube) diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 0ddb11eeff3..edfe4da79e6 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -692,7 +692,7 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, std::size_t f_idx = 0; std::string line; std::vector st; - std::vector coordinates; + std::vector > coordinates; try { while (!fs.eof ()) diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index 257138b6ac9..983d9c277eb 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -367,7 +367,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer& poly_data, pcl::TextureMe // Add dummy material mesh.tex_materials.push_back (pcl::TexMaterial ()); - std::vector dummy; + std::vector > dummy; mesh.tex_coordinates.push_back (dummy); vtkIdType nr_points = poly_data->GetNumberOfPoints (); diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index 9d2309a7cc5..0ff59acc90e 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -724,7 +724,7 @@ NarfKeypoint::calculateInterestPoints () typedef double RealForPolynomial; PolynomialCalculationsT polynomial_calculations; BivariatePolynomialT polynomial (2); - std::vector > sample_points; + std::vector, Eigen::aligned_allocator > > sample_points; std::vector x_values, y_values; std::vector types; std::vector invalid_beams, old_invalid_beams; diff --git a/ml/include/pcl/ml/densecrf.h b/ml/include/pcl/ml/densecrf.h index 25f0b5c0303..7b7f9da44a6 100644 --- a/ml/include/pcl/ml/densecrf.h +++ b/ml/include/pcl/ml/densecrf.h @@ -65,12 +65,12 @@ namespace pcl * coordinates as ijk of the voxel grid */ void - setDataVector (const std::vector data); + setDataVector (const std::vector > data); /** \brief The associated color of the data */ void - setColorVector (const std::vector color); + setColorVector (const std::vector > color); void setUnaryEnergy (const std::vector unary); @@ -96,8 +96,8 @@ namespace pcl void - addPairwiseNormals (std::vector &coord, - std::vector &normals, + addPairwiseNormals (std::vector > &coord, + std::vector > &normals, float sx, float sy, float sz, float snx, float sny, float snz, float w); @@ -139,10 +139,10 @@ namespace pcl int N_, M_; /** \brief Data vector */ - std::vector data_; + std::vector > data_; /** \brief Color vector */ - std::vector color_; + std::vector > color_; /** TODO: double might use to much memory */ /** \brief CRF unary potentials */ diff --git a/ml/src/densecrf.cpp b/ml/src/densecrf.cpp index 0277961e9fc..e5a25f93f40 100644 --- a/ml/src/densecrf.cpp +++ b/ml/src/densecrf.cpp @@ -58,7 +58,7 @@ pcl::DenseCrf::~DenseCrf () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void -pcl::DenseCrf::setDataVector (const std::vector data) +pcl::DenseCrf::setDataVector (const std::vector > data) { xyz_ = true; data_ = data; @@ -66,7 +66,7 @@ pcl::DenseCrf::setDataVector (const std::vector data) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void -pcl::DenseCrf::setColorVector (const std::vector color) +pcl::DenseCrf::setColorVector (const std::vector > color) { rgb_ = true; color_ = color; @@ -133,8 +133,8 @@ pcl::DenseCrf::addPairwiseBilateral (float sx, float sy, float sz, ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void -pcl::DenseCrf::addPairwiseNormals (std::vector &coord, - std::vector &normals, +pcl::DenseCrf::addPairwiseNormals (std::vector > &coord, + std::vector > &normals, float sx, float sy, float sz, float snx, float sny, float snz, float w) diff --git a/recognition/include/pcl/recognition/cg/hough_3d.h b/recognition/include/pcl/recognition/cg/hough_3d.h index feb0c154280..85eda6c8fd4 100644 --- a/recognition/include/pcl/recognition/cg/hough_3d.h +++ b/recognition/include/pcl/recognition/cg/hough_3d.h @@ -447,7 +447,7 @@ namespace pcl bool needs_training_; /** \brief The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.*/ - std::vector model_votes_; + std::vector > model_votes_; /** \brief The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. */ double hough_threshold_; diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h index e9e650cdf3c..b5247bc8487 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h @@ -33,13 +33,13 @@ namespace pcl std::string directory_; float HEAD_ST_DIAMETER_; float larger_radius_ratio_; - std::vector head_center_votes_; - std::vector > head_center_votes_clustered_; - std::vector > head_center_original_votes_clustered_; - std::vector angle_votes_; + std::vector > head_center_votes_; + std::vector, Eigen::aligned_allocator > head_center_votes_clustered_; + std::vector, Eigen::aligned_allocator > head_center_original_votes_clustered_; + std::vector > angle_votes_; std::vector uncertainties_; - std::vector head_clusters_centers_; - std::vector head_clusters_rotation_; + std::vector > head_clusters_centers_; + std::vector > head_clusters_rotation_; pcl::PointCloud::Ptr input_; pcl::PointCloud::Ptr face_heat_map_; diff --git a/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp b/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp index b80fdb14211..030cae3624d 100644 --- a/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp +++ b/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp @@ -177,7 +177,7 @@ pcl::Hough3DGrouping::ho return (false); } - std::vector scene_votes (n_matches); + std::vector > scene_votes (n_matches); Eigen::Vector3d d_min, d_max, bin_size; d_min.setConstant (std::numeric_limits::max ()); diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index efdbf84f8a1..85e25c1596d 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -141,7 +141,7 @@ pcl::features::ISMVoteList::findStrongestPeaks ( double SIGMA_DIST = in_sigma;// rule of thumb: 10% of the object radius const double FINAL_EPS = SIGMA_DIST / 100;// another heuristic - std::vector peaks (NUM_INIT_PTS); + std::vector > peaks (NUM_INIT_PTS); std::vector peak_densities (NUM_INIT_PTS); double max_density = -1.0; for (int i = 0; i < NUM_INIT_PTS; i++) @@ -1288,7 +1288,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe Eigen::MatrixXf centers (number_of_clusters, feature_dimension); Eigen::MatrixXf old_centers (number_of_clusters, feature_dimension); std::vector counters (number_of_clusters); - std::vector boxes (feature_dimension); + std::vector > boxes (feature_dimension); Eigen::Vector2f* box = &boxes[0]; double best_compactness = std::numeric_limits::max (); @@ -1504,7 +1504,7 @@ pcl::ism::ImplicitShapeModelEstimation::generateCe ////////////////////////////////////////////////////////////////////////////////////////////// template void -pcl::ism::ImplicitShapeModelEstimation::generateRandomCenter (const std::vector& boxes, +pcl::ism::ImplicitShapeModelEstimation::generateRandomCenter (const std::vector >& boxes, Eigen::VectorXf& center) { size_t dimension = boxes.size (); diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index 7acd17dc680..c643ef30fa2 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -565,7 +565,7 @@ namespace pcl * \param[out] center it will the contain generated center */ void - generateRandomCenter (const std::vector& boxes, Eigen::VectorXf& center); + generateRandomCenter (const std::vector >& boxes, Eigen::VectorXf& center); /** \brief Computes the square distance beetween two vectors. * \param[in] vec_1 first vector diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 4e565117264..ba11d622490 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -266,13 +266,13 @@ namespace pcl /** \brief Input cloud points covariances. */ - std::vector input_covariances_; + std::vector > input_covariances_; /** \brief Target cloud points covariances. */ - std::vector target_covariances_; + std::vector > target_covariances_; /** \brief Mahalanobis matrices holder. */ - std::vector mahalanobis_; + std::vector > mahalanobis_; /** \brief maximum number of optimizations */ int max_inner_iterations_; @@ -286,7 +286,7 @@ namespace pcl template void computeCovariances(typename pcl::PointCloud::ConstPtr cloud, const typename pcl::search::KdTree::Ptr tree, - std::vector& cloud_covariances); + std::vector >& cloud_covariances); /** \return trace of mat1^t . mat2 * \param mat1 matrix of dimension nxm diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index c430b0f13ba..43079f4c9cb 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -56,7 +56,7 @@ template template void pcl::GeneralizedIterativeClosestPoint::computeCovariances(typename pcl::PointCloud::ConstPtr cloud, const typename pcl::search::KdTree::Ptr kdtree, - std::vector& cloud_covariances) + std::vector >& cloud_covariances) { if (k_correspondences_ > int (cloud->size ())) { @@ -73,7 +73,7 @@ pcl::GeneralizedIterativeClosestPoint::computeCovarian cloud_covariances.resize (cloud->size ()); typename pcl::PointCloud::const_iterator points_iterator = cloud->begin (); - std::vector::iterator matrices_iterator = cloud_covariances.begin (); + std::vector >::iterator matrices_iterator = cloud_covariances.begin (); for(; points_iterator != cloud->end (); ++points_iterator, ++matrices_iterator) diff --git a/registration/include/pcl/registration/impl/lum.hpp b/registration/include/pcl/registration/impl/lum.hpp index 7f854a9396f..4dd0877d9ce 100644 --- a/registration/include/pcl/registration/impl/lum.hpp +++ b/registration/include/pcl/registration/impl/lum.hpp @@ -304,8 +304,8 @@ pcl::registration::LUM::computeEdge (const Edge &e) pcl::CorrespondencesPtr corrs = (*slam_graph_)[e].corrs_; // Build the average and difference vectors for all correspondences - std::vector corrs_aver (corrs->size ()); - std::vector corrs_diff (corrs->size ()); + std::vector > corrs_aver (corrs->size ()); + std::vector > corrs_diff (corrs->size ()); int oci = 0; // oci = output correspondence iterator for (int ici = 0; ici != static_cast (corrs->size ()); ++ici) // ici = input correspondence iterator { diff --git a/segmentation/include/pcl/segmentation/crf_segmentation.h b/segmentation/include/pcl/segmentation/crf_segmentation.h index 942778f691b..a84d3e33017 100644 --- a/segmentation/include/pcl/segmentation/crf_segmentation.h +++ b/segmentation/include/pcl/segmentation/crf_segmentation.h @@ -169,11 +169,11 @@ namespace pcl /** \brief voxel grid data points packing order [x0y0z0, x1y0z0,x2y0z0,...,x0y1z0,x1y1z0,...,x0y0z1,x1y0z1,...] */ - std::vector data_; + std::vector > data_; - std::vector color_; + std::vector > color_; - std::vector normal_; + std::vector > normal_; /** \brief smoothness kernel parameters * [0] = standard deviation x diff --git a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp index 8937305676c..a9fadf3828b 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp @@ -220,8 +220,8 @@ pcl::CrfSegmentation::createDataVectorFromVoxelGrid () //data_.reserve (dim_.x () * dim_.y () * dim_.z ()); /* - std::vector data; - std::vector color; + std::vector > data; + std::vector > color; // fill the data vector for (int kk = min_b.z (), k = 0; kk <= max_b.z (); kk++, k++) { diff --git a/simulation/include/pcl/simulation/range_likelihood.h b/simulation/include/pcl/simulation/range_likelihood.h index aa080522204..e1e37c8726d 100644 --- a/simulation/include/pcl/simulation/range_likelihood.h +++ b/simulation/include/pcl/simulation/range_likelihood.h @@ -225,7 +225,7 @@ namespace pcl gllib::Program::Ptr likelihood_program_; GLuint quad_vbo_; - std::vector vertices_; + std::vector > vertices_; float* score_buffer_; Quad quad_; SumReduce sum_reduce_; diff --git a/surface/include/pcl/surface/gp3.h b/surface/include/pcl/surface/gp3.h index e62b05ef71e..50218ee149e 100644 --- a/surface/include/pcl/surface/gp3.h +++ b/surface/include/pcl/surface/gp3.h @@ -358,7 +358,7 @@ namespace pcl /** \brief Temporary variable to store a triangle (as a set of point indices) **/ pcl::Vertices triangle_; /** \brief Temporary variable to store point coordinates **/ - std::vector coords_; + std::vector > coords_; /** \brief A list of angles to neighbors **/ std::vector angles_; diff --git a/surface/include/pcl/surface/impl/gp3.hpp b/surface/include/pcl/surface/impl/gp3.hpp index 9e915b65a10..226c9f007ab 100644 --- a/surface/include/pcl/surface/impl/gp3.hpp +++ b/surface/include/pcl/surface/impl/gp3.hpp @@ -138,7 +138,7 @@ pcl::GreedyProjectionTriangulation::reconstructPolygons (std::vector

uvn_nn (nnn_); + std::vector > uvn_nn (nnn_); Eigen::Vector2f uvn_s; // iterating through fringe points and finishing them until everything is done diff --git a/surface/include/pcl/surface/impl/marching_cubes.hpp b/surface/include/pcl/surface/impl/marching_cubes.hpp index 12c0ca50434..16b7690f446 100644 --- a/surface/include/pcl/surface/impl/marching_cubes.hpp +++ b/surface/include/pcl/surface/impl/marching_cubes.hpp @@ -122,7 +122,7 @@ pcl::MarchingCubes::createSurface (std::vector &leaf_node, center[1] = min_p_[1] + (max_p_[1] - min_p_[1]) * float (index_3d[1]) / float (res_y_); center[2] = min_p_[2] + (max_p_[2] - min_p_[2]) * float (index_3d[2]) / float (res_z_); - std::vector p; + std::vector > p; p.resize (8); for (int i = 0; i < 8; ++i) { diff --git a/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp b/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp index 4f52ca58811..33552f37169 100644 --- a/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp +++ b/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp @@ -90,7 +90,7 @@ pcl::MarchingCubesRBF::voxelizeData () w = M.fullPivLu ().solve (d); std::vector weights (2*N); - std::vector centers (2*N); + std::vector > centers (2*N); for (unsigned int i = 0; i < N; ++i) { centers[i] = Eigen::Vector3f (input_->points[i].getVector3fMap ()).cast (); @@ -110,7 +110,7 @@ pcl::MarchingCubesRBF::voxelizeData () double f = 0.0; std::vector::const_iterator w_it (weights.begin()); - for (std::vector::const_iterator c_it = centers.begin (); + for (std::vector >::const_iterator c_it = centers.begin (); c_it != centers.end (); ++c_it, ++w_it) f += *w_it * kernel (*c_it, point); diff --git a/surface/include/pcl/surface/impl/mls.hpp b/surface/include/pcl/surface/impl/mls.hpp index 374dc24e1e5..f7df1399c91 100644 --- a/surface/include/pcl/surface/impl/mls.hpp +++ b/surface/include/pcl/surface/impl/mls.hpp @@ -216,7 +216,7 @@ pcl::MovingLeastSquares::computeMLSPointNormal (int index, { // Update neighborhood, since point was projected, and computing relative // positions. Note updating only distances for the weights for speed - std::vector de_meaned (nn_indices.size ()); + std::vector > de_meaned (nn_indices.size ()); for (size_t ni = 0; ni < nn_indices.size (); ++ni) { de_meaned[ni][0] = input_->points[nn_indices[ni]].x - point[0]; diff --git a/surface/include/pcl/surface/impl/texture_mapping.hpp b/surface/include/pcl/surface/impl/texture_mapping.hpp index 8c0828a4a0e..ed7bd504f5c 100644 --- a/surface/include/pcl/surface/impl/texture_mapping.hpp +++ b/surface/include/pcl/surface/impl/texture_mapping.hpp @@ -42,13 +42,13 @@ #include /////////////////////////////////////////////////////////////////////////////////////////////// -template std::vector +template std::vector > pcl::TextureMapping::mapTexture2Face ( const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3) { - std::vector tex_coordinates; + std::vector > tex_coordinates; // process for each face Eigen::Vector3f p1p2 (p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]); Eigen::Vector3f p1p3 (p3[0] - p1[0], p3[1] - p1[1], p3[2] - p1[2]); @@ -153,12 +153,12 @@ pcl::TextureMapping::mapTexture2Mesh (pcl::TextureMesh &tex_mesh) Eigen::Vector3f facet[3]; // texture coordinates for each mesh - std::vector > texture_map; + std::vector > >texture_map; for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m) { // texture coordinates for each mesh - std::vector texture_map_tmp; + std::vector > texture_map_tmp; // processing for each face for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i) @@ -178,7 +178,7 @@ pcl::TextureMapping::mapTexture2Mesh (pcl::TextureMesh &tex_mesh) } // get texture coordinates of each face - std::vector tex_coordinates = mapTexture2Face (facet[0], facet[1], facet[2]); + std::vector > tex_coordinates = mapTexture2Face (facet[0], facet[1], facet[2]); for (size_t n = 0; n < tex_coordinates.size (); ++n) texture_map_tmp.push_back (tex_coordinates[n]); }// end faces @@ -244,12 +244,12 @@ pcl::TextureMapping::mapTexture2MeshUV (pcl::TextureMesh &tex_mesh) float z_offset = 0 - z_lowest; // texture coordinates for each mesh - std::vector > texture_map; + std::vector > >texture_map; for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m) { // texture coordinates for each mesh - std::vector texture_map_tmp; + std::vector > texture_map_tmp; // processing for each face for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i) @@ -303,7 +303,7 @@ pcl::TextureMapping::mapMultipleTexturesToMeshUV (pcl::TextureMesh &te pcl::fromPCLPointCloud2 (tex_mesh.cloud, *originalCloud); // texture coordinates for each mesh - std::vector > texture_map; + std::vector > > texture_map; for (size_t m = 0; m < cams.size (); ++m) { @@ -317,7 +317,7 @@ pcl::TextureMapping::mapMultipleTexturesToMeshUV (pcl::TextureMesh &te pcl::transformPointCloud (*originalCloud, *camera_transformed_cloud, cam_trans.inverse ()); // vector of texture coordinates for each face - std::vector texture_map_tmp; + std::vector > texture_map_tmp; // processing each face visible by this camera PointInT pt; @@ -351,7 +351,7 @@ pcl::TextureMapping::mapMultipleTexturesToMeshUV (pcl::TextureMesh &te }// end cameras // push on extra empty UV map (for unseen faces) so that obj writer does not crash! - std::vector texture_map_tmp; + std::vector > texture_map_tmp; for (size_t i = 0; i < tex_mesh.tex_polygons[cams.size ()].size (); ++i) for (size_t j = 0; j < tex_mesh.tex_polygons[cams.size ()][i].vertices.size (); ++j) { @@ -908,7 +908,7 @@ pcl::TextureMapping::textureMeshwithMultipleCameras (pcl::TextureMesh if (static_cast (mesh.tex_coordinates.size ()) <= current_cam) { - std::vector dummy_container; + std::vector > dummy_container; mesh.tex_coordinates.push_back (dummy_container); } mesh.tex_coordinates[current_cam].resize (3 * visibility.size ()); @@ -966,7 +966,7 @@ pcl::TextureMapping::textureMeshwithMultipleCameras (pcl::TextureMesh if (mesh.tex_coordinates.size() <= cameras.size ()) { - std::vector dummy_container; + std::vector > dummy_container; mesh.tex_coordinates.push_back(dummy_container); } diff --git a/surface/include/pcl/surface/texture_mapping.h b/surface/include/pcl/surface/texture_mapping.h index 4e3baf10135..692536955d8 100644 --- a/surface/include/pcl/surface/texture_mapping.h +++ b/surface/include/pcl/surface/texture_mapping.h @@ -351,7 +351,7 @@ namespace pcl * \param[in] p2 the second point * \param[in] p3 the third point */ - std::vector + std::vector > mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3); /** \brief Returns the circumcenter of a triangle and the circle's radius. diff --git a/test/common/test_vector_average.cpp b/test/common/test_vector_average.cpp index c55099261ef..06e433eaf6c 100644 --- a/test/common/test_vector_average.cpp +++ b/test/common/test_vector_average.cpp @@ -45,8 +45,8 @@ using namespace pcl; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, VectorAverage_mean) { - std::vector points; - std::vector weights; + std::vector > points; + std::vector > weights; points.push_back (Eigen::Vector3f (-0.558191f, 0.180822f, -0.809769f)); weights.push_back (0.160842f); points.push_back (Eigen::Vector3f (-0.510641f, 0.290673f, -0.809169f)); diff --git a/tools/voxel_grid_occlusion_estimation.cpp b/tools/voxel_grid_occlusion_estimation.cpp index 5f03abd79c7..e36a24d6797 100644 --- a/tools/voxel_grid_occlusion_estimation.cpp +++ b/tools/voxel_grid_occlusion_estimation.cpp @@ -217,7 +217,7 @@ int main (int argc, char** argv) tt.tic (); // estimate the occluded space - std::vector occluded_voxels; + std::vector > occluded_voxels; vg.occlusionEstimationAll (occluded_voxels); print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", (int)occluded_voxels.size ()); print_info (" occluded voxels]\n"); diff --git a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp index 6d782dbee88..84d67b0ead6 100644 --- a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp +++ b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp @@ -482,7 +482,7 @@ pcl::tracking::PyramidalKLTTracker::track (const PointClou std::vector& status, Eigen::Affine3f& motion) const { - std::vector next_pts (prev_keypoints->size ()); + std::vector > next_pts (prev_keypoints->size ()); Eigen::Array2f half_win ((track_width_-1)*0.5f, (track_height_-1)*0.5f); pcl::TransformationFromCorrespondences transformation_computer; const int nb_points = prev_keypoints->size (); diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 213f6fa752f..ce7d0f79b35 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -3400,7 +3400,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( // Get camera positions vtkPolyData *sphere = subdivide->GetOutput (); - std::vector cam_positions; + std::vector > cam_positions; if (!use_vertices) { vtkSmartPointer cells_sphere = sphere->GetPolys ();