Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros_utils/pointcloud_to_stl.h"
00037 
00038 #include <geometry_msgs/PoseStamped.h>
00039 #include <geometry_msgs/PointStamped.h>
00040 
00041 #include <pcl/point_types.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/kdtree/kdtree_flann.h>
00044 #include <pcl/features/normal_3d.h>
00045 #include <pcl/surface/gp3.h>
00046 #include <pcl/io/vtk_lib_io.h>
00047 #include <pcl/TextureMesh.h>
00048 #include <pcl/surface/texture_mapping.h>
00049 #include <pcl/surface/mls.h>
00050 #include <pcl/io/obj_io.h>
00051 #include <pcl/filters/filter.h>
00052 
00053 #include "jsk_recognition_utils/pcl_conversion_util.h"
00054 
00055 namespace jsk_pcl_ros_utils
00056 {
00057   void PointCloudToSTL::cloudCallback(const sensor_msgs::PointCloud2::ConstPtr& input)
00058   {
00059     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00060     pcl::fromROSMsg(*input, *cloud);
00061     exportSTL(cloud);
00062 
00063 
00064     visualization_msgs::Marker marker_msg;
00065     marker_msg.header = input->header;
00066     marker_msg.mesh_resource = std::string("package://jsk_pcl_ros_utils/temp.stl");
00067     marker_msg.ns = "pcl_mesh_reconstrunction";
00068     marker_msg.id = 0;
00069     marker_msg.type = visualization_msgs::Marker::MESH_RESOURCE;
00070     marker_msg.action = visualization_msgs::Marker::ADD;
00071 
00072     marker_msg.pose.position.x = 1;
00073     marker_msg.pose.position.y = 1;
00074     marker_msg.pose.position.z = 1;
00075     marker_msg.pose.orientation.x = 0.0;
00076     marker_msg.pose.orientation.y = 0.0;
00077     marker_msg.pose.orientation.z = 0.0;
00078     marker_msg.pose.orientation.w = 1.0;
00079     marker_msg.scale.x = 1;
00080     marker_msg.scale.y = 1;
00081     marker_msg.scale.z = 1;
00082     pub_mesh_.publish(marker_msg);
00083 
00084   }
00085 
00086   void PointCloudToSTL::exportSTL(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &input_cloud){
00087 
00088     pcl::PolygonMesh triangles;
00089     ofm.setInputCloud (input_cloud);
00090     ofm.reconstruct (triangles);
00091 
00092     
00093 
00094 
00095 
00096 
00097 
00098 
00099 
00100 
00101 
00102 
00103 
00104 
00105 
00106 
00107 
00108 
00109 
00110 
00111 
00112 
00113 
00114 
00115 
00116 
00117 
00118 
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 
00130 
00131 
00132 
00133 
00134 
00135 
00136 
00137 
00138 
00139 
00140 
00141 
00142 
00143 
00144 
00145 
00146 
00147 
00148 
00149 
00150 
00151 
00152     ros::Time now_time = ros::Time::now();
00153     std::stringstream ss;
00154     if (file_name_.length())
00155       ss << file_name_.c_str();
00156     else
00157       ss << "/tmp/" << now_time.toNSec() << "_pointcloud.stl";
00158     
00159     ROS_INFO("Writing... %s", ss.str().c_str());
00160     pcl::io::savePolygonFileSTL(ss.str(),triangles);
00161     latest_output_path_ = ss.str();
00162 
00163     
00164 
00165 
00166 
00167 
00168 
00169 
00170 
00171 
00172 
00173 
00174 
00175 
00176 
00177 
00178 
00179 
00180 
00181 
00182 
00183 
00184 
00185 
00186 
00187 
00188 
00189 
00190 
00191 
00192 
00193 
00194 
00195 
00196 
00197 
00198 
00199 
00200 
00201 
00202 
00203 
00204 
00205 
00206 
00207 
00208   }
00209 
00210   bool PointCloudToSTL::createSTL(jsk_recognition_msgs::SetPointCloud2::Request &req,
00211                                   jsk_recognition_msgs::SetPointCloud2::Response &res)
00212   {
00213     if(req.name.length())
00214       file_name_ = req.name;
00215     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00216     pcl::fromROSMsg(req.cloud, *cloud);
00217     exportSTL(cloud);
00218     res.output = latest_output_path_;
00219   }
00220 
00221   void PointCloudToSTL::onInit(void)
00222   {
00223     PCLNodelet::onInit();
00224     pnh_->param("filename", file_name_ , std::string(""));
00225     pnh_->param("search_radius", search_radius_ , 0.05);
00226     pnh_->param("mu", mu_, 3.5);
00227     pnh_->param("maximum_nearest_neighbors", maximum_nearest_neighbors_, 100);
00228     pnh_->param("maximum_surface_angle", maximum_surface_angle_, 0.7853981633974483);
00229     pnh_->param("minimum_angle", minimum_angle_, 0.17453292519943295);
00230     pnh_->param("maximum_angle", maximum_angle_, 2.0943951023931953);
00231     pnh_->param("normal_consistency", normal_consistency_, false);
00232 
00233     pnh_->param("triangle_pixel_size", triangle_pixel_size_, 1.0);
00234     pnh_->param("max_edge_length", max_edge_length_, 4.5);
00235     pnh_->param("store_shadow_faces", store_shadow_faces_, true);
00236 
00237     sub_input_ = pnh_->subscribe("input", 1, &PointCloudToSTL::cloudCallback, this);
00238     create_stl_srv_
00239       = pnh_->advertiseService("create_stl", &PointCloudToSTL::createSTL, this);
00240 
00241     pub_mesh_ = pnh_->advertise<visualization_msgs::Marker>("pc_stl_mesh", 1);
00242 
00243     ofm.setTrianglePixelSize (triangle_pixel_size_);
00244     ofm.setTriangulationType (pcl::OrganizedFastMesh<pcl::PointXYZRGB>::TRIANGLE_ADAPTIVE_CUT);
00245     ofm.setMaxEdgeLength(max_edge_length_);
00246     ofm.storeShadowedFaces(store_shadow_faces_);
00247   }
00248 }
00249 
00250 #include <pluginlib/class_list_macros.h>
00251 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PointCloudToSTL, nodelet::Nodelet);