[pcl] Update to release 1.4.0 Add patch for gcc-4.7 fixes

rmattes rmattes at fedoraproject.org
Tue Jan 17 04:11:25 UTC 2012


commit 043de35c457808b0fc0babdfe8f845a96a2b94c5
Author: Rich Mattes <richmattes at gmail.com>
Date:   Mon Jan 16 22:55:47 2012 -0500

    Update to release 1.4.0
    Add patch for gcc-4.7 fixes

 PCL-1.4.0-Source-fedora.patch |   79 ++++++
 pcl-1.4.0-gcc47.patch         |  525 +++++++++++++++++++++++++++++++++++++++++
 pcl.spec                      |   16 +-
 3 files changed, 614 insertions(+), 6 deletions(-)
---
diff --git a/PCL-1.4.0-Source-fedora.patch b/PCL-1.4.0-Source-fedora.patch
new file mode 100644
index 0000000..443ecc5
--- /dev/null
+++ b/PCL-1.4.0-Source-fedora.patch
@@ -0,0 +1,79 @@
+diff -urN PCL-1.3.1-Source/cmake/pcl_targets.cmake PCL-1.3.1-Source.fedora/cmake/pcl_targets.cmake
+--- PCL-1.3.1-Source/cmake/pcl_targets.cmake	2011-12-03 00:35:48.000000000 +0100
++++ PCL-1.3.1-Source.fedora/cmake/pcl_targets.cmake	2012-01-16 19:40:43.433690172 +0100
+@@ -1,5 +1,7 @@
+ include(${PROJECT_SOURCE_DIR}/cmake/pcl_utils.cmake)
+ 
++set(PCL_PKGCONFIG_SUFFIX "-${PCL_MAJOR_VERSION}.${PCL_MINOR_VERSION}" CACHE STRING "Suffix to append to pkg-config files")
++
+ ###############################################################################
+ # Add an option to build a subsystem or not.
+ # _var The name of the variable to store the option in.
+@@ -334,14 +336,14 @@
+     LIST_TO_STRING(_ext_deps_str "${_ext_deps}")
+     set(PKG_EXTERNAL_DEPS ${_ext_deps_str})
+     foreach(_dep ${_pcl_deps})
+-      set(PKG_EXTERNAL_DEPS "${PKG_EXTERNAL_DEPS} pcl_${_dep}-${PCL_MAJOR_VERSION}.${PCL_MINOR_VERSION}")
++      set(PKG_EXTERNAL_DEPS "${PKG_EXTERNAL_DEPS} pcl_${_dep}${PCL_PKGCONFIG_SUFFIX}")
+     endforeach(_dep)
+     set(PKG_INTERNAL_DEPS "")
+     foreach(_dep ${_int_deps})
+         set(PKG_INTERNAL_DEPS "${PKG_INTERNAL_DEPS} -l${_dep}")
+     endforeach(_dep)
+ 
+-    set(_pc_file ${CMAKE_CURRENT_BINARY_DIR}/${_name}-${PCL_MAJOR_VERSION}.${PCL_MINOR_VERSION}.pc)
++    set(_pc_file ${CMAKE_CURRENT_BINARY_DIR}/${_name}${PCL_PKGCONFIG_SUFFIX}.pc)
+     configure_file(${PROJECT_SOURCE_DIR}/cmake/pkgconfig.cmake.in ${_pc_file}
+         @ONLY)
+     install(FILES ${_pc_file} DESTINATION ${PKGCFG_INSTALL_DIR}
+diff -urN PCL-1.3.1-Source/io/CMakeLists.txt PCL-1.3.1-Source.fedora/io/CMakeLists.txt
+--- PCL-1.3.1-Source/io/CMakeLists.txt	2011-12-03 00:35:48.000000000 +0100
++++ PCL-1.3.1-Source.fedora/io/CMakeLists.txt	2012-01-16 19:40:43.436690163 +0100
+@@ -116,9 +116,10 @@
+     endif(OPENNI_FOUND)
+ 
+     set(EXT_DEPS eigen3)
+-    if(OPENNI_FOUND)
+-      list(APPEND EXT_DEPS openni-dev)
+-    endif(OPENNI_FOUND)
++    # Disable on Fedora, there is no pkg-config file
++    #if(OPENNI_FOUND)
++    #  list(APPEND EXT_DEPS openni-dev)
++    #endif(OPENNI_FOUND)
+     PCL_MAKE_PKGCONFIG(${LIB_NAME} ${SUBSYS_NAME} "${SUBSYS_DESC}"
+       "${SUBSYS_DEPS}" "${EXT_DEPS}" "" "" "")
+ 
+diff -urN PCL-1.3.1-Source/PCLConfig.cmake.in PCL-1.3.1-Source.fedora/PCLConfig.cmake.in
+--- PCL-1.3.1-Source/PCLConfig.cmake.in	2011-12-03 00:35:48.000000000 +0100
++++ PCL-1.3.1-Source.fedora/PCLConfig.cmake.in	2012-01-16 19:47:07.404643739 +0100
+@@ -304,9 +304,13 @@
+ # PCLConfig.cmake is installed to PCL_ROOT/cmake
+   get_filename_component(PCL_ROOT "${PCL_DIR}" PATH)
+ else(WIN32)
+-# PCLConfig.cmake is installed to PCL_ROOT/share/pcl-x.y
++  # PCLConfig.cmake is installed to PCL_ROOT/share/pcl-x.y or PCL_ROOT/lib${LIB_SUFFIX}/cmake/pcl
+   get_filename_component(PCL_ROOT "${PCL_DIR}" PATH)
+   get_filename_component(PCL_ROOT "${PCL_ROOT}" PATH)
++  if (${PCL_DIR} MATCHES ".*lib.*")
++    # PCLConfig.cmake is installed to PCL_ROOT/lib${LIB_SUFFIX}/cmake/pcl
++    get_filename_component(PCL_ROOT "${PCL_ROOT}" PATH)
++  endif()
+ endif(WIN32)
+ 
+ # check whether PCLConfig.cmake is found into a PCL installation or in a build tree
+diff -urN PCL-1.3.1-Source/visualization/CMakeLists.txt PCL-1.3.1-Source.fedora/visualization/CMakeLists.txt
+--- PCL-1.3.1-Source/visualization/CMakeLists.txt	2011-12-03 00:35:48.000000000 +0100
++++ PCL-1.3.1-Source.fedora/visualization/CMakeLists.txt	2012-01-16 19:40:43.437690160 +0100
+@@ -83,9 +83,9 @@
+      target_link_libraries(${LIB_NAME} pcl_io pcl_kdtree pcl_range_image 
+                                        vtkCommon vtkWidgets vtkHybrid)
+     set(EXT_DEPS "")
+-    if(OPENNI_FOUND)
+-      list(APPEND EXT_DEPS openni-dev)
+-    endif(OPENNI_FOUND)
++    #if(OPENNI_FOUND)
++    #  list(APPEND EXT_DEPS openni-dev)
++    #endif(OPENNI_FOUND)
+     PCL_MAKE_PKGCONFIG(${LIB_NAME} ${SUBSYS_NAME} "${SUBSYS_DESC}"
+       "${SUBSYS_DEPS}" "${EXT_DEPS}" "" "" "")
+ 
diff --git a/pcl-1.4.0-gcc47.patch b/pcl-1.4.0-gcc47.patch
new file mode 100644
index 0000000..f578e04
--- /dev/null
+++ b/pcl-1.4.0-gcc47.patch
@@ -0,0 +1,525 @@
+Index: octree/include/pcl/octree/impl/octree_pointcloud.hpp
+===================================================================
+--- octree/include/pcl/octree/impl/octree_pointcloud.hpp	(revision 3921)
++++ octree/include/pcl/octree/impl/octree_pointcloud.hpp	(working copy)
+@@ -724,11 +724,11 @@
+   // iterate over all children
+   for (childIdx = 0; childIdx < 8; childIdx++)
+   {
+-    if (!branchHasChild (*node_arg, childIdx))
++    if (!this->branchHasChild (*node_arg, childIdx))
+       continue;
+ 
+     const OctreeNode * childNode;
+-    childNode = getBranchChild (*node_arg, childIdx);
++    childNode = this->getBranchChild (*node_arg, childIdx);
+ 
+     // generate new key for current branch voxel
+     OctreeKey newKey;
+Index: octree/include/pcl/octree/impl/octree_search.hpp
+===================================================================
+--- octree/include/pcl/octree/impl/octree_search.hpp	(revision 3921)
++++ octree/include/pcl/octree/impl/octree_search.hpp	(working copy)
+@@ -51,9 +51,9 @@
+   bool b_success = false;
+ 
+   // generate key
+-  genOctreeKeyforPoint (point, key);
++  this->genOctreeKeyforPoint (point, key);
+ 
+-  LeafT* leaf = getLeaf (key);
++  LeafT* leaf = this->getLeaf (key);
+ 
+   if (leaf)
+   {
+@@ -196,7 +196,7 @@
+   // iterate over all children
+   for (childIdx = 0; childIdx < 8; childIdx++)
+   {
+-    if (branchHasChild (*node, childIdx))
++    if (this->branchHasChild (*node, childIdx))
+     {
+       PointT voxelCenter;
+ 
+@@ -205,10 +205,10 @@
+       searchEntryHeap[childIdx].key.z = (key.z << 1) + (!!(childIdx & (1 << 0)));
+ 
+       // generate voxel center point for voxel at key
+-      genVoxelCenterFromOctreeKey (searchEntryHeap[childIdx].key, treeDepth, voxelCenter);
++      this->genVoxelCenterFromOctreeKey (searchEntryHeap[childIdx].key, treeDepth, voxelCenter);
+ 
+       // generate new priority queue element
+-      searchEntryHeap[childIdx].node = getBranchChild (*node, childIdx);
++      searchEntryHeap[childIdx].node = this->getBranchChild (*node, childIdx);
+       searchEntryHeap[childIdx].pointDistance = pointSquaredDist (voxelCenter, point);
+     }
+     else
+@@ -301,11 +301,11 @@
+   // iterate over all children
+   for (childIdx = 0; childIdx < 8; childIdx++)
+   {
+-    if (!branchHasChild (*node, childIdx))
++    if (!this->branchHasChild (*node, childIdx))
+       continue;
+ 
+     const OctreeNode* childNode;
+-    childNode = getBranchChild (*node, childIdx);
++    childNode = this->getBranchChild (*node, childIdx);
+ 
+     OctreeKey newKey;
+     PointT voxelCenter;
+@@ -317,7 +317,7 @@
+     newKey.z = (key.z << 1) + (!!(childIdx & (1 << 0)));
+ 
+     // generate voxel center point for voxel at key
+-    genVoxelCenterFromOctreeKey (newKey, treeDepth, voxelCenter);
++    this->genVoxelCenterFromOctreeKey (newKey, treeDepth, voxelCenter);
+ 
+     // calculate distance to search point
+     squaredDist = pointSquaredDist ((const PointT &)voxelCenter, point);
+@@ -393,7 +393,7 @@
+   // iterate over all children
+   for (childIdx = 0; childIdx < 8; childIdx++)
+   {
+-    if (!branchHasChild (*node, childIdx))
++    if (!this->branchHasChild (*node, childIdx))
+       continue;
+ 
+     PointT voxelCenter;
+@@ -404,7 +404,7 @@
+     newKey.z = (key.z << 1) + (!!(childIdx & (1 << 0)));
+ 
+     // generate voxel center point for voxel at key
+-    genVoxelCenterFromOctreeKey (newKey, treeDepth, voxelCenter);
++    this->genVoxelCenterFromOctreeKey (newKey, treeDepth, voxelCenter);
+ 
+     voxelPointDist = pointSquaredDist (voxelCenter, point);
+ 
+@@ -420,7 +420,7 @@
+   // make sure we found at least one branch child
+   assert (minChildIdx<8);
+ 
+-  childNode = getBranchChild (*node, minChildIdx);
++  childNode = this->getBranchChild (*node, minChildIdx);
+ 
+   if (treeDepth < this->octreeDepth_)
+   {
+@@ -540,7 +540,7 @@
+   {
+     PointT newPoint;
+ 
+-    genLeafNodeCenterFromOctreeKey (key, newPoint);
++    this->genLeafNodeCenterFromOctreeKey (key, newPoint);
+ 
+     voxelCenterList.push_back (newPoint);
+ 
+@@ -571,7 +571,7 @@
+       childIdx = a;
+ 
+     // childNode == 0 if childNode doesn't exist
+-    childNode = getBranchChild ((OctreeBranch&)*node, childIdx);
++    childNode = this->getBranchChild ((OctreeBranch&)*node, childIdx);
+ 
+     // Generate new key for current branch voxel
+     childKey.x = (key.x << 1) | (!!(childIdx & (1 << 2)));
+@@ -695,7 +695,7 @@
+       childIdx = a;
+ 
+     // childNode == 0 if childNode doesn't exist
+-    childNode = getBranchChild ((OctreeBranch&)*node, childIdx);
++    childNode = this->getBranchChild ((OctreeBranch&)*node, childIdx);
+     // Generate new key for current branch voxel
+     childKey.x = (key.x << 1) | (!!(childIdx & (1 << 2)));
+     childKey.y = (key.y << 1) | (!!(childIdx & (1 << 1)));
+Index: surface/include/pcl/surface/impl/mls_omp.hpp
+===================================================================
+--- surface/include/pcl/surface/impl/mls_omp.hpp	(revision 3921)
++++ surface/include/pcl/surface/impl/mls_omp.hpp	(working copy)
+@@ -59,7 +59,7 @@
+     std::vector<float> nn_sqr_dists;
+ 
+     // Get the initial estimates of point positions and their neighborhoods
+-    if (!searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists))
++    if (!this->searchForNeighbors ((*indices_)[cp], nn_indices, nn_sqr_dists))
+     {
+       if (normals_)
+         normals_->points[cp].normal[0] = normals_->points[cp].normal[1] = normals_->points[cp].normal[2] = normals_->points[cp].curvature = std::numeric_limits<float>::quiet_NaN ();
+@@ -73,7 +73,7 @@
+ 
+     Eigen::Vector4f model_coefficients;
+     // Get a plane approximating the local surface's tangent and project point onto it
+-    computeMLSPointNormal (output.points[cp], *input_, nn_indices, nn_sqr_dists,
++    this->computeMLSPointNormal (output.points[cp], *input_, nn_indices, nn_sqr_dists,
+                            model_coefficients); 
+ 
+     // Save results to output cloud
+Index: surface/include/pcl/surface/impl/marching_cubes_greedy.hpp
+===================================================================
+--- surface/include/pcl/surface/impl/marching_cubes_greedy.hpp	(revision 3921)
++++ surface/include/pcl/surface/impl/marching_cubes_greedy.hpp	(working copy)
+@@ -72,11 +72,11 @@
+ 
+     // the vertices are shared by 8 voxels, so we need to update all 8 of them
+     HashMap neighbor_list;
+-    getNeighborList1D (cell_data, index_3d, neighbor_list);
++    this->getNeighborList1D (cell_data, index_3d, neighbor_list);
+     BOOST_FOREACH (typename HashMap::value_type entry, neighbor_list)
+     {
+       Eigen::Vector3i i3d;
+-      getIndexIn3D(entry.first, i3d);
++      this->getIndexIn3D(entry.first, i3d);
+       // if the neighbor doesn't exist, add it, otherwise we need to do an OR operation on the vertices
+       if (cell_hash_map_.find (entry.first) == cell_hash_map_.end ())
+       {
+Index: surface/include/pcl/surface/impl/marching_cubes_greedy_dot.hpp
+===================================================================
+--- surface/include/pcl/surface/impl/marching_cubes_greedy_dot.hpp	(revision 3921)
++++ surface/include/pcl/surface/impl/marching_cubes_greedy_dot.hpp	(working copy)
+@@ -72,11 +72,11 @@
+ 
+     // the vertices are shared by 8 voxels, so we need to update all 8 of them
+     HashMap neighbor_list;
+-    getNeighborList1D (cell_data, index_3d, neighbor_list);
++    this->getNeighborList1D (cell_data, index_3d, neighbor_list);
+     BOOST_FOREACH (typename HashMap::value_type entry, neighbor_list)
+     {
+       Eigen::Vector3i i3d;
+-      getIndexIn3D (entry.first, i3d);
++      this->getIndexIn3D (entry.first, i3d);
+       // getCellCenterFromIndex (const Eigen::Vector3i &index, Eigen::Vector4f &center) const
+       Eigen::Vector4f posVector;
+       MarchingCubes<PointNT>::getCellCenterFromIndex (i3d, posVector);
+Index: registration/include/pcl/registration/impl/icp.hpp
+===================================================================
+--- registration/include/pcl/registration/impl/icp.hpp	(revision 3921)
++++ registration/include/pcl/registration/impl/icp.hpp	(working copy)
+@@ -82,7 +82,7 @@
+     // Iterating over the entire index vector and  find all correspondences
+     for (size_t idx = 0; idx < indices_->size (); ++idx)
+     {
+-      if (!searchForNeighbors (output, (*indices_)[idx], nn_indices, nn_dists))
++      if (!this->searchForNeighbors (output, (*indices_)[idx], nn_indices, nn_dists))
+       {
+         PCL_ERROR ("[pcl::%s::computeTransformation] Unable to find a nearest neighbor in the target dataset for point %d in the source!\n", getClassName ().c_str (), (*indices_)[idx]);
+         return;
+@@ -185,7 +185,7 @@
+ 
+     if (nr_iterations_ >= max_iterations_ ||
+         fabs ((transformation_ - previous_transformation_).sum ()) < transformation_epsilon_ ||
+-        fabs (getFitnessScore (correspondence_distances_, previous_correspondence_distances)) <= euclidean_fitness_epsilon_
++        fabs (this->getFitnessScore (correspondence_distances_, previous_correspondence_distances)) <= euclidean_fitness_epsilon_
+        )
+     {
+       converged_ = true;
+@@ -196,7 +196,7 @@
+       PCL_DEBUG ("fabs ((transformation_ - previous_transformation_).sum ()) (%f) < transformation_epsilon_ (%f)\n",
+                  fabs ((transformation_ - previous_transformation_).sum ()), transformation_epsilon_);
+       PCL_DEBUG ("fabs (getFitnessScore (correspondence_distances_, previous_correspondence_distances)) (%f) <= euclidean_fitness_epsilon_ (%f)\n",
+-                 fabs (getFitnessScore (correspondence_distances_, previous_correspondence_distances)),
++                 fabs (this->getFitnessScore (correspondence_distances_, previous_correspondence_distances)),
+                  euclidean_fitness_epsilon_);
+ 
+     }
+Index: features/include/pcl/features/spin_image.h
+===================================================================
+--- features/include/pcl/features/spin_image.h	(revision 3921)
++++ features/include/pcl/features/spin_image.h	(working copy)
+@@ -159,7 +159,7 @@
+       setInputWithNormals (const PointCloudInConstPtr& input, 
+                            const PointCloudNConstPtr& normals)
+       {
+-        setInputCloud (input);
++        this->setInputCloud (input);
+         input_normals_ = normals;
+       }
+ 
+@@ -176,8 +176,8 @@
+       setSearchSurfaceWithNormals (const PointCloudInConstPtr& surface, 
+                                    const PointCloudNConstPtr& normals)
+       {
+-        setSearchSurface (surface);
+-        setInputNormals (normals);
++        this->setSearchSurface (surface);
++        this->setInputNormals (normals);
+       }
+ 
+       /** \brief Sets single vector a rotation axis for all input points.
+Index: features/include/pcl/features/impl/fpfh_omp.hpp
+===================================================================
+--- features/include/pcl/features/impl/fpfh_omp.hpp	(revision 3921)
++++ features/include/pcl/features/impl/fpfh_omp.hpp	(working copy)
+@@ -96,7 +96,7 @@
+     this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists);
+ 
+     // Estimate the SPFH signature around p_idx
+-    computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1_, hist_f2_, hist_f3_);
++    this->computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1_, hist_f2_, hist_f3_);
+ 
+     // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices
+     spfh_hist_lookup[p_idx] = i;
+Index: features/include/pcl/features/impl/intensity_gradient.hpp
+===================================================================
+--- features/include/pcl/features/impl/intensity_gradient.hpp	(revision 3921)
++++ features/include/pcl/features/impl/intensity_gradient.hpp	(working copy)
+@@ -229,7 +229,7 @@
+ 
+     Eigen::Vector3f normal = Eigen::Vector3f::Map (normals_->points[idx].normal);
+     Eigen::Vector3f gradient;
+-    computePointIntensityGradient (*surface_, nn_indices, centroid.head<3> (), mean_intensity, normal, gradient);
++    this->computePointIntensityGradient (*surface_, nn_indices, centroid.head<3> (), mean_intensity, normal, gradient);
+ 
+     output.points (idx, 0) = gradient[0];
+     output.points (idx, 1) = gradient[1];
+Index: features/include/pcl/features/impl/intensity_spin.hpp
+===================================================================
+--- features/include/pcl/features/impl/intensity_spin.hpp	(revision 3921)
++++ features/include/pcl/features/impl/intensity_spin.hpp	(working copy)
+@@ -221,7 +221,7 @@
+     }
+ 
+     // Compute the intensity spin image
+-    computeIntensitySpinImage (*surface_, search_radius_, sigma_, k, nn_indices, nn_dist_sqr, intensity_spin_image);
++    this->computeIntensitySpinImage (*surface_, search_radius_, sigma_, k, nn_indices, nn_dist_sqr, intensity_spin_image);
+ 
+     // Copy into the resultant cloud
+     int bin = 0;
+Index: features/include/pcl/features/impl/shot_omp.hpp
+===================================================================
+--- features/include/pcl/features/impl/shot_omp.hpp	(revision 3921)
++++ features/include/pcl/features/impl/shot_omp.hpp	(working copy)
+@@ -83,7 +83,7 @@
+ #else
+     int tid = 0;
+ #endif
+-	computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot[tid], rfs[tid]);
++	this->computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot[tid], rfs[tid]);
+ 
+ 	// Copy into the resultant cloud
+     for (int d = 0; d < shot[tid].size (); ++d)
+@@ -139,7 +139,7 @@
+ #else
+     int tid = 0;
+ #endif
+-    computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot[tid], rfs[tid]);
++    this->computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot[tid], rfs[tid]);
+ 
+     // Copy into the resultant cloud
+     for (int d = 0; d < shot[tid].size (); ++d)
+Index: features/include/pcl/features/impl/3dsc.hpp
+===================================================================
+--- features/include/pcl/features/impl/3dsc.hpp	(revision 3921)
++++ features/include/pcl/features/impl/3dsc.hpp	(working copy)
+@@ -340,7 +340,7 @@
+     }
+ 
+     std::vector<float> descriptor (descriptor_length_);
+-    if (!computePoint (point_index, *normals_, rf, descriptor))
++    if (!this->computePoint (point_index, *normals_, rf, descriptor))
+       output.is_dense = false;
+     for (int j = 0; j < 9; ++j)
+       output.points (point_index, j) = rf[j];
+Index: features/include/pcl/features/impl/rift.hpp
+===================================================================
+--- features/include/pcl/features/impl/rift.hpp	(revision 3921)
++++ features/include/pcl/features/impl/rift.hpp	(working copy)
+@@ -246,7 +246,7 @@
+     }
+ 
+     // Compute the RIFT descriptor
+-    computeRIFT (*surface_, *gradient_, (*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr, rift_descriptor);
++    this->computeRIFT (*surface_, *gradient_, (*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr, rift_descriptor);
+ 
+     // Copy into the resultant cloud
+     int bin = 0;
+Index: features/include/pcl/features/impl/principal_curvatures.hpp
+===================================================================
+--- features/include/pcl/features/impl/principal_curvatures.hpp	(revision 3921)
++++ features/include/pcl/features/impl/principal_curvatures.hpp	(working copy)
+@@ -188,7 +188,7 @@
+       }
+ 
+       // Estimate the principal curvatures at each patch
+-      computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
++      this->computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
+                                        output.points (idx, 0), output.points (idx, 1), output.points (idx, 2),
+                                        output.points (idx, 3), output.points (idx, 4));
+     }
+@@ -207,7 +207,7 @@
+       }
+ 
+       // Estimate the principal curvatures at each patch
+-      computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
++      this->computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
+                                        output.points (idx, 0), output.points (idx, 1), output.points (idx, 2),
+                                        output.points (idx, 3), output.points (idx, 4));
+     }
+Index: features/include/pcl/features/impl/boundary.hpp
+===================================================================
+--- features/include/pcl/features/impl/boundary.hpp	(revision 3921)
++++ features/include/pcl/features/impl/boundary.hpp	(working copy)
+@@ -196,10 +196,10 @@
+       // Obtain a coordinate system on the least-squares plane
+       //v = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal ();
+       //u = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v);
+-      getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v);
++      this->getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v);
+ 
+       // Estimate whether the point is lying on a boundary surface or not
+-      output.points (idx, 0) = isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
++      output.points (idx, 0) = this->isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
+     }
+   }
+   else
+@@ -218,10 +218,10 @@
+       // Obtain a coordinate system on the least-squares plane
+       //v = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal ();
+       //u = normals_->points[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v);
+-      getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v);
++      this->getCoordinateSystemOnPlane (normals_->points[(*indices_)[idx]], u, v);
+ 
+       // Estimate whether the point is lying on a boundary surface or not
+-      output.points (idx, 0) = isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
++      output.points (idx, 0) = this->isBoundaryPoint (*surface_, input_->points[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
+     }
+   }
+ }
+Index: features/include/pcl/features/impl/fpfh.hpp
+===================================================================
+--- features/include/pcl/features/impl/fpfh.hpp	(revision 3921)
++++ features/include/pcl/features/impl/fpfh.hpp	(working copy)
+@@ -307,7 +307,7 @@
+   std::vector<float> nn_dists (k_);
+ 
+   std::vector<int> spfh_hist_lookup;
+-  computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
++  this->computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
+ 
+   // Intialize the array that will store the FPFH signature
+   output.points.resize (indices_->size (), nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_);
+@@ -332,7 +332,7 @@
+         nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
+ 
+       // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ...
+-      weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
++      this->weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
+       output.points.row (idx) = fpfh_histogram_;
+     }
+   }
+@@ -354,7 +354,7 @@
+         nn_indices[i] = spfh_hist_lookup[nn_indices[i]];
+ 
+       // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ...
+-      weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
++      this->weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
+       output.points.row (idx) = fpfh_histogram_;
+     }
+   }
+Index: features/include/pcl/features/impl/moment_invariants.hpp
+===================================================================
+--- features/include/pcl/features/impl/moment_invariants.hpp	(revision 3921)
++++ features/include/pcl/features/impl/moment_invariants.hpp	(working copy)
+@@ -181,7 +181,7 @@
+         continue;
+       }
+ 
+-      computePointMomentInvariants (*surface_, nn_indices,
++      this->computePointMomentInvariants (*surface_, nn_indices,
+                                     output.points (idx, 0), output.points (idx, 1), output.points (idx, 2));
+     }
+   }
+@@ -198,7 +198,7 @@
+         continue;
+        }
+ 
+-      computePointMomentInvariants (*surface_, nn_indices,
++      this->computePointMomentInvariants (*surface_, nn_indices,
+                                     output.points (idx, 0), output.points (idx, 1), output.points (idx, 2));
+     }
+   }
+Index: features/include/pcl/features/impl/spin_image.hpp
+===================================================================
+--- features/include/pcl/features/impl/spin_image.hpp	(revision 3921)
++++ features/include/pcl/features/impl/spin_image.hpp	(working copy)
+@@ -106,7 +106,7 @@
+ 
+   std::vector<int> nn_indices;
+   std::vector<float> nn_sqr_dists;
+-  const int neighb_cnt = searchForNeighbors (index, search_radius_, nn_indices, nn_sqr_dists);
++  const int neighb_cnt = this->searchForNeighbors (index, search_radius_, nn_indices, nn_sqr_dists);
+   if (neighb_cnt < (int)min_pts_neighb_)
+   {
+     throw PCLException (
+@@ -324,7 +324,7 @@
+   output.points.resize (indices_->size (), 153);
+   for (int i_input = 0; i_input < (int)indices_->size (); ++i_input)
+   {
+-    Eigen::ArrayXXd res = computeSiForPoint (indices_->at (i_input));
++    Eigen::ArrayXXd res = this->computeSiForPoint (indices_->at (i_input));
+ 
+     // Copy into the resultant cloud
+     for (int iRow = 0; iRow < res.rows () ; iRow++)
+Index: features/include/pcl/features/impl/shot.hpp
+===================================================================
+--- features/include/pcl/features/impl/shot.hpp	(revision 3921)
++++ features/include/pcl/features/impl/shot.hpp	(working copy)
+@@ -672,7 +672,7 @@
+     interpolateSingleChannel (indices, sqr_dists, input_->points[index].getVector4fMap (), rf, binDistanceShape, nr_shape_bins_, shot);
+ 
+   // Normalize the final histogram
+-  normalizeHistogram (shot, descLength_);
++  this->normalizeHistogram (shot, descLength_);
+ }
+ 
+ 
+@@ -691,14 +691,14 @@
+ 
+    // Clear the resultant shot
+   std::vector<double> binDistanceShape;
+-  createBinDistanceShape (index, indices, sqr_dists, *input_, *normals_, *surface_, search_radius_, binDistanceShape, rf);
++  this->createBinDistanceShape (index, indices, sqr_dists, *input_, *normals_, *surface_, search_radius_, binDistanceShape, rf);
+ 
+   // Interpolate
+   shot.setZero ();
+   interpolateSingleChannel (indices, sqr_dists, input_->points[index].getVector4fMap (), rf, binDistanceShape, nr_shape_bins_, shot);
+ 
+   // Normalize the final histogram
+-  normalizeHistogram (shot, descLength_);
++  this->normalizeHistogram (shot, descLength_);
+ }
+ 
+ 
+@@ -717,14 +717,14 @@
+ 
+    // Clear the resultant shot
+   std::vector<double> binDistanceShape;
+-  createBinDistanceShape (index, indices, sqr_dists, *input_, *normals_, *surface_, search_radius_, binDistanceShape, rf);
++  this->createBinDistanceShape (index, indices, sqr_dists, *input_, *normals_, *surface_, search_radius_, binDistanceShape, rf);
+ 
+   // Interpolate
+   shot.setZero ();
+   interpolateSingleChannel (indices, sqr_dists, input_->points[index].getVector4fMap (), rf, binDistanceShape, nr_shape_bins_, shot);
+ 
+   // Normalize the final histogram
+-  normalizeHistogram (shot, descLength_);
++  this->normalizeHistogram (shot, descLength_);
+ }
+ 
+ 
+@@ -839,7 +839,7 @@
+      }
+ 
+     // Compute the SHOT descriptor for the current 3D feature
+-    computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot_, rf_);
++    this->computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot_, rf_);
+ 
+     // Copy into the resultant cloud
+     for (int d = 0; d < shot_.size (); ++d)
+@@ -955,7 +955,7 @@
+      }
+ 
+     // Estimate the SHOT at each patch
+-    computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot_, rf_);
++    this->computePointSHOT ((*indices_)[idx], nn_indices, nn_dists, shot_, rf_);
+ 
+     // Copy into the resultant cloud
+     for (int d = 0; d < shot_.size (); ++d)
diff --git a/pcl.spec b/pcl.spec
index 10483e5..477bae7 100644
--- a/pcl.spec
+++ b/pcl.spec
@@ -1,14 +1,14 @@
 Name:           pcl
-Version:        1.3.1
-Release:        5%{?dist}
+Version:        1.4.0
+Release:        1%{?dist}
 Summary:        Library for point cloud processing
 
 Group:          System Environment/Libraries
 License:        BSD
 URL:            http://pointclouds.org/
-Source0:        http://dev.pointclouds.org/attachments/download/572/PCL-1.3.1-Source.tar.bz2
-Patch0:         PCL-1.3.1-Source-fedora.patch
-Patch1:         pcl-1.3.1-gcc47.patch
+Source0:        http://dev.pointclouds.org/attachments/download/610/PCL-1.4.0-Source.tar.bz2
+Patch0:         PCL-1.4.0-Source-fedora.patch
+Patch1:         pcl-1.4.0-gcc47.patch
 BuildRoot:      %{_tmppath}/%{name}-%{version}-%{release}-root-%(%{__id_u} -n)
 
 # For plain building
@@ -158,7 +158,7 @@ rm -rf $RPM_BUILD_ROOT
 %defattr(-,root,root,-)
 %doc AUTHORS.txt LICENSE.txt
 %{_libdir}/*.so.*
-%{_datadir}/%{name}-1.3
+%{_datadir}/%{name}-1.4
 
 %files devel
 %defattr(-,root,root,-)
@@ -180,6 +180,10 @@ rm -rf $RPM_BUILD_ROOT
 
 
 %changelog
+* Mon Jan 16 2012 Rich Mattes <richmattes at gmail.com> - 1.4.0-1
+- Update to release 1.4.0
+- Add patch for gcc-4.7 fixes
+
 * Mon Jan 16 2012 Tim Niemueller <tim at niemueller.de> - 1.3.1-5
 - Update patch to fix PCLConfig.cmake
 


More information about the scm-commits mailing list