35 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <geometry_msgs/PoseStamped.h>
39 #include <geometry_msgs/PointStamped.h>
41 #include <pcl/point_types.h>
42 #include <pcl/io/pcd_io.h>
43 #include <pcl/kdtree/kdtree_flann.h>
44 #include <pcl/features/normal_3d.h>
45 #include <pcl/surface/gp3.h>
46 #include <pcl/io/vtk_lib_io.h>
47 #include <pcl/TextureMesh.h>
48 #include <pcl/surface/texture_mapping.h>
49 #include <pcl/surface/mls.h>
50 #include <pcl/io/obj_io.h>
51 #include <pcl/filters/filter.h>
59 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
64 visualization_msgs::Marker marker_msg;
65 marker_msg.header =
input->header;
67 marker_msg.ns =
"pcl_mesh_reconstrunction";
69 marker_msg.type = visualization_msgs::Marker::MESH_RESOURCE;
70 marker_msg.action = visualization_msgs::Marker::ADD;
72 marker_msg.pose.position.x = 1;
73 marker_msg.pose.position.y = 1;
74 marker_msg.pose.position.z = 1;
75 marker_msg.pose.orientation.x = 0.0;
76 marker_msg.pose.orientation.y = 0.0;
77 marker_msg.pose.orientation.z = 0.0;
78 marker_msg.pose.orientation.w = 1.0;
79 marker_msg.scale.x = 1;
80 marker_msg.scale.y = 1;
81 marker_msg.scale.z = 1;
88 pcl::PolygonMesh triangles;
89 ofm.setInputCloud (input_cloud);
90 ofm.reconstruct (triangles);
153 std::stringstream ss;
157 ss <<
"/tmp/" << now_time.
toNSec() <<
"_pointcloud.stl";
159 ROS_INFO(
"Writing... %s", ss.str().c_str());
160 pcl::io::savePolygonFileSTL(ss.str(),triangles);
211 jsk_recognition_msgs::SetPointCloud2::Response &res)
213 if(req.name.length())
215 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
223 PCLNodelet::onInit();
241 pub_mesh_ =
pnh_->advertise<visualization_msgs::Marker>(
"pc_stl_mesh", 1);
244 ofm.setTriangulationType (pcl::OrganizedFastMesh<pcl::PointXYZRGB>::TRIANGLE_ADAPTIVE_CUT);