Program Listing for File feature.hpp
↰ Return to documentation for file (include/pcl_ros/features/feature.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id: feature.h 35422 2011-01-24 20:04:44Z rusu $
*
*/
#ifndef PCL_ROS__FEATURES__FEATURE_HPP_
#define PCL_ROS__FEATURES__FEATURE_HPP_
// PCL includes
#include <pcl/features/feature.h>
#include <pcl_msgs/PointIndices.h>
#include <message_filters/pass_through.h>
// Dynamic reconfigure
#include <dynamic_reconfigure/server.h>
// PCL conversions
#include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/pcl_nodelet.hpp"
#include "pcl_ros/FeatureConfig.hpp"
namespace pcl_ros
{
namespace sync_policies = message_filters::sync_policies;
class Feature : public PCLNodelet
{
public:
typedef pcl::KdTree<pcl::PointXYZ> KdTree;
typedef pcl::KdTree<pcl::PointXYZ>::Ptr KdTreePtr;
typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn;
typedef boost::shared_ptr<PointCloudIn> PointCloudInPtr;
typedef boost::shared_ptr<const PointCloudIn> PointCloudInConstPtr;
typedef pcl::IndicesPtr IndicesPtr;
typedef pcl::IndicesConstPtr IndicesConstPtr;
Feature()
: /*input_(), indices_(), surface_(), */ tree_(), k_(0), search_radius_(0),
use_surface_(false), spatial_locator_type_(-1)
{}
protected:
// PointCloudInConstPtr input_;
// IndicesConstPtr indices_;
// PointCloudInConstPtr surface_;
KdTreePtr tree_;
int k_;
double search_radius_;
// ROS nodelet attributes
message_filters::Subscriber<PointCloudIn> sub_surface_filter_;
ros::Subscriber sub_input_;
bool use_surface_;
int spatial_locator_type_;
boost::shared_ptr<dynamic_reconfigure::Server<FeatureConfig>> srv_;
virtual bool childInit(ros::NodeHandle & nh) = 0;
virtual void emptyPublish(const PointCloudInConstPtr & cloud) = 0;
virtual void computePublish(
const PointCloudInConstPtr & cloud,
const PointCloudInConstPtr & surface,
const IndicesPtr & indices) = 0;
void config_callback(FeatureConfig & config, uint32_t level);
message_filters::PassThrough<PointIndices> nf_pi_;
message_filters::PassThrough<PointCloudIn> nf_pc_;
inline void
input_callback(const PointCloudInConstPtr & input)
{
PointIndices indices;
indices.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
PointCloudIn cloud;
cloud.header.stamp = input->header.stamp;
nf_pc_.add(ros_ptr(cloud.makeShared()));
nf_pi_.add(boost::make_shared<PointIndices>(indices));
}
private:
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn,
PointCloudIn, PointIndices>>> sync_input_surface_indices_a_;
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn,
PointCloudIn, PointIndices>>> sync_input_surface_indices_e_;
virtual void onInit();
virtual void subscribe();
virtual void unsubscribe();
void input_surface_indices_callback(
const PointCloudInConstPtr & cloud,
const PointCloudInConstPtr & cloud_surface,
const PointIndicesConstPtr & indices);
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
class FeatureFromNormals : public Feature
{
public:
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef pcl::PointCloud<pcl::Normal> PointCloudN;
typedef boost::shared_ptr<PointCloudN> PointCloudNPtr;
typedef boost::shared_ptr<const PointCloudN> PointCloudNConstPtr;
FeatureFromNormals()
: normals_() {}
protected:
PointCloudNConstPtr normals_;
virtual bool childInit(ros::NodeHandle & nh) = 0;
virtual void emptyPublish(const PointCloudInConstPtr & cloud) = 0;
virtual void computePublish(
const PointCloudInConstPtr & cloud,
const PointCloudNConstPtr & normals,
const PointCloudInConstPtr & surface,
const IndicesPtr & indices) = 0;
private:
message_filters::Subscriber<PointCloudN> sub_normals_filter_;
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn,
PointCloudN, PointCloudIn, PointIndices>>> sync_input_normals_surface_indices_a_;
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn,
PointCloudN, PointCloudIn, PointIndices>>> sync_input_normals_surface_indices_e_;
void computePublish(
const PointCloudInConstPtr &,
const PointCloudInConstPtr &,
const IndicesPtr &) {} // This should never be called
virtual void onInit();
virtual void subscribe();
virtual void unsubscribe();
void input_normals_surface_indices_callback(
const PointCloudInConstPtr & cloud,
const PointCloudNConstPtr & cloud_normals,
const PointCloudInConstPtr & cloud_surface,
const PointIndicesConstPtr & indices);
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace pcl_ros
#endif // PCL_ROS__FEATURES__FEATURE_HPP_