#include <torus_finder.h>
|
typedef TorusFinderConfig | Config |
|
Definition at line 85 of file torus_finder.h.
◆ Config
◆ TorusFinder()
jsk_pcl_ros::TorusFinder::TorusFinder |
( |
| ) |
|
|
inline |
◆ configCallback()
void jsk_pcl_ros::TorusFinder::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::TorusFinder::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ segment()
void jsk_pcl_ros::TorusFinder::segment |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg | ) |
|
|
protectedvirtual |
◆ segmentFromPoints()
void jsk_pcl_ros::TorusFinder::segmentFromPoints |
( |
const geometry_msgs::PolygonStamped::ConstPtr & |
polygon_msg | ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::TorusFinder::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::TorusFinder::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ algorithm_
◆ done_initialization_
bool jsk_pcl_ros::TorusFinder::done_initialization_ |
|
protected |
◆ eps_hint_angle_
double jsk_pcl_ros::TorusFinder::eps_hint_angle_ |
|
protected |
◆ hint_axis_
◆ max_iterations_
int jsk_pcl_ros::TorusFinder::max_iterations_ |
|
protected |
◆ max_radius_
double jsk_pcl_ros::TorusFinder::max_radius_ |
|
protected |
◆ min_radius_
double jsk_pcl_ros::TorusFinder::min_radius_ |
|
protected |
◆ min_size_
int jsk_pcl_ros::TorusFinder::min_size_ |
|
protected |
◆ mutex_
◆ outlier_threshold_
double jsk_pcl_ros::TorusFinder::outlier_threshold_ |
|
protected |
◆ pub_average_time_
◆ pub_coefficients_
◆ pub_inliers_
◆ pub_latest_time_
◆ pub_pose_stamped_
◆ pub_torus_
◆ pub_torus_array_
◆ pub_torus_array_with_failure_
ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_array_with_failure_ |
|
protected |
◆ pub_torus_with_failure_
◆ srv_
◆ sub_
◆ sub_points_
◆ timer_
◆ use_hint_
bool jsk_pcl_ros::TorusFinder::use_hint_ |
|
protected |
◆ use_normal_
bool jsk_pcl_ros::TorusFinder::use_normal_ |
|
protected |
◆ voxel_grid_sampling_
bool jsk_pcl_ros::TorusFinder::voxel_grid_sampling_ |
|
protected |
◆ voxel_size_
double jsk_pcl_ros::TorusFinder::voxel_size_ |
|
protected |
The documentation for this class was generated from the following files: