#include <pointcloud_to_stl.h>

Public Member Functions | |
| PointCloudToSTL () | |
Protected Member Functions | |
| virtual void | cloudCallback (const sensor_msgs::PointCloud2::ConstPtr &input) |
| virtual bool | createSTL (jsk_recognition_msgs::SetPointCloud2::Request &req, jsk_recognition_msgs::SetPointCloud2::Response &res) |
| virtual void | exportSTL (const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &cloud) |
| virtual void | onInit () |
Protected Attributes | |
| ros::ServiceServer | create_stl_srv_ |
| std::string | file_name_ |
| std::string | frame_ |
| std::string | latest_output_path_ |
| double | max_edge_length_ |
| double | maximum_angle_ |
| int | maximum_nearest_neighbors_ |
| double | maximum_surface_angle_ |
| double | minimum_angle_ |
| double | mu_ |
| bool | normal_consistency_ |
| pcl::OrganizedFastMesh < pcl::PointXYZRGB > | ofm |
| ros::Publisher | pub_mesh_ |
| double | search_radius_ |
| bool | store_shadow_faces_ |
| ros::Subscriber | sub_input_ |
| double | triangle_pixel_size_ |
Definition at line 54 of file pointcloud_to_stl.h.
| jsk_pcl_ros_utils::PointCloudToSTL::PointCloudToSTL | ( | ) | [inline] |
Definition at line 57 of file pointcloud_to_stl.h.
| void jsk_pcl_ros_utils::PointCloudToSTL::cloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | input | ) | [protected, virtual] |
Definition at line 57 of file pointcloud_to_stl_nodelet.cpp.
| bool jsk_pcl_ros_utils::PointCloudToSTL::createSTL | ( | jsk_recognition_msgs::SetPointCloud2::Request & | req, |
| jsk_recognition_msgs::SetPointCloud2::Response & | res | ||
| ) | [protected, virtual] |
Definition at line 210 of file pointcloud_to_stl_nodelet.cpp.
| void jsk_pcl_ros_utils::PointCloudToSTL::exportSTL | ( | const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr & | cloud | ) | [protected, virtual] |
Definition at line 86 of file pointcloud_to_stl_nodelet.cpp.
| void jsk_pcl_ros_utils::PointCloudToSTL::onInit | ( | void | ) | [protected, virtual] |
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 221 of file pointcloud_to_stl_nodelet.cpp.
Definition at line 67 of file pointcloud_to_stl.h.
std::string jsk_pcl_ros_utils::PointCloudToSTL::file_name_ [protected] |
Definition at line 81 of file pointcloud_to_stl.h.
std::string jsk_pcl_ros_utils::PointCloudToSTL::frame_ [protected] |
Definition at line 69 of file pointcloud_to_stl.h.
std::string jsk_pcl_ros_utils::PointCloudToSTL::latest_output_path_ [protected] |
Definition at line 82 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::max_edge_length_ [protected] |
Definition at line 80 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::maximum_angle_ [protected] |
Definition at line 75 of file pointcloud_to_stl.h.
int jsk_pcl_ros_utils::PointCloudToSTL::maximum_nearest_neighbors_ [protected] |
Definition at line 72 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::maximum_surface_angle_ [protected] |
Definition at line 73 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::minimum_angle_ [protected] |
Definition at line 74 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::mu_ [protected] |
Definition at line 71 of file pointcloud_to_stl.h.
bool jsk_pcl_ros_utils::PointCloudToSTL::normal_consistency_ [protected] |
Definition at line 76 of file pointcloud_to_stl.h.
pcl::OrganizedFastMesh<pcl::PointXYZRGB> jsk_pcl_ros_utils::PointCloudToSTL::ofm [protected] |
Definition at line 83 of file pointcloud_to_stl.h.
Definition at line 65 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::search_radius_ [protected] |
Definition at line 70 of file pointcloud_to_stl.h.
bool jsk_pcl_ros_utils::PointCloudToSTL::store_shadow_faces_ [protected] |
Definition at line 77 of file pointcloud_to_stl.h.
Definition at line 66 of file pointcloud_to_stl.h.
double jsk_pcl_ros_utils::PointCloudToSTL::triangle_pixel_size_ [protected] |
Definition at line 79 of file pointcloud_to_stl.h.