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 #ifndef CLOUD_ALGOS_DEPTH_IMAGE_TRIANGULATION_H
00032 #define CLOUD_ALGOS_DEPTH_IMAGE_TRIANGULATION_H
00033
00034 #include <pcl_cloud_algos/cloud_algos.h>
00035 #include <pcl_cloud_algos/pcl_cloud_algos_point_types.h>
00036
00037
00038 #include <Eigen/Core>
00039 #include <Eigen/LU>
00040 #include <Eigen/Geometry>
00041
00042
00043 #include <sensor_msgs/PointCloud.h>
00044 #include <sensor_msgs/PointCloud2.h>
00045 #include <geometry_msgs/Point32.h>
00046 #include <triangle_mesh_msgs/TriangleMesh.h>
00047
00048
00049 #include <boost/thread/mutex.hpp>
00050
00051 namespace pcl_cloud_algos
00052 {
00053
00054 class DepthImageTriangulation : public CloudAlgo
00055 {
00056 public:
00058 struct triangle
00059 {
00060 int a,b,c;
00061 };
00062
00063
00064 typedef sensor_msgs::PointCloud2 InputType;
00065 typedef triangle_mesh_msgs::TriangleMesh OutputType;
00066
00067
00068 static std::string default_output_topic ()
00069 {
00070 return std::string ("cloud_triangulated");
00071 }
00072
00073
00074 static std::string default_input_topic ()
00075 {
00076 return std::string ("cloud_pcd");
00077 }
00078
00079
00080 static std::string default_node_name ()
00081 {
00082 return std::string ("depth_image_triangulation_node");
00083 }
00084
00085
00086 void init (ros::NodeHandle&);
00087 void pre ();
00088 void post ();
00089 std::vector<std::string> requires ();
00090 std::vector<std::string> provides ();
00091 std::string process (const boost::shared_ptr<const InputType>&);
00092 boost::shared_ptr<const OutputType> output ();
00093
00098 void get_scan_and_point_id (pcl::PointCloud<pcl::PointXYZINormalScanLine> &cloud_in);
00099
00106 float dist_3d (const pcl::PointCloud<pcl::PointXYZINormalScanLine> &cloud_in, int a, int b);
00107
00115 void write_vtk_file (std::string output, std::vector<triangle> triangles, const pcl::PointCloud<pcl::PointXYZINormalScanLine> &cloud_in, int nr_tr);
00116
00117
00118 DepthImageTriangulation () : CloudAlgo ()
00119 {
00120 max_length = 0.05;
00121 max_index_ = max_line_ = 0;
00122 write_to_vtk_ = true;
00123 save_pcd_ = false;
00124 line_nr_in_channel_ = index_nr_in_channel_ = -1;
00125 }
00126
00127
00128 ros::Publisher createPublisher (ros::NodeHandle& nh)
00129 {
00130 ros::Publisher p = nh.advertise<OutputType> (default_output_topic (), 5);
00131 return p;
00132 }
00133
00134 private:
00136 boost::mutex cloud_lock_;
00137
00138
00139 ros::NodeHandle nh_;
00140
00142 pcl::PointCloud<pcl::PointXYZINormalScanLine> cloud_with_line_;
00143
00145 int max_index_, max_line_;
00146
00148 signed int line_nr_in_channel_, index_nr_in_channel_;
00149
00151 float max_length;
00152
00154 bool write_to_vtk_, save_pcd_;
00155
00157 boost::shared_ptr<OutputType> mesh_;
00158 };
00159 }
00160 #endif
00161