#include <torus_finder.h>
Definition at line 53 of file torus_finder.h.
typedef TorusFinderConfig jsk_pcl_ros::TorusFinder::Config |
Definition at line 56 of file torus_finder.h.
jsk_pcl_ros::TorusFinder::TorusFinder | ( | ) | [inline] |
Definition at line 57 of file torus_finder.h.
void jsk_pcl_ros::TorusFinder::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 90 of file torus_finder_nodelet.cpp.
void jsk_pcl_ros::TorusFinder::onInit | ( | void | ) | [protected, virtual] |
Definition at line 46 of file torus_finder_nodelet.cpp.
void jsk_pcl_ros::TorusFinder::segment | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg | ) | [protected, virtual] |
Definition at line 140 of file torus_finder_nodelet.cpp.
void jsk_pcl_ros::TorusFinder::segmentFromPoints | ( | const geometry_msgs::PolygonStamped::ConstPtr & | polygon_msg | ) | [protected, virtual] |
Definition at line 116 of file torus_finder_nodelet.cpp.
void jsk_pcl_ros::TorusFinder::subscribe | ( | ) | [protected, virtual] |
Definition at line 104 of file torus_finder_nodelet.cpp.
void jsk_pcl_ros::TorusFinder::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 110 of file torus_finder_nodelet.cpp.
std::string jsk_pcl_ros::TorusFinder::algorithm_ [protected] |
Definition at line 88 of file torus_finder.h.
bool jsk_pcl_ros::TorusFinder::done_initialization_ [protected] |
Definition at line 99 of file torus_finder.h.
double jsk_pcl_ros::TorusFinder::eps_hint_angle_ [protected] |
Definition at line 92 of file torus_finder.h.
Eigen::Vector3f jsk_pcl_ros::TorusFinder::hint_axis_ [protected] |
Definition at line 83 of file torus_finder.h.
int jsk_pcl_ros::TorusFinder::max_iterations_ [protected] |
Definition at line 95 of file torus_finder.h.
double jsk_pcl_ros::TorusFinder::max_radius_ [protected] |
Definition at line 90 of file torus_finder.h.
double jsk_pcl_ros::TorusFinder::min_radius_ [protected] |
Definition at line 89 of file torus_finder.h.
int jsk_pcl_ros::TorusFinder::min_size_ [protected] |
Definition at line 96 of file torus_finder.h.
boost::mutex jsk_pcl_ros::TorusFinder::mutex_ [protected] |
Definition at line 82 of file torus_finder.h.
double jsk_pcl_ros::TorusFinder::outlier_threshold_ [protected] |
Definition at line 91 of file torus_finder.h.
Definition at line 80 of file torus_finder.h.
Definition at line 77 of file torus_finder.h.
ros::Publisher jsk_pcl_ros::TorusFinder::pub_inliers_ [protected] |
Definition at line 76 of file torus_finder.h.
Definition at line 79 of file torus_finder.h.
Definition at line 78 of file torus_finder.h.
ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_ [protected] |
Definition at line 72 of file torus_finder.h.
Definition at line 73 of file torus_finder.h.
Definition at line 75 of file torus_finder.h.
Definition at line 74 of file torus_finder.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::TorusFinder::srv_ [protected] |
Definition at line 69 of file torus_finder.h.
ros::Subscriber jsk_pcl_ros::TorusFinder::sub_ [protected] |
Definition at line 70 of file torus_finder.h.
ros::Subscriber jsk_pcl_ros::TorusFinder::sub_points_ [protected] |
Definition at line 71 of file torus_finder.h.
Definition at line 81 of file torus_finder.h.
bool jsk_pcl_ros::TorusFinder::use_hint_ [protected] |
Definition at line 93 of file torus_finder.h.
bool jsk_pcl_ros::TorusFinder::use_normal_ [protected] |
Definition at line 94 of file torus_finder.h.
bool jsk_pcl_ros::TorusFinder::voxel_grid_sampling_ [protected] |
Definition at line 97 of file torus_finder.h.
double jsk_pcl_ros::TorusFinder::voxel_size_ [protected] |
Definition at line 98 of file torus_finder.h.