Go to the documentation of this file.
   36 #ifndef JSK_PCL_ROS_HINTED_PLANE_DETECTOR_H_ 
   37 #define JSK_PCL_ROS_HINTED_PLANE_DETECTOR_H_ 
   40 #include <pcl/point_types.h> 
   43 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   49 #include <geometry_msgs/PolygonStamped.h> 
   50 #include <jsk_recognition_msgs/PolygonArray.h> 
   51 #include <dynamic_reconfigure/server.h> 
   52 #include <jsk_pcl_ros/HintedPlaneDetectorConfig.h> 
   56   class HintedPlaneDetector: 
public jsk_topic_tools::DiagnosticNodelet
 
   59     typedef HintedPlaneDetectorConfig 
Config;
 
   61     sensor_msgs::PointCloud2,
 
   69     virtual void setHintCloud(
const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
   71       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
   72       const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg);
 
   74       pcl::PointCloud<pcl::PointXYZ>::Ptr hint_cloud,
 
   77       pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
 
   80       pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
 
   81       const std::vector<pcl::PointIndices>& cluster_indices,
 
   86       const pcl::PCLHeader& 
header);
 
   89       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
 
   90       const pcl::PointIndices::Ptr indices,
 
   91       pcl::PointIndices& output);
 
   93       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
 
   94       const pcl::PointIndices::Ptr indices,
 
   96       pcl::PointIndices& output);
 
   98       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
 
   99       const pcl::PointIndices::Ptr indices,
 
  100       const Eigen::Vector3f& normal,
 
  101       pcl::PointIndices& output,
 
  102       pcl::ModelCoefficients& coefficients);
 
  104       const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
 
  106       pcl::PointIndices& output);
 
  
ros::Publisher pub_coefficients_
bool enable_normal_filtering_
bool enable_density_filtering_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Publisher pub_density_filtered_indices_
double outlier_threashold_
ros::Subscriber sub_cloud_single_
virtual void hintFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output)
virtual void planeFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const Eigen::Vector3f &normal, pcl::PointIndices &output, pcl::ModelCoefficients &coefficients)
ros::Publisher pub_polygon_array_
virtual void unsubscribe()
virtual void densityFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::PointIndices &output)
virtual ~HintedPlaneDetector()
virtual pcl::PointIndices::Ptr getBestCluster(pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, const std::vector< pcl::PointIndices > &cluster_indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_hint_cloud_
double normal_filter_eps_angle_
ros::Publisher pub_inliers_
int euclidean_clustering_filter_min_size_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
ros::Publisher pub_plane_filtered_indices_
ros::Publisher pub_hint_filtered_indices_
virtual void euclideanFilter(const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output)
sensor_msgs::PointCloud2::ConstPtr hint_cloud_
ros::Publisher pub_hint_polygon_array_
double euclidean_clustering_filter_tolerance_
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &hint_cloud_msg)
virtual bool detectHintPlane(pcl::PointCloud< pcl::PointXYZ >::Ptr hint_cloud, jsk_recognition_utils::ConvexPolygon::Ptr &convex)
virtual void publishPolygon(const jsk_recognition_utils::ConvexPolygon::Ptr convex, ros::Publisher &pub_polygon, ros::Publisher &pub_polygon_array, const pcl::PCLHeader &header)
ros::Publisher pub_euclidean_filtered_indices_
bool enable_euclidean_filtering_
boost::mutex mutex
global mutex.
ros::Subscriber sub_hint_cloud_single_
ros::Publisher pub_hint_inliers_
virtual void configCallback(Config &config, uint32_t level)
double hint_outlier_threashold_
bool enable_distance_filtering_
ros::Publisher pub_hint_coefficients_
virtual void setHintCloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
ros::Publisher pub_polygon_
ros::Publisher pub_hint_polygon_
virtual bool detectLargerPlane(pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, jsk_recognition_utils::ConvexPolygon::Ptr hint_convex)
HintedPlaneDetectorConfig Config
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11