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_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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition at line 72 of file pcl_nodelet.h.
typedef boost::shared_ptr<const std::vector<int> > pcl_ros::PCLNodelet::IndicesConstPtr |
Definition at line 90 of file pcl_nodelet.h.
typedef boost::shared_ptr<std::vector<int> > pcl_ros::PCLNodelet::IndicesPtr |
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.
|
inline |
Empty constructor.
Definition at line 93 of file pcl_nodelet.h.
|
inlineprotected |
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.
|
inlineprotected |
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.
|
inlineprotected |
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.
|
inlineprotected |
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.
|
inlineprotectedvirtual |
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Reimplemented from nodelet_topic_tools::NodeletLazy.
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 203 of file pcl_nodelet.h.
|
inlineprotectedvirtual |
Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility.
Implements nodelet_topic_tools::NodeletLazy.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::FeatureFromNormals, pcl_ros::Feature, pcl_ros::SACSegmentation, pcl_ros::Filter, pcl_ros::MovingLeastSquares, pcl_ros::ExtractPolygonalPrismData, pcl_ros::ProjectInliers, pcl_ros::SegmentDifferences, pcl_ros::EuclideanClusterExtraction, and pcl_ros::ConvexHull2D.
Definition at line 198 of file pcl_nodelet.h.
|
inlineprotectedvirtual |
Implements nodelet_topic_tools::NodeletLazy.
Reimplemented in pcl_ros::SACSegmentationFromNormals, pcl_ros::FeatureFromNormals, pcl_ros::Feature, pcl_ros::Filter, pcl_ros::SACSegmentation, pcl_ros::MovingLeastSquares, pcl_ros::ExtractPolygonalPrismData, pcl_ros::ProjectInliers, pcl_ros::SegmentDifferences, pcl_ros::EuclideanClusterExtraction, and pcl_ros::ConvexHull2D.
Definition at line 199 of file pcl_nodelet.h.
|
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.
|
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.
|
protected |
The maximum queue size (default: 3).
Definition at line 127 of file pcl_nodelet.h.
|
protected |
The output PointCloud publisher.
Definition at line 124 of file pcl_nodelet.h.
|
protected |
The message filter subscriber for PointIndices.
Definition at line 121 of file pcl_nodelet.h.
|
protected |
The message filter subscriber for PointCloud2.
Definition at line 118 of file pcl_nodelet.h.
|
protected |
TF listener object.
Definition at line 133 of file pcl_nodelet.h.
|
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.