Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pcl_ros::PCLNodelet Class Reference

PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class. More...

#include <pcl_nodelet.h>

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

Public Types

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

 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

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...
 
virtual void onInit ()
 Nodelet initialization routine. Reads in global parameters used by all nodelets. More...
 
virtual void subscribe ()
 Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility. More...
 
virtual void unsubscribe ()
 
- 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

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_
 

Detailed Description

PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.

Definition at line 72 of file pcl_nodelet.h.

Member Typedef Documentation

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

Definition at line 90 of file pcl_nodelet.h.

Definition at line 89 of file pcl_nodelet.h.

typedef pcl_msgs::ModelCoefficients pcl_ros::PCLNodelet::ModelCoefficients

Definition at line 85 of file pcl_nodelet.h.

typedef ModelCoefficients::ConstPtr pcl_ros::PCLNodelet::ModelCoefficientsConstPtr

Definition at line 87 of file pcl_nodelet.h.

typedef ModelCoefficients::Ptr pcl_ros::PCLNodelet::ModelCoefficientsPtr

Definition at line 86 of file pcl_nodelet.h.

typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::PCLNodelet::PointCloud

Definition at line 77 of file pcl_nodelet.h.

typedef sensor_msgs::PointCloud2 pcl_ros::PCLNodelet::PointCloud2

Definition at line 75 of file pcl_nodelet.h.

typedef PointCloud::ConstPtr pcl_ros::PCLNodelet::PointCloudConstPtr

Definition at line 79 of file pcl_nodelet.h.

typedef PointCloud::Ptr pcl_ros::PCLNodelet::PointCloudPtr

Definition at line 78 of file pcl_nodelet.h.

typedef pcl_msgs::PointIndices pcl_ros::PCLNodelet::PointIndices

Definition at line 81 of file pcl_nodelet.h.

typedef PointIndices::ConstPtr pcl_ros::PCLNodelet::PointIndicesConstPtr

Definition at line 83 of file pcl_nodelet.h.

typedef PointIndices::Ptr pcl_ros::PCLNodelet::PointIndicesPtr

Definition at line 82 of file pcl_nodelet.h.

Constructor & Destructor Documentation

pcl_ros::PCLNodelet::PCLNodelet ( )
inline

Empty constructor.

Definition at line 93 of file pcl_nodelet.h.

Member Function Documentation

bool pcl_ros::PCLNodelet::isValid ( const PointCloud2::ConstPtr &  cloud,
const std::string &  topic_name = "input" 
)
inlineprotected

Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).

Parameters
cloudthe point cloud to test
topic_namean optional topic name (only used for printing, defaults to "input")

Definition at line 140 of file pcl_nodelet.h.

bool pcl_ros::PCLNodelet::isValid ( const PointCloudConstPtr cloud,
const std::string &  topic_name = "input" 
)
inlineprotected

Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).

Parameters
cloudthe point cloud to test
topic_namean optional topic name (only used for printing, defaults to "input")

Definition at line 156 of file pcl_nodelet.h.

bool pcl_ros::PCLNodelet::isValid ( const PointIndicesConstPtr indices,
const std::string &  topic_name = "indices" 
)
inlineprotected

Test whether a given PointIndices message is "valid" (i.e., has values).

Parameters
indicesthe point indices message to test
topic_namean optional topic name (only used for printing, defaults to "indices")

Definition at line 172 of file pcl_nodelet.h.

bool pcl_ros::PCLNodelet::isValid ( const ModelCoefficientsConstPtr model,
const std::string &  topic_name = "model" 
)
inlineprotected

Test whether a given ModelCoefficients message is "valid" (i.e., has values).

Parameters
modelthe model coefficients to test
topic_namean optional topic name (only used for printing, defaults to "model")

Definition at line 187 of file pcl_nodelet.h.

virtual void pcl_ros::PCLNodelet::onInit ( )
inlineprotectedvirtual
virtual void pcl_ros::PCLNodelet::subscribe ( )
inlineprotectedvirtual
virtual void pcl_ros::PCLNodelet::unsubscribe ( )
inlineprotectedvirtual

Member Data Documentation

bool pcl_ros::PCLNodelet::approximate_sync_
protected

True if we use an approximate time synchronizer versus an exact one (false by default).

Definition at line 130 of file pcl_nodelet.h.

bool pcl_ros::PCLNodelet::latched_indices_
protected

Set to true if the indices topic is latched.

If use_indices_ is true, the ~input and ~indices topics generally must be synchronised in time. By setting this flag to true, the most recent value from ~indices can be used instead of requiring a synchronised message.

Definition at line 115 of file pcl_nodelet.h.

int pcl_ros::PCLNodelet::max_queue_size_
protected

The maximum queue size (default: 3).

Definition at line 127 of file pcl_nodelet.h.

ros::Publisher pcl_ros::PCLNodelet::pub_output_
protected

The output PointCloud publisher.

Definition at line 124 of file pcl_nodelet.h.

message_filters::Subscriber<PointIndices> pcl_ros::PCLNodelet::sub_indices_filter_
protected

The message filter subscriber for PointIndices.

Definition at line 121 of file pcl_nodelet.h.

message_filters::Subscriber<PointCloud> pcl_ros::PCLNodelet::sub_input_filter_
protected

The message filter subscriber for PointCloud2.

Definition at line 118 of file pcl_nodelet.h.

tf::TransformListener pcl_ros::PCLNodelet::tf_listener_
protected

TF listener object.

Definition at line 133 of file pcl_nodelet.h.

bool pcl_ros::PCLNodelet::use_indices_
protected

Set to true if point indices are used.

When receiving a point cloud, if use_indices_ is false, the entire point cloud is processed for the given operation. If use_indices_ is true, then the ~indices topic is read to get the vector of point indices specifying the subset of the point cloud that will be used for the operation. In the case where use_indices_ is true, the ~input and ~indices topics must be synchronised in time, either exact or within a specified jitter. See also latched_indices_ and approximate_sync.

Definition at line 94 of file pcl_nodelet.h.


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


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