Go to the documentation of this file.
38 #ifndef PCL_ROS_FEATURE_H_
39 #define PCL_ROS_FEATURE_H_
42 #include <pcl/features/feature.h>
48 #include <dynamic_reconfigure/server.h>
49 #include "pcl_ros/FeatureConfig.h"
68 typedef pcl::KdTree<pcl::PointXYZ>
KdTree;
154 cloud.header.stamp = input->header.stamp;
156 nf_pi_.
add (boost::make_shared<PointIndices> (indices));
181 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
246 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
250 #endif //#ifndef PCL_ROS_FEATURE_H_
boost::shared_ptr< PointCloudN > PointCloudNPtr
boost::shared_ptr< PointCloudIn > PointCloudInPtr
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
bool use_surface_
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
Pointer to a dynamic reconfigure service.
pcl::KdTree< pcl::PointXYZ > KdTree
void input_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
void input_normals_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_a_
Synchronized input, surface, and point indices.
pcl::IndicesConstPtr IndicesConstPtr
PointCloudNConstPtr normals_
A pointer to the input dataset that contains the point normals of the XYZ dataset.
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it.
PointIndices::ConstPtr PointIndicesConstPtr
boost::shared_ptr< const PointCloudN > PointCloudNConstPtr
pcl::IndicesPtr IndicesPtr
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 &)
Internal method.
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
message_filters::Subscriber< PointCloudN > sub_normals_filter_
The normals PointCloud subscriber filter.
Feature()
Empty constructor.
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
sensor_msgs::PointCloud2 PointCloud2
pcl::PointCloud< pcl::PointXYZ > PointCloudIn
virtual void unsubscribe()
int k_
The number of K nearest neighbors to use for each point.
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
pcl::KdTree< pcl::PointXYZ >::Ptr KdTreePtr
void add(const EventType &evt)
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > sync_input_normals_surface_indices_a_
Synchronized input, normals, surface, and point indices.
virtual void onInit()
Nodelet initialization routine.
virtual void subscribe()
NodeletLazy connection routine.
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
message_filters::PassThrough< PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
virtual void subscribe()
NodeletLazy connection routine.
KdTreePtr tree_
The input point cloud dataset.
message_filters::PassThrough< PointCloudIn > nf_pc_
ros::Subscriber sub_input_
The input PointCloud subscriber.
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
void input_callback(const PointCloudInConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
pcl_msgs::PointIndices PointIndices
pcl::PointCloud< pcl::Normal > PointCloudN
double search_radius_
The nearest neighbors search radius for each point.
virtual void onInit()
Nodelet initialization routine.
boost::shared_ptr< T > ros_ptr(const boost::shared_ptr< T > &p)
void config_callback(FeatureConfig &config, uint32_t level)
Dynamic reconfigure callback.
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it. Internal method.
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40