Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::TorusFinder Class Reference

#include <torus_finder.h>

Inheritance diagram for jsk_pcl_ros::TorusFinder:
Inheritance graph
[legend]

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 85 of file torus_finder.h.

Member Typedef Documentation

◆ Config

typedef TorusFinderConfig jsk_pcl_ros::TorusFinder::Config

Definition at line 120 of file torus_finder.h.

Constructor & Destructor Documentation

◆ TorusFinder()

jsk_pcl_ros::TorusFinder::TorusFinder ( )
inline

Definition at line 121 of file torus_finder.h.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::TorusFinder::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 90 of file torus_finder_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::TorusFinder::onInit ( )
protectedvirtual

Definition at line 46 of file torus_finder_nodelet.cpp.

◆ segment()

void jsk_pcl_ros::TorusFinder::segment ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
protectedvirtual

Definition at line 140 of file torus_finder_nodelet.cpp.

◆ segmentFromPoints()

void jsk_pcl_ros::TorusFinder::segmentFromPoints ( const geometry_msgs::PolygonStamped::ConstPtr &  polygon_msg)
protectedvirtual

Definition at line 116 of file torus_finder_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::TorusFinder::subscribe ( )
protectedvirtual

Definition at line 104 of file torus_finder_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::TorusFinder::unsubscribe ( )
protectedvirtual

Definition at line 110 of file torus_finder_nodelet.cpp.

Member Data Documentation

◆ algorithm_

std::string jsk_pcl_ros::TorusFinder::algorithm_
protected

Definition at line 152 of file torus_finder.h.

◆ done_initialization_

bool jsk_pcl_ros::TorusFinder::done_initialization_
protected

Definition at line 163 of file torus_finder.h.

◆ eps_hint_angle_

double jsk_pcl_ros::TorusFinder::eps_hint_angle_
protected

Definition at line 156 of file torus_finder.h.

◆ hint_axis_

Eigen::Vector3f jsk_pcl_ros::TorusFinder::hint_axis_
protected

Definition at line 147 of file torus_finder.h.

◆ max_iterations_

int jsk_pcl_ros::TorusFinder::max_iterations_
protected

Definition at line 159 of file torus_finder.h.

◆ max_radius_

double jsk_pcl_ros::TorusFinder::max_radius_
protected

Definition at line 154 of file torus_finder.h.

◆ min_radius_

double jsk_pcl_ros::TorusFinder::min_radius_
protected

Definition at line 153 of file torus_finder.h.

◆ min_size_

int jsk_pcl_ros::TorusFinder::min_size_
protected

Definition at line 160 of file torus_finder.h.

◆ mutex_

boost::mutex jsk_pcl_ros::TorusFinder::mutex_
protected

Definition at line 146 of file torus_finder.h.

◆ outlier_threshold_

double jsk_pcl_ros::TorusFinder::outlier_threshold_
protected

Definition at line 155 of file torus_finder.h.

◆ pub_average_time_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_average_time_
protected

Definition at line 144 of file torus_finder.h.

◆ pub_coefficients_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_coefficients_
protected

Definition at line 141 of file torus_finder.h.

◆ pub_inliers_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_inliers_
protected

Definition at line 140 of file torus_finder.h.

◆ pub_latest_time_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_latest_time_
protected

Definition at line 143 of file torus_finder.h.

◆ pub_pose_stamped_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_pose_stamped_
protected

Definition at line 142 of file torus_finder.h.

◆ pub_torus_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_
protected

Definition at line 136 of file torus_finder.h.

◆ pub_torus_array_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_array_
protected

Definition at line 137 of file torus_finder.h.

◆ pub_torus_array_with_failure_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_array_with_failure_
protected

Definition at line 139 of file torus_finder.h.

◆ pub_torus_with_failure_

ros::Publisher jsk_pcl_ros::TorusFinder::pub_torus_with_failure_
protected

Definition at line 138 of file torus_finder.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::TorusFinder::srv_
protected

Definition at line 133 of file torus_finder.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::TorusFinder::sub_
protected

Definition at line 134 of file torus_finder.h.

◆ sub_points_

ros::Subscriber jsk_pcl_ros::TorusFinder::sub_points_
protected

Definition at line 135 of file torus_finder.h.

◆ timer_

jsk_recognition_utils::WallDurationTimer jsk_pcl_ros::TorusFinder::timer_
protected

Definition at line 145 of file torus_finder.h.

◆ use_hint_

bool jsk_pcl_ros::TorusFinder::use_hint_
protected

Definition at line 157 of file torus_finder.h.

◆ use_normal_

bool jsk_pcl_ros::TorusFinder::use_normal_
protected

Definition at line 158 of file torus_finder.h.

◆ voxel_grid_sampling_

bool jsk_pcl_ros::TorusFinder::voxel_grid_sampling_
protected

Definition at line 161 of file torus_finder.h.

◆ voxel_size_

double jsk_pcl_ros::TorusFinder::voxel_size_
protected

Definition at line 162 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 Jan 7 2025 04:05:46