Template Class PCLNode
- Defined in File pcl_node.hpp 
Inheritance Relationships
Base Type
- public rclcpp::Node
Class Documentation
- 
template<typename T, typename PublisherT = rclcpp::Publisher<T>>
 class PCLNode : public rclcpp::Node
- PCLNode represents the base PCL Node class. All PCL node should inherit from this class. - Public Types - 
typedef sensor_msgs::msg::PointCloud2 PointCloud2
 - 
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud
 - 
typedef PointCloud::Ptr PointCloudPtr
 - 
typedef PointCloud::ConstPtr PointCloudConstPtr
 - 
typedef pcl_msgs::msg::PointIndices PointIndices
 - 
typedef PointIndices::SharedPtr PointIndicesPtr
 - 
typedef PointIndices::ConstSharedPtr PointIndicesConstPtr
 - 
typedef pcl_msgs::msg::ModelCoefficients ModelCoefficients
 - 
typedef ModelCoefficients::SharedPtr ModelCoefficientsPtr
 - 
typedef ModelCoefficients::ConstSharedPtr ModelCoefficientsConstPtr
 - 
typedef pcl::IndicesPtr IndicesPtr
 - 
typedef pcl::IndicesConstPtr IndicesConstPtr
 - Public Functions - 
inline PCLNode(std::string node_name, const rclcpp::NodeOptions &options)
- Empty constructor. 
 - Protected Functions - Test whether a given PointCloud message is “valid” (i.e., has points, and width and height are non-zero). - Parameters:
- cloud – the point cloud to test 
- topic_name – an optional topic name (only used for printing, defaults to “input”) 
 
 
 - 
inline 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). - Parameters:
- cloud – the point cloud to test 
- topic_name – an optional topic name (only used for printing, defaults to “input”) 
 
 
 - 
inline bool isValid(const PointIndicesConstPtr&, const std::string& = "indices")
- Test whether a given PointIndices message is “valid” (i.e., has values). - Parameters:
- indices – the point indices message to test 
- topic_name – an optional topic name (only used for printing, defaults to “indices”) 
 
 
 - 
inline bool isValid(const ModelCoefficientsConstPtr&, const std::string& = "model")
- Test whether a given ModelCoefficients message is “valid” (i.e., has values). - Parameters:
- model – the model coefficients to test 
- topic_name – an optional topic name (only used for printing, defaults to “model”) 
 
 
 - 
inline virtual void subscribe()
- Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility. 
 - 
inline virtual void unsubscribe()
 - Protected Attributes - 
bool use_indices_
- 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 transient_local_indices_ and approximate_sync. 
 - 
bool transient_local_indices_
- Set to true if the indices topic has transient_local durability. - 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. 
 - 
message_filters::Subscriber<PointCloud2> sub_input_filter_
- The message filter subscriber for PointCloud2. 
 - 
message_filters::Subscriber<PointIndices> sub_indices_filter_
- The message filter subscriber for PointIndices. 
 - 
std::shared_ptr<PublisherT> pub_output_
- The output PointCloud publisher. Allow each individual class that inherits from this to declare the Publisher with their type. 
 - 
int max_queue_size_
- The maximum queue size (default: 3). 
 - 
bool approximate_sync_
- True if we use an approximate time synchronizer versus an exact one (false by default). 
 - 
tf2_ros::Buffer tf_buffer_
- TF listener object. 
 - 
tf2_ros::TransformListener tf_listener_
 
- 
typedef sensor_msgs::msg::PointCloud2 PointCloud2