#include <depth_image_triangulation.h>

Classes | |
| struct | triangle |
| triangle points More... | |
Public Types | |
| typedef sensor_msgs::PointCloud2 | InputType |
| typedef triangle_mesh_msgs::TriangleMesh | OutputType |
Public Member Functions | |
| ros::Publisher | createPublisher (ros::NodeHandle &nh) |
| DepthImageTriangulation () | |
| float | dist_3d (const pcl::PointCloud< pcl::PointXYZINormalScanLine > &cloud_in, int a, int b) |
| computes distance between 2 points | |
| void | get_scan_and_point_id (pcl::PointCloud< pcl::PointXYZINormalScanLine > &cloud_in) |
| get scan and point id for hokuyo scans | |
| void | init (ros::NodeHandle &) |
| boost::shared_ptr< const OutputType > | output () |
| void | post () |
| void | pre () |
| std::string | process (const boost::shared_ptr< const InputType > &) |
| std::vector< std::string > | provides () |
| std::vector< std::string > | requires () |
| void | write_vtk_file (std::string output, std::vector< triangle > triangles, const pcl::PointCloud< pcl::PointXYZINormalScanLine > &cloud_in, int nr_tr) |
| writes triangulation result to a VTK file for visualization purposes | |
Static Public Member Functions | |
| static std::string | default_input_topic () |
| static std::string | default_node_name () |
| static std::string | default_output_topic () |
Private Attributes | |
| boost::mutex | cloud_lock_ |
| lock the function when restoring line id | |
| pcl::PointCloud < pcl::PointXYZINormalScanLine > | cloud_with_line_ |
| working point cloud | |
| signed int | index_nr_in_channel_ |
| signed int | line_nr_in_channel_ |
| channel indices for line and index in point cloud msg | |
| int | max_index_ |
| max index and max line in point cloud | |
| float | max_length |
| max allowed length between triangle's line segments | |
| int | max_line_ |
| boost::shared_ptr< OutputType > | mesh_ |
| resultant output triangulated map | |
| ros::NodeHandle | nh_ |
| bool | save_pcd_ |
| bool | write_to_vtk_ |
| write output to vtk yes/no, save PCD file yes/no | |
Definition at line 54 of file depth_image_triangulation.h.
| typedef sensor_msgs::PointCloud2 pcl_cloud_algos::DepthImageTriangulation::InputType |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 64 of file depth_image_triangulation.h.
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 65 of file depth_image_triangulation.h.
Definition at line 118 of file depth_image_triangulation.h.
| ros::Publisher pcl_cloud_algos::DepthImageTriangulation::createPublisher | ( | ros::NodeHandle & | nh | ) | [inline, virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 128 of file depth_image_triangulation.h.
| static std::string pcl_cloud_algos::DepthImageTriangulation::default_input_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 74 of file depth_image_triangulation.h.
| static std::string pcl_cloud_algos::DepthImageTriangulation::default_node_name | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 80 of file depth_image_triangulation.h.
| static std::string pcl_cloud_algos::DepthImageTriangulation::default_output_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 68 of file depth_image_triangulation.h.
| float DepthImageTriangulation::dist_3d | ( | const pcl::PointCloud< pcl::PointXYZINormalScanLine > & | cloud_in, |
| int | a, | ||
| int | b | ||
| ) |
computes distance between 2 points
| cloud_in | |
| int | a |
| int | b |
Definition at line 92 of file depth_image_triangulation.cpp.
| void DepthImageTriangulation::get_scan_and_point_id | ( | pcl::PointCloud< pcl::PointXYZINormalScanLine > & | cloud_in | ) |
get scan and point id for hokuyo scans
| sensor_msg::PointCloud |
Definition at line 51 of file depth_image_triangulation.cpp.
| void DepthImageTriangulation::init | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 100 of file depth_image_triangulation.cpp.
| boost::shared_ptr< const DepthImageTriangulation::OutputType > DepthImageTriangulation::output | ( | ) |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 448 of file depth_image_triangulation.cpp.
| void DepthImageTriangulation::post | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 115 of file depth_image_triangulation.cpp.
| void DepthImageTriangulation::pre | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 109 of file depth_image_triangulation.cpp.
| std::string DepthImageTriangulation::process | ( | const boost::shared_ptr< const InputType > & | ) |
Definition at line 142 of file depth_image_triangulation.cpp.
| std::vector< std::string > DepthImageTriangulation::provides | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 134 of file depth_image_triangulation.cpp.
| std::vector< std::string > DepthImageTriangulation::requires | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 121 of file depth_image_triangulation.cpp.
| void DepthImageTriangulation::write_vtk_file | ( | std::string | output, |
| std::vector< triangle > | triangles, | ||
| const pcl::PointCloud< pcl::PointXYZINormalScanLine > & | cloud_in, | ||
| int | nr_tr | ||
| ) |
writes triangulation result to a VTK file for visualization purposes
| output[] | output vtk file |
| triangles | vector of triangles |
| &cloud_in | |
| nr_tr | number of triangles |
Definition at line 410 of file depth_image_triangulation.cpp.
lock the function when restoring line id
Definition at line 136 of file depth_image_triangulation.h.
pcl::PointCloud<pcl::PointXYZINormalScanLine> pcl_cloud_algos::DepthImageTriangulation::cloud_with_line_ [private] |
working point cloud
Definition at line 142 of file depth_image_triangulation.h.
signed int pcl_cloud_algos::DepthImageTriangulation::index_nr_in_channel_ [private] |
Definition at line 148 of file depth_image_triangulation.h.
signed int pcl_cloud_algos::DepthImageTriangulation::line_nr_in_channel_ [private] |
channel indices for line and index in point cloud msg
Definition at line 148 of file depth_image_triangulation.h.
max index and max line in point cloud
Definition at line 145 of file depth_image_triangulation.h.
float pcl_cloud_algos::DepthImageTriangulation::max_length [private] |
max allowed length between triangle's line segments
Definition at line 151 of file depth_image_triangulation.h.
Definition at line 145 of file depth_image_triangulation.h.
boost::shared_ptr<OutputType> pcl_cloud_algos::DepthImageTriangulation::mesh_ [private] |
resultant output triangulated map
Definition at line 157 of file depth_image_triangulation.h.
Definition at line 139 of file depth_image_triangulation.h.
Definition at line 154 of file depth_image_triangulation.h.
write output to vtk yes/no, save PCD file yes/no
Definition at line 154 of file depth_image_triangulation.h.