32 #ifndef _LASER_TO_PC_H_
33 #define _LASER_TO_PC_H_
37 #include <sensor_msgs/PointCloud2.h>
38 #include <tf/transform_listener.h>
39 #include <pcl_ros/transforms.h>
40 #include <laser_geometry/laser_geometry.h>
43 #include <pcl/point_types.h>
44 #include <pcl/conversions.h>
47 #include <points_from_volume/points_from_volume.h>
69 ros::Publisher *pub_ptr;
86 void filter (
const sensor_msgs::LaserScanPtr& msg);
tf::TransformListener * listener_ptr
transform_listener pointer
PointCloud< PointXYZ > convex_hull
convex_hull for extraction
laser_to_pc()
class constructor
double min_z
z limits for extraction
~laser_to_pc()
class destructor