diff --git a/pcl_ros/CHANGELOG.rst b/pcl_ros/CHANGELOG.rst index 4b97a31c..21bf140b 100644 --- a/pcl_ros/CHANGELOG.rst +++ b/pcl_ros/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package pcl_ros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.1.0 (2013-07-09) +------------------ * Add missing include in one of the installed headers * Refactors to use pcl-1.7 * Use the PointIndices from pcl_msgs diff --git a/pcl_ros/include/pcl_ros/features/boundary.h b/pcl_ros/include/pcl_ros/features/boundary.h index bb91cd61..39a0d10e 100644 --- a/pcl_ros/include/pcl_ros/features/boundary.h +++ b/pcl_ros/include/pcl_ros/features/boundary.h @@ -38,6 +38,8 @@ #ifndef PCL_ROS_BOUNDARY_H_ #define PCL_ROS_BOUNDARY_H_ +#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true + #include #include "pcl_ros/features/feature.h" @@ -55,11 +57,11 @@ namespace pcl_ros { private: pcl::BoundaryEstimation impl_; - + typedef pcl::PointCloud PointCloudOut; /** \brief Child initialization routine. Internal method. */ - inline bool + inline bool childInit (ros::NodeHandle &nh) { // Create the output publisher @@ -71,7 +73,7 @@ namespace pcl_ros void emptyPublish (const PointCloudInConstPtr &cloud); /** \brief Compute the feature and publish it. */ - void computePublish (const PointCloudInConstPtr &cloud, + void computePublish (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices); diff --git a/pcl_ros/src/pcl_ros/features/boundary.cpp b/pcl_ros/src/pcl_ros/features/boundary.cpp index 5fa970f6..0b6a8c36 100644 --- a/pcl_ros/src/pcl_ros/features/boundary.cpp +++ b/pcl_ros/src/pcl_ros/features/boundary.cpp @@ -38,7 +38,7 @@ #include #include "pcl_ros/features/boundary.h" -void +void pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud) { PointCloudOut output; @@ -46,7 +46,7 @@ pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pub_output_.publish (output.makeShared ()); } -void +void pcl_ros::BoundaryEstimation::computePublish (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, diff --git a/perception_pcl/CHANGELOG.rst b/perception_pcl/CHANGELOG.rst index 57f09623..c51638d6 100644 --- a/perception_pcl/CHANGELOG.rst +++ b/perception_pcl/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package perception_pcl ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +1.1.0 (2013-07-09) +------------------ * Fixes from converting from pcl-1.7, incomplete 1.0.34 (2013-05-21)