36 #ifndef JSK_PCL_ROS_UTILS_POINTCLOUD_TO_STL_H_ 37 #define JSK_PCL_ROS_UTILS_POINTCLOUD_TO_STL_H_ 42 #include <sensor_msgs/PointCloud2.h> 44 #include <jsk_recognition_msgs/SetPointCloud2.h> 45 #include <visualization_msgs/Marker.h> 49 #include <pcl/point_types.h> 50 #include <pcl/surface/organized_fast_mesh.h> 60 virtual void cloudCallback(
const sensor_msgs::PointCloud2::ConstPtr& input);
61 virtual void exportSTL(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &
cloud);
62 virtual bool createSTL(jsk_recognition_msgs::SetPointCloud2::Request &req,
63 jsk_recognition_msgs::SetPointCloud2::Response &res);
83 pcl::OrganizedFastMesh<pcl::PointXYZRGB>
ofm;
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &input)
pcl::OrganizedFastMesh< pcl::PointXYZRGB > ofm
double maximum_surface_angle_
std::string latest_output_path_
virtual void exportSTL(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud)
ros::Subscriber sub_input_
virtual bool createSTL(jsk_recognition_msgs::SetPointCloud2::Request &req, jsk_recognition_msgs::SetPointCloud2::Response &res)
double triangle_pixel_size_
int maximum_nearest_neighbors_
ros::ServiceServer create_stl_srv_