PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class. More...
#include <pcl_nodelet.h>
Public Types | |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef pcl::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::PointIndices | PointIndices |
typedef PointIndices::ConstPtr | PointIndicesConstPtr |
typedef PointIndices::Ptr | PointIndicesPtr |
Public Member Functions | |
PCLNodelet () | |
Empty constructor. | |
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). | |
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). | |
bool | isValid (const PointIndicesConstPtr &indices, const std::string &topic_name="indices") |
Test whether a given PointIndices message is "valid" (i.e., has values). | |
bool | isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model") |
Test whether a given ModelCoefficients message is "valid" (i.e., has values). | |
virtual void | onInit () |
Nodelet initialization routine. Reads in global parameters used by all nodelets. | |
Protected Attributes | |
bool | approximate_sync_ |
True if we use an approximate time synchronizer versus an exact one (false by default). | |
bool | latched_indices_ |
Set to true if the indices topic is latched. | |
int | max_queue_size_ |
The maximum queue size (default: 3). | |
boost::shared_ptr < ros::NodeHandle > | pnh_ |
The ROS NodeHandle used for parameters, publish/subscribe, etc. | |
ros::Publisher | pub_output_ |
The output PointCloud publisher. | |
message_filters::Subscriber < PointIndices > | sub_indices_filter_ |
The message filter subscriber for PointIndices. | |
message_filters::Subscriber < PointCloud > | sub_input_filter_ |
The message filter subscriber for PointCloud2. | |
tf::TransformListener | tf_listener_ |
TF listener object. | |
bool | use_indices_ |
Set to true if point indices are used. |
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition at line 69 of file pcl_nodelet.h.
typedef boost::shared_ptr<const std::vector<int> > pcl_ros::PCLNodelet::IndicesConstPtr |
Reimplemented in pcl_ros::Feature, and pcl_ros::Filter.
Definition at line 87 of file pcl_nodelet.h.
typedef boost::shared_ptr<std::vector<int> > pcl_ros::PCLNodelet::IndicesPtr |
Reimplemented in pcl_ros::Feature, and pcl_ros::Filter.
Definition at line 86 of file pcl_nodelet.h.
typedef pcl::ModelCoefficients pcl_ros::PCLNodelet::ModelCoefficients |
Definition at line 82 of file pcl_nodelet.h.
typedef ModelCoefficients::ConstPtr pcl_ros::PCLNodelet::ModelCoefficientsConstPtr |
Definition at line 84 of file pcl_nodelet.h.
typedef ModelCoefficients::Ptr pcl_ros::PCLNodelet::ModelCoefficientsPtr |
Definition at line 83 of file pcl_nodelet.h.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::ExtractPolygonalPrismData, pcl_ros::SACSegmentation, pcl_ros::SegmentDifferences, and pcl_ros::ConvexHull2D.
Definition at line 74 of file pcl_nodelet.h.
typedef sensor_msgs::PointCloud2 pcl_ros::PCLNodelet::PointCloud2 |
Reimplemented in pcl_ros::FeatureFromNormals, pcl_ros::PCDWriter, pcl_ros::Filter, and pcl_ros::PCDReader.
Definition at line 72 of file pcl_nodelet.h.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::ExtractPolygonalPrismData, pcl_ros::SACSegmentation, pcl_ros::SegmentDifferences, and pcl_ros::ConvexHull2D.
Definition at line 76 of file pcl_nodelet.h.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::ExtractPolygonalPrismData, pcl_ros::SACSegmentation, pcl_ros::SegmentDifferences, and pcl_ros::ConvexHull2D.
Definition at line 75 of file pcl_nodelet.h.
typedef pcl::PointIndices pcl_ros::PCLNodelet::PointIndices |
Definition at line 78 of file pcl_nodelet.h.
typedef PointIndices::ConstPtr pcl_ros::PCLNodelet::PointIndicesConstPtr |
Definition at line 80 of file pcl_nodelet.h.
typedef PointIndices::Ptr pcl_ros::PCLNodelet::PointIndicesPtr |
Definition at line 79 of file pcl_nodelet.h.
pcl_ros::PCLNodelet::PCLNodelet | ( | ) | [inline] |
Empty constructor.
Definition at line 90 of file pcl_nodelet.h.
bool pcl_ros::PCLNodelet::isValid | ( | const PointCloud2::ConstPtr & | cloud, |
const std::string & | topic_name = "input" |
||
) | [inline, protected] |
Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).
cloud | the point cloud to test |
topic_name | an 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" |
||
) | [inline, protected] |
Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero).
cloud | the point cloud to test |
topic_name | an 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" |
||
) | [inline, protected] |
Test whether a given PointIndices message is "valid" (i.e., has values).
indices | the point indices message to test |
topic_name | an 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" |
||
) | [inline, protected] |
Test whether a given ModelCoefficients message is "valid" (i.e., has values).
model | the model coefficients to test |
topic_name | an 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 | ( | ) | [inline, protected, virtual] |
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Implements nodelet::Nodelet.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::FeatureFromNormals, pcl_ros::Feature, pcl_ros::Filter, pcl_ros::SACSegmentation, pcl_ros::MovingLeastSquares, pcl_ros::PCDWriter, pcl_ros::ExtractPolygonalPrismData, pcl_ros::ProjectInliers, pcl_ros::SegmentDifferences, pcl_ros::EuclideanClusterExtraction, pcl_ros::ConvexHull2D, and pcl_ros::PCDReader.
Definition at line 199 of file pcl_nodelet.h.
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.
boost::shared_ptr<ros::NodeHandle> pcl_ros::PCLNodelet::pnh_ [protected] |
The ROS NodeHandle used for parameters, publish/subscribe, etc.
Definition at line 91 of file pcl_nodelet.h.
ros::Publisher pcl_ros::PCLNodelet::pub_output_ [protected] |
The output PointCloud publisher.
Reimplemented in pcl_ros::ExtractPolygonalPrismData.
Definition at line 124 of file pcl_nodelet.h.
The message filter subscriber for PointIndices.
Definition at line 121 of file pcl_nodelet.h.
The message filter subscriber for PointCloud2.
Reimplemented in pcl_ros::Filter.
Definition at line 118 of file pcl_nodelet.h.
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 107 of file pcl_nodelet.h.