Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::TorusFinder Class Reference

#include <torus_finder.h>

List of all members.

Public Types

typedef TorusFinderConfig Config

Public Member Functions

 TorusFinder ()

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual void onInit ()
virtual void segment (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void segmentFromPoints (const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

std::string algorithm_
bool done_initialization_
double eps_hint_angle_
Eigen::Vector3f hint_axis_
int max_iterations_
double max_radius_
double min_radius_
int min_size_
boost::mutex mutex_
double outlier_threshold_
ros::Publisher pub_average_time_
ros::Publisher pub_coefficients_
ros::Publisher pub_inliers_
ros::Publisher pub_latest_time_
ros::Publisher pub_pose_stamped_
ros::Publisher pub_torus_
ros::Publisher pub_torus_array_
ros::Publisher pub_torus_array_with_failure_
ros::Publisher pub_torus_with_failure_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_
ros::Subscriber sub_points_
jsk_recognition_utils::WallDurationTimer timer_
bool use_hint_
bool use_normal_
bool voxel_grid_sampling_
double voxel_size_

Detailed Description

Definition at line 53 of file torus_finder.h.


Member Typedef Documentation

typedef TorusFinderConfig jsk_pcl_ros::TorusFinder::Config

Definition at line 56 of file torus_finder.h.


Constructor & Destructor Documentation

Definition at line 57 of file torus_finder.h.


Member Function Documentation

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.


Member Data Documentation

Definition at line 88 of file torus_finder.h.

Definition at line 99 of file torus_finder.h.

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.

Definition at line 95 of file torus_finder.h.

Definition at line 90 of file torus_finder.h.

Definition at line 89 of file torus_finder.h.

Definition at line 96 of file torus_finder.h.

Definition at line 82 of file torus_finder.h.

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.

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.

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.

Definition at line 70 of file torus_finder.h.

Definition at line 71 of file torus_finder.h.

Definition at line 81 of file torus_finder.h.

Definition at line 93 of file torus_finder.h.

Definition at line 94 of file torus_finder.h.

Definition at line 97 of file torus_finder.h.

Definition at line 98 of file torus_finder.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:47