00001 // -*- mode: C++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2015, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 #ifndef JSK_PCL_ROS_POINTCLOUD_TO_STL_H_ 00037 #define JSK_PCL_ROS_POINTCLOUD_TO_STL_H_ 00038 00039 // ros 00040 #include <ros/ros.h> 00041 #include <ros/names.h> 00042 #include <sensor_msgs/PointCloud2.h> 00043 #include <tf/transform_broadcaster.h> 00044 #include <jsk_pcl_ros/SetPointCloud2.h> 00045 #include <visualization_msgs/Marker.h> 00046 00047 // pcl 00048 #include <pcl_ros/pcl_nodelet.h> 00049 #include <pcl/point_types.h> 00050 #include <pcl/surface/organized_fast_mesh.h> 00051 00052 namespace jsk_pcl_ros 00053 { 00054 class PointCloudToSTL: public pcl_ros::PCLNodelet 00055 { 00056 public: 00057 PointCloudToSTL(){} 00058 protected: 00059 virtual void onInit(); 00060 virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr& input); 00061 virtual void exportSTL(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud); 00062 virtual bool createSTL(jsk_pcl_ros::SetPointCloud2::Request &req, 00063 jsk_pcl_ros::SetPointCloud2::Response &res); 00064 virtual bool createURDF(jsk_pcl_ros::SetPointCloud2::Request &req, 00065 jsk_pcl_ros::SetPointCloud2::Response &res); 00066 virtual bool spawnURDF(jsk_pcl_ros::SetPointCloud2::Request &req, 00067 jsk_pcl_ros::SetPointCloud2::Response &res); 00068 00069 ros::Publisher pub_mesh_; 00070 ros::Subscriber sub_input_; 00071 ros::ServiceServer create_stl_srv_; 00072 ros::ServiceServer create_urdf_srv_; 00073 ros::ServiceServer spawn_urdf_srv_; 00074 00075 std::string frame_; 00076 double search_radius_; 00077 double mu_; 00078 int maximum_nearest_neighbors_; 00079 double maximum_surface_angle_; 00080 double minimum_angle_; 00081 double maximum_angle_; 00082 bool normal_consistency_; 00083 bool store_shadow_faces_; 00084 00085 double triangle_pixel_size_; 00086 double max_edge_length_; 00087 std::string file_name_; 00088 std::string latest_output_path_; 00089 pcl::OrganizedFastMesh<pcl::PointXYZRGB> ofm; 00090 00091 private: 00092 }; 00093 } 00094 00095 #endif