37 #include <sensor_msgs/PointCloud2.h>
38 #include <tf/transform_listener.h>
39 #include <pcl_ros/transforms.h>
42 #include <pcl/point_types.h>
43 #include <pcl/conversions.h>
44 #include <pcl/filters/voxel_grid.h>
47 #include <points_from_volume/points_from_volume.h>
50 #define PFLN printf("LINE= %d in FILE=%s \n", __LINE__, __FILE__);
107 void filter(
const sensor_msgs::PointCloud2Ptr& msg);
116 sensor_msgs::PointCloud2 voxel_filter(
const sensor_msgs::PointCloud2Ptr& msg_in,
double voxel_size);
filtering()
Class constructor.
double min_z
Minimum value for Z pointcloud.
~filtering()
Class destructor.
double max_z
Maximum value for Z pointcloud.
PointCloud< T > pc_out
Point cloud filtered.
string frame_id
The frame_id to transform.
tf::TransformListener * transform_listener_ptr
Pointer to a transform listener.
filtering class declaration
ros::Publisher * pub_ptr
Pointer to pointcloud publisher.
double voxel_size
Voxel grid size.
PointCloud< T > convex_hull
The convex hull for cloud extraction.