Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_TORUS_FINDER_H_
38 #define JSK_PCL_ROS_TORUS_FINDER_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.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>
53 class TorusFinder:
public jsk_topic_tools::DiagnosticNodelet
56 typedef TorusFinderConfig
Config;
62 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
63 virtual void segmentFromPoints(
const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg);
bool done_initialization_
ros::Publisher pub_coefficients_
ros::Publisher pub_torus_array_
ros::Publisher pub_inliers_
ros::Publisher pub_torus_array_with_failure_
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Subscriber sub_points_
bool voxel_grid_sampling_
Eigen::Vector3f hint_axis_
ros::Publisher pub_pose_stamped_
jsk_recognition_utils::WallDurationTimer timer_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
double outlier_threshold_
ros::Publisher pub_latest_time_
ros::Publisher pub_average_time_
boost::mutex mutex
global mutex.
virtual void unsubscribe()
virtual void segmentFromPoints(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg)
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_torus_with_failure_
ros::Publisher pub_torus_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45