Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
pcl_ros::Feature Class Referenceabstract

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods. More...

#include <feature.h>

Inheritance diagram for pcl_ros::Feature:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef pcl::KdTree< pcl::PointXYZ > KdTree
 
typedef pcl::KdTree< pcl::PointXYZ >::Ptr KdTreePtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloudIn
 
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
 
typedef PointCloudIn::Ptr PointCloudInPtr
 
- Public Types inherited from pcl_ros::PCLNodelet
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef pcl_msgs::ModelCoefficients ModelCoefficients
 
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
 
typedef ModelCoefficients::Ptr ModelCoefficientsPtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 

Public Member Functions

 Feature ()
 Empty constructor. More...
 
- Public Member Functions inherited from pcl_ros::PCLNodelet
 PCLNodelet ()
 Empty constructor. More...
 
- Public Member Functions inherited from nodelet_topic_tools::NodeletLazy
 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual bool childInit (ros::NodeHandle &nh)=0
 Child initialization routine. Internal method. More...
 
virtual void computePublish (const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
 Compute the feature and publish it. Internal method. More...
 
void config_callback (FeatureConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
virtual void emptyPublish (const PointCloudInConstPtr &cloud)=0
 Publish an empty point cloud of the feature output type. More...
 
void input_callback (const PointCloudInConstPtr &input)
 Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp. More...
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointIndicesConstPtr &indices, const std::string &topic_name="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
bool isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

int k_
 The number of K nearest neighbors to use for each point. More...
 
message_filters::PassThrough< PointCloudInnf_pc_
 
message_filters::PassThrough< PointIndicesnf_pi_
 Null passthrough filter, used for pushing empty elements in the synchronizer. More...
 
double search_radius_
 The nearest neighbors search radius for each point. More...
 
int spatial_locator_type_
 Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index. More...
 
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
ros::Subscriber sub_input_
 The input PointCloud subscriber. More...
 
message_filters::Subscriber< PointCloudInsub_surface_filter_
 The surface PointCloud subscriber filter. More...
 
KdTreePtr tree_
 The input point cloud dataset. More...
 
bool use_surface_
 Set to true if the nodelet needs to listen for incoming point clouds representing the search surface. More...
 
- Protected Attributes inherited from pcl_ros::PCLNodelet
bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
bool latched_indices_
 Set to true if the indices topic is latched. More...
 
int max_queue_size_
 The maximum queue size (default: 3). More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
message_filters::Subscriber< PointIndicessub_indices_filter_
 The message filter subscriber for PointIndices. More...
 
message_filters::Subscriber< PointCloudsub_input_filter_
 The message filter subscriber for PointCloud2. More...
 
tf::TransformListener tf_listener_
 TF listener object. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

Private Member Functions

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. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
virtual void subscribe ()
 NodeletLazy connection routine. More...
 
virtual void unsubscribe ()
 

Private Attributes

boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_a_
 Synchronized input, surface, and point indices. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
 

Detailed Description

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods.

Author
Radu Bogdan Rusu

Definition at line 66 of file feature.h.

Member Typedef Documentation

typedef boost::shared_ptr<const std::vector<int> > pcl_ros::Feature::IndicesConstPtr

Definition at line 77 of file feature.h.

typedef boost::shared_ptr<std::vector<int> > pcl_ros::Feature::IndicesPtr

Definition at line 76 of file feature.h.

typedef pcl::KdTree<pcl::PointXYZ> pcl_ros::Feature::KdTree

Definition at line 69 of file feature.h.

typedef pcl::KdTree<pcl::PointXYZ>::Ptr pcl_ros::Feature::KdTreePtr

Definition at line 70 of file feature.h.

Definition at line 72 of file feature.h.

typedef PointCloudIn::ConstPtr pcl_ros::Feature::PointCloudInConstPtr

Definition at line 74 of file feature.h.

typedef PointCloudIn::Ptr pcl_ros::Feature::PointCloudInPtr

Definition at line 73 of file feature.h.

Constructor & Destructor Documentation

pcl_ros::Feature::Feature ( )
inline

Empty constructor.

Definition at line 80 of file feature.h.

Member Function Documentation

virtual bool pcl_ros::Feature::childInit ( ros::NodeHandle nh)
protectedpure virtual
virtual void pcl_ros::Feature::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudInConstPtr surface,
const IndicesPtr indices 
)
protectedpure virtual
void pcl_ros::Feature::config_callback ( FeatureConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure callback.

Parameters
configthe config object
levelthe dynamic reconfigure level

Definition at line 180 of file features/feature.cpp.

virtual void pcl_ros::Feature::emptyPublish ( const PointCloudInConstPtr cloud)
protectedpure virtual
void pcl_ros::Feature::input_callback ( const PointCloudInConstPtr input)
inlineprotected

Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.

Definition at line 150 of file feature.h.

void pcl_ros::Feature::input_surface_indices_callback ( const PointCloudInConstPtr cloud,
const PointCloudInConstPtr cloud_surface,
const PointIndicesConstPtr indices 
)
private

Input point cloud callback. Used when use_indices and use_surface are set.

Parameters
cloudthe pointer to the input point cloud
cloud_surfacethe pointer to the surface point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 196 of file features/feature.cpp.

void pcl_ros::Feature::onInit ( )
privatevirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::FeatureFromNormals.

Definition at line 56 of file features/feature.cpp.

void pcl_ros::Feature::subscribe ( )
privatevirtual

NodeletLazy connection routine.

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::FeatureFromNormals.

Definition at line 101 of file features/feature.cpp.

void pcl_ros::Feature::unsubscribe ( )
privatevirtual

Reimplemented from pcl_ros::PCLNodelet.

Reimplemented in pcl_ros::FeatureFromNormals.

Definition at line 160 of file features/feature.cpp.

Member Data Documentation

int pcl_ros::Feature::k_
protected

The number of K nearest neighbors to use for each point.

Definition at line 98 of file feature.h.

message_filters::PassThrough<PointCloudIn> pcl_ros::Feature::nf_pc_
protected

Definition at line 143 of file feature.h.

message_filters::PassThrough<PointIndices> pcl_ros::Feature::nf_pi_
protected

Null passthrough filter, used for pushing empty elements in the synchronizer.

Definition at line 142 of file feature.h.

double pcl_ros::Feature::search_radius_
protected

The nearest neighbors search radius for each point.

Definition at line 101 of file feature.h.

int pcl_ros::Feature::spatial_locator_type_
protected

Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.

Definition at line 118 of file feature.h.

boost::shared_ptr<dynamic_reconfigure::Server<FeatureConfig> > pcl_ros::Feature::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 121 of file feature.h.

ros::Subscriber pcl_ros::Feature::sub_input_
protected

The input PointCloud subscriber.

Definition at line 108 of file feature.h.

message_filters::Subscriber<PointCloudIn> pcl_ros::Feature::sub_surface_filter_
protected

The surface PointCloud subscriber filter.

Definition at line 105 of file feature.h.

Synchronized input, surface, and point indices.

Definition at line 162 of file feature.h.

Definition at line 163 of file feature.h.

KdTreePtr pcl_ros::Feature::tree_
protected

The input point cloud dataset.

A pointer to the vector of point indices to use. An input point cloud describing the surface that is to be used for nearest neighbors estimation. A pointer to the spatial search object.

Definition at line 82 of file feature.h.

bool pcl_ros::Feature::use_surface_
protected

Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.

Definition at line 111 of file feature.h.


The documentation for this class was generated from the following files:


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18