Changes in preparation for PCL 1.11 (#273) (#279)

* Deriving typedef from pcl type

* Explicit boost shared_ptr for function parameters

* Use boost::shared_ptr instead of PCL::Ptr

* Implementing boost-std compatibility

* Using the compatibility layer
This commit is contained in:
Kunal Tyagi 2020-05-12 10:50:15 +09:00 committed by GitHub
parent 36eb607be7
commit 2b770b15ed
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
28 changed files with 225 additions and 103 deletions

View File

@ -70,11 +70,11 @@ namespace pcl_ros
typedef pcl::KdTree<pcl::PointXYZ>::Ptr KdTreePtr;
typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn;
typedef PointCloudIn::Ptr PointCloudInPtr;
typedef PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef boost::shared_ptr<PointCloudIn> PointCloudInPtr;
typedef boost::shared_ptr<const PointCloudIn> PointCloudInConstPtr;
typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
typedef pcl::IndicesPtr IndicesPtr;
typedef pcl::IndicesConstPtr IndicesConstPtr;
/** \brief Empty constructor. */
Feature () : /*input_(), indices_(), surface_(), */tree_(), k_(0), search_radius_(0),
@ -153,7 +153,7 @@ namespace pcl_ros
indices.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
PointCloudIn cloud;
cloud.header.stamp = input->header.stamp;
nf_pc_.add (cloud.makeShared ());
nf_pc_.add (ros_ptr(cloud.makeShared ()));
nf_pi_.add (boost::make_shared<PointIndices> (indices));
}
@ -191,8 +191,8 @@ namespace pcl_ros
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef pcl::PointCloud<pcl::Normal> PointCloudN;
typedef PointCloudN::Ptr PointCloudNPtr;
typedef PointCloudN::ConstPtr PointCloudNConstPtr;
typedef boost::shared_ptr<PointCloudN> PointCloudNPtr;
typedef boost::shared_ptr<const PointCloudN> PointCloudNConstPtr;
FeatureFromNormals () : normals_() {};

View File

@ -59,8 +59,8 @@ namespace pcl_ros
public:
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
typedef pcl::IndicesPtr IndicesPtr;
typedef pcl::IndicesConstPtr IndicesConstPtr;
Filter () {}

View File

@ -48,6 +48,7 @@
// PCL includes
#include <pcl_msgs/PointIndices.h>
#include <pcl_msgs/ModelCoefficients.h>
#include <pcl/pcl_base.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/point_cloud.h"
@ -75,8 +76,8 @@ namespace pcl_ros
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
typedef pcl_msgs::PointIndices PointIndices;
typedef PointIndices::Ptr PointIndicesPtr;
@ -86,8 +87,8 @@ namespace pcl_ros
typedef ModelCoefficients::Ptr ModelCoefficientsPtr;
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr;
typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
typedef pcl::IndicesPtr IndicesPtr;
typedef pcl::IndicesConstPtr IndicesConstPtr;
/** \brief Empty constructor. */
PCLNodelet () : use_indices_ (false), latched_indices_ (false),

View File

@ -294,4 +294,125 @@ namespace ros
} // namespace ros
// test if testing machinery can be implemented
#if defined(__cpp_rvalue_references) && defined(__cpp_constexpr)
#define ROS_POINTER_COMPATIBILITY_IMPLEMENTED 1
#else
#define ROS_POINTER_COMPATIBILITY_IMPLEMENTED 0
#endif
#if ROS_POINTER_COMPATIBILITY_IMPLEMENTED
#include <type_traits> // for std::is_same
#include <memory> // for std::shared_ptr
#include <pcl/pcl_config.h>
#if PCL_VERSION_COMPARE(>=, 1, 11, 0)
#include <pcl/memory.h>
#elif PCL_VERSION_COMPARE(>=, 1, 10, 0)
#include <pcl/make_shared.h>
#endif
#endif
namespace pcl
{
namespace detail
{
#if ROS_POINTER_COMPATIBILITY_IMPLEMENTED
#if PCL_VERSION_COMPARE(>=, 1, 10, 0)
template <class T>
constexpr static bool pcl_uses_boost = std::is_same<boost::shared_ptr<T>,
pcl::shared_ptr<T>>::value;
#else
template <class T>
constexpr static bool pcl_uses_boost = true;
#endif
template<class SharedPointer> struct Holder
{
SharedPointer p;
Holder(const SharedPointer &p) : p(p) {}
Holder(const Holder &other) : p(other.p) {}
Holder(Holder &&other) : p(std::move(other.p)) {}
void operator () (...) { p.reset(); }
};
template<class T>
inline std::shared_ptr<T> to_std_ptr(const boost::shared_ptr<T> &p)
{
typedef Holder<std::shared_ptr<T>> H;
if(H *h = boost::get_deleter<H>(p))
{
return h->p;
}
else
{
return std::shared_ptr<T>(p.get(), Holder<boost::shared_ptr<T>>(p));
}
}
template<class T>
inline boost::shared_ptr<T> to_boost_ptr(const std::shared_ptr<T> &p)
{
typedef Holder<boost::shared_ptr<T>> H;
if(H * h = std::get_deleter<H>(p))
{
return h->p;
}
else
{
return boost::shared_ptr<T>(p.get(), Holder<std::shared_ptr<T>>(p));
}
}
#endif
} // namespace pcl::detail
// add functions to convert to smart pointer used by ROS
template <class T>
inline boost::shared_ptr<T> ros_ptr(const boost::shared_ptr<T> &p)
{
return p;
}
#if ROS_POINTER_COMPATIBILITY_IMPLEMENTED
template <class T>
inline boost::shared_ptr<T> ros_ptr(const std::shared_ptr<T> &p)
{
return detail::to_boost_ptr(p);
}
// add functions to convert to smart pointer used by PCL, based on PCL's own pointer
template <class T, class = typename std::enable_if<!detail::pcl_uses_boost<T>>::type>
inline std::shared_ptr<T> pcl_ptr(const std::shared_ptr<T> &p)
{
return p;
}
template <class T, class = typename std::enable_if<!detail::pcl_uses_boost<T>>::type>
inline std::shared_ptr<T> pcl_ptr(const boost::shared_ptr<T> &p)
{
return detail::to_std_ptr(p);
}
template <class T, class = typename std::enable_if<detail::pcl_uses_boost<T>>::type>
inline boost::shared_ptr<T> pcl_ptr(const std::shared_ptr<T> &p)
{
return detail::to_boost_ptr(p);
}
template <class T, class = typename std::enable_if<detail::pcl_uses_boost<T>>::type>
inline boost::shared_ptr<T> pcl_ptr(const boost::shared_ptr<T> &p)
{
return p;
}
#else
template <class T>
inline boost::shared_ptr<T> pcl_ptr(const boost::shared_ptr<T> &p)
{
return p;
}
#endif
} // namespace pcl
#endif

View File

@ -64,8 +64,8 @@ namespace pcl_ros
class ExtractPolygonalPrismData : public PCLNodelet
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
protected:
/** \brief The output PointIndices publisher. */

View File

@ -61,8 +61,8 @@ namespace pcl_ros
class SACSegmentation : public PCLNodelet
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
public:
/** \brief Constructor. */
@ -181,12 +181,12 @@ namespace pcl_ros
class SACSegmentationFromNormals: public SACSegmentation
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
typedef pcl::PointCloud<pcl::Normal> PointCloudN;
typedef PointCloudN::Ptr PointCloudNPtr;
typedef PointCloudN::ConstPtr PointCloudNConstPtr;
typedef boost::shared_ptr<PointCloudN> PointCloudNPtr;
typedef boost::shared_ptr<const PointCloudN> PointCloudNConstPtr;
public:
/** \brief Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.

View File

@ -60,8 +60,8 @@ namespace pcl_ros
class SegmentDifferences : public PCLNodelet
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
public:
/** \brief Empty constructor. */

View File

@ -56,8 +56,8 @@ namespace pcl_ros
class ConvexHull2D : public PCLNodelet
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
typedef PointCloud::Ptr PointCloudPtr;
typedef PointCloud::ConstPtr PointCloudConstPtr;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
private:
/** \brief Nodelet initialization routine. */

View File

@ -62,8 +62,8 @@ namespace pcl_ros
typedef pcl::PointNormal NormalOut;
typedef pcl::PointCloud<PointIn> PointCloudIn;
typedef PointCloudIn::Ptr PointCloudInPtr;
typedef PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef boost::shared_ptr<PointCloudIn> PointCloudInPtr;
typedef boost::shared_ptr<const PointCloudIn> PointCloudInConstPtr;
typedef pcl::PointCloud<NormalOut> NormalCloudOut;
typedef pcl::KdTree<PointIn> KdTree;

View File

@ -43,7 +43,7 @@ pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,17 +57,17 @@ pcl_ros::BoundaryEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::BoundaryEstimation BoundaryEstimation;

View File

@ -43,7 +43,7 @@ pcl_ros::FPFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,10 +57,10 @@ pcl_ros::FPFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -68,7 +68,7 @@ pcl_ros::FPFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::FPFHEstimation FPFHEstimation;

View File

@ -43,7 +43,7 @@ pcl_ros::FPFHEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,10 +57,10 @@ pcl_ros::FPFHEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -68,7 +68,7 @@ pcl_ros::FPFHEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::FPFHEstimationOMP FPFHEstimationOMP;

View File

@ -43,7 +43,7 @@ pcl_ros::MomentInvariantsEstimation::emptyPublish (const PointCloudInConstPtr &c
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -56,9 +56,9 @@ pcl_ros::MomentInvariantsEstimation::computePublish (const PointCloudInConstPtr
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setSearchSurface (pcl_ptr(surface));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -66,7 +66,7 @@ pcl_ros::MomentInvariantsEstimation::computePublish (const PointCloudInConstPtr
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::MomentInvariantsEstimation MomentInvariantsEstimation;

View File

@ -43,7 +43,7 @@ pcl_ros::NormalEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -56,9 +56,9 @@ pcl_ros::NormalEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setSearchSurface (pcl_ptr(surface));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -66,7 +66,7 @@ pcl_ros::NormalEstimation::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::NormalEstimation NormalEstimation;

View File

@ -43,7 +43,7 @@ pcl_ros::NormalEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -56,9 +56,9 @@ pcl_ros::NormalEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setSearchSurface (pcl_ptr(surface));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -66,7 +66,7 @@ pcl_ros::NormalEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::NormalEstimationOMP NormalEstimationOMP;

View File

@ -45,7 +45,7 @@ pcl_ros::NormalEstimationTBB::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloud output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -71,7 +71,7 @@ pcl_ros::NormalEstimationTBB::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::NormalEstimationTBB NormalEstimationTBB;

View File

@ -43,7 +43,7 @@ pcl_ros::PFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,10 +57,10 @@ pcl_ros::PFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -68,7 +68,7 @@ pcl_ros::PFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::PFHEstimation PFHEstimation;

View File

@ -43,7 +43,7 @@ pcl_ros::PrincipalCurvaturesEstimation::emptyPublish (const PointCloudInConstPtr
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,10 +57,10 @@ pcl_ros::PrincipalCurvaturesEstimation::computePublish (const PointCloudInConstP
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -68,7 +68,7 @@ pcl_ros::PrincipalCurvaturesEstimation::computePublish (const PointCloudInConstP
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::PrincipalCurvaturesEstimation PrincipalCurvaturesEstimation;

View File

@ -42,7 +42,7 @@ pcl_ros::SHOTEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -56,10 +56,10 @@ pcl_ros::SHOTEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -67,7 +67,7 @@ pcl_ros::SHOTEstimation::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::SHOTEstimation SHOTEstimation;

View File

@ -42,7 +42,7 @@ pcl_ros::SHOTEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -56,10 +56,10 @@ pcl_ros::SHOTEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -67,7 +67,7 @@ pcl_ros::SHOTEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::SHOTEstimationOMP SHOTEstimationOMP;

View File

@ -43,7 +43,7 @@ pcl_ros::VFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)
{
PointCloudOut output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
void
@ -57,10 +57,10 @@ pcl_ros::VFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
impl_.setRadiusSearch (search_radius_);
// Set the inputs
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices);
impl_.setSearchSurface (surface);
impl_.setInputNormals (normals);
impl_.setSearchSurface (pcl_ptr(surface));
impl_.setInputNormals (pcl_ptr(normals));
// Estimate the feature
PointCloudOut output;
impl_.compute (output);
@ -68,7 +68,7 @@ pcl_ros::VFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::VFHEstimation VFHEstimation;

View File

@ -203,7 +203,7 @@ pcl_ros::EuclideanClusterExtraction::input_indices_callback (
if (indices)
indices_ptr.reset (new std::vector<int> (indices->indices));
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices_ptr);
std::vector<pcl::PointIndices> clusters;
@ -240,7 +240,7 @@ pcl_ros::EuclideanClusterExtraction::input_indices_callback (
header.stamp += ros::Duration (i * 0.001);
toPCL(header, output.header);
// Publish a Boost shared ptr const data
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
NODELET_DEBUG ("[segmentAndPublish] Published cluster %zu (with %zu values and stamp %f) on topic %s",
i, clusters[i].indices.size (), header.stamp.toSec (), pnh_->resolveName ("output").c_str ());
}

View File

@ -190,16 +190,16 @@ pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback (
pub_output_.publish (inliers);
return;
}
impl_.setInputPlanarHull (planar_hull.makeShared ());
impl_.setInputPlanarHull (pcl_ptr(planar_hull.makeShared ()));
}
else
impl_.setInputPlanarHull (hull);
impl_.setInputPlanarHull (pcl_ptr(hull));
IndicesPtr indices_ptr;
if (indices && !indices->header.frame_id.empty ())
indices_ptr.reset (new std::vector<int> (indices->indices));
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices_ptr);
// Final check if the data is empty (remember that indices are set to the size of the data -- if indices* = NULL)

View File

@ -325,7 +325,7 @@ pcl_ros::SACSegmentation::input_indices_callback (const PointCloudConstPtr &clou
if (indices && !indices->header.frame_id.empty ())
indices_ptr.reset (new std::vector<int> (indices->indices));
impl_.setInputCloud (cloud_tf);
impl_.setInputCloud (pcl_ptr(cloud_tf));
impl_.setIndices (indices_ptr);
// Final check if the data is empty (remember that indices are set to the size of the data -- if indices* = NULL)
@ -652,8 +652,8 @@ pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback (
return;
}
impl_.setInputCloud (cloud);
impl_.setInputNormals (cloud_normals);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setInputNormals (pcl_ptr(cloud_normals));
IndicesPtr indices_ptr;
if (indices && !indices->header.frame_id.empty ())

View File

@ -116,7 +116,7 @@ pcl_ros::SegmentDifferences::input_target_callback (const PointCloudConstPtr &cl
NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
PointCloud output;
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
return;
}
@ -127,13 +127,13 @@ pcl_ros::SegmentDifferences::input_target_callback (const PointCloudConstPtr &cl
cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
cloud_target->width * cloud_target->height, pcl::getFieldsList (*cloud_target).c_str (), fromPCL(cloud_target->header).stamp.toSec (), cloud_target->header.frame_id.c_str (), pnh_->resolveName ("target").c_str ());
impl_.setInputCloud (cloud);
impl_.setTargetCloud (cloud_target);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setTargetCloud (pcl_ptr(cloud_target));
PointCloud output;
impl_.segment (output);
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
NODELET_DEBUG ("[%s::segmentAndPublish] Published PointCloud2 with %zu points and stamp %f on topic %s", getName ().c_str (),
output.points.size (), fromPCL(output.header).stamp.toSec (), pnh_->resolveName ("output").c_str ());
}

View File

@ -122,7 +122,7 @@ void
NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
// Publish an empty message
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
return;
}
// If indices are given, check if they are valid
@ -131,7 +131,7 @@ void
NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
// Publish an empty message
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
return;
}
@ -151,7 +151,7 @@ void
if (indices)
indices_ptr.reset (new std::vector<int> (indices->indices));
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
impl_.setIndices (indices_ptr);
// Estimate the feature
@ -195,7 +195,7 @@ void
}
// Publish a Boost shared ptr const data
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
}
typedef pcl_ros::ConvexHull2D ConvexHull2D;

View File

@ -142,7 +142,7 @@ pcl_ros::MovingLeastSquares::input_indices_callback (const PointCloudInConstPtr
{
NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
return;
}
// If indices are given, check if they are valid
@ -150,7 +150,7 @@ pcl_ros::MovingLeastSquares::input_indices_callback (const PointCloudInConstPtr
{
NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
return;
}
@ -167,7 +167,7 @@ pcl_ros::MovingLeastSquares::input_indices_callback (const PointCloudInConstPtr
///
// Reset the indices and surface pointers
impl_.setInputCloud (cloud);
impl_.setInputCloud (pcl_ptr(cloud));
IndicesPtr indices_ptr;
if (indices)
@ -183,9 +183,9 @@ pcl_ros::MovingLeastSquares::input_indices_callback (const PointCloudInConstPtr
// Publish a Boost shared ptr const data
// Enforce that the TF frame and the timestamp are copied
output.header = cloud->header;
pub_output_.publish (output.makeShared ());
pub_output_.publish (ros_ptr(output.makeShared ()));
normals->header = cloud->header;
pub_normals_.publish (normals);
pub_normals_.publish (ros_ptr(normals));
}
//////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -83,7 +83,7 @@ class PointCloudToPCD
////////////////////////////////////////////////////////////////////////////////
// Callback
void
cloud_cb (const pcl::PCLPointCloud2::ConstPtr& cloud)
cloud_cb (const boost::shared_ptr<const pcl::PCLPointCloud2>& cloud)
{
if ((cloud->width * cloud->height) == 0)
return;