Go to the documentation of this file.
38 #ifndef PCL_ROS_FILTER_H_
39 #define PCL_ROS_FILTER_H_
45 #include <dynamic_reconfigure/server.h>
46 #include "pcl_ros/FilterConfig.h"
152 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
156 #endif //#ifndef PCL_ROS_FILTER_H_
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
virtual void onInit()
Nodelet initialization routine.
boost::mutex mutex_
Internal mutex.
virtual void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.
pcl::IndicesPtr IndicesPtr
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different.
PointIndices::ConstPtr PointIndicesConstPtr
void input_indices_callback(const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
PointCloud2 + Indices data callback.
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_)....
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
virtual void subscribe()
Lazy transport subscribe routine.
void computePublish(const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
Call the child filter () method, optionally transform the result, and publish it.
std::string filter_field_name_
The desired user filter field name.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointIndices > > > sync_input_indices_a_
message_filters::Subscriber< PointCloud2 > sub_input_filter_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different.
std::string tf_input_orig_frame_
The original data input TF frame.
virtual bool child_init(ros::NodeHandle &, bool &has_service)
Child initialization routine.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
virtual void unsubscribe()
Lazy transport unsubscribe routine.
sensor_msgs::PointCloud2 PointCloud2
pcl::IndicesConstPtr IndicesConstPtr
ros::Subscriber sub_input_
The input PointCloud subscriber.
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)=0
Virtual abstract filter method. To be implemented by every child.
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40