Go to the documentation of this file.
   39 #ifndef PCL_ROS_FILTERS_CROPBOX_H_ 
   40 #define PCL_ROS_FILTERS_CROPBOX_H_ 
   43 #include <pcl/filters/crop_box.h> 
   47 #include "pcl_ros/CropBoxConfig.h" 
   72         boost::mutex::scoped_lock lock (
mutex_);
 
   73         pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
 
   75         impl_.setInputCloud (pcl_input);
 
   76         impl_.setIndices (indices);
 
   77         pcl::PCLPointCloud2 pcl_output;
 
   78         impl_.filter (pcl_output);
 
   98       pcl::CropBox<pcl::PCLPointCloud2> 
impl_;
 
  100       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  104 #endif  //#ifndef PCL_ROS_FILTERS_CROPBOX_H_ 
  
void config_callback(pcl_ros::CropBoxConfig &config, uint32_t level)
Dynamic reconfigure service callback.
boost::mutex mutex_
Internal mutex.
pcl::IndicesPtr IndicesPtr
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
pcl::CropBox< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
sensor_msgs::PointCloud2 PointCloud2
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::CropBoxConfig > > srv_
Pointer to a dynamic reconfigure service.
CropBox is a filter that allows the user to filter all the data inside of a given box.
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
pcl_ros
Author(s): Open Perception, Julius Kammerl 
, William Woodall 
autogenerated on Fri Jul 12 2024 02:54:40