37 #ifndef JSK_PCL_ROS_TORUS_FINDER_H_ 38 #define JSK_PCL_ROS_TORUS_FINDER_H_ 41 #include <sensor_msgs/PointCloud2.h> 42 #include <jsk_recognition_msgs/TorusArray.h> 43 #include <jsk_recognition_msgs/Torus.h> 44 #include <jsk_pcl_ros/TorusFinderConfig.h> 45 #include <dynamic_reconfigure/server.h> 46 #include <geometry_msgs/PoseStamped.h> 48 #include <geometry_msgs/PolygonStamped.h> 62 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
double outlier_threshold_
Eigen::Vector3f hint_axis_
ros::Publisher pub_latest_time_
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
ros::Publisher pub_torus_
virtual void segmentFromPoints(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg)
ros::Publisher pub_average_time_
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
ros::Publisher pub_torus_array_
ros::Publisher pub_torus_with_failure_
bool done_initialization_
boost::mutex mutex
global mutex.
ros::Publisher pub_torus_array_with_failure_
ros::Publisher pub_coefficients_
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Publisher pub_inliers_
ros::Publisher pub_pose_stamped_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool voxel_grid_sampling_
jsk_recognition_utils::WallDurationTimer timer_
ros::Subscriber sub_points_