Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_REGION_GROWING_MULTIPLE_PLANE_SEGMENTATION_H_
38 #define JSK_PCL_ROS_REGION_GROWING_MULTIPLE_PLANE_SEGMENTATION_H_
40 #include <dynamic_reconfigure/server.h>
41 #include "jsk_pcl_ros/RegionGrowingMultiplePlaneSegmentationConfig.h"
46 #include <jsk_topic_tools/diagnostic_nodelet.h>
48 #include "jsk_recognition_msgs/PolygonArray.h"
49 #include "jsk_recognition_msgs/ClusterPointIndices.h"
50 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
52 #include <std_msgs/Float32.h>
56 class RegionGrowingMultiplePlaneSegmentation:
57 public jsk_topic_tools::DiagnosticNodelet
60 typedef pcl::PointXYZRGB
PointT;
61 typedef RegionGrowingMultiplePlaneSegmentationConfig
64 sensor_msgs::PointCloud2,
67 : DiagnosticNodelet(
"RegionGrowingMultiplePlaneSegmentation"),
79 const sensor_msgs::PointCloud2::ConstPtr&
msg,
80 const sensor_msgs::PointCloud2::ConstPtr& normal_msg);
87 const double angular_threshold,
88 const double distance_threshold)
94 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr &cloud,
95 const pcl::PointIndices::Ptr& indices,
96 pcl::PointIndices& inliers,
97 pcl::ModelCoefficients& coefficient);
100 const pcl::PointXYZRGBNormal& b,
107 Eigen::Vector3f a_normal(
a.normal_x,
a.normal_y,
a.normal_z);
108 Eigen::Vector3f b_normal(
b.normal_x,
b.normal_y,
b.normal_z);
109 double dot = std::abs(a_normal.dot(b_normal));
114 else if (dot < -1.0) {
jsk_recognition_utils::WallDurationTimer timer_
double angular_threshold_
RegionGrowingMultiplePlaneSegmentation()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > NormalSyncPolicy
static void setCondifionFunctionParameter(const double angular_threshold, const double distance_threshold)
ros::Publisher pub_average_time_
double cluster_tolerance_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
static double global_angular_threshold
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::PointCloud2::ConstPtr &normal_msg)
ros::Publisher pub_inliers_
virtual void configCallback(Config &config, uint32_t level)
double ransac_refine_outlier_distance_threshold_
static bool regionGrowingFunction(const pcl::PointXYZRGBNormal &a, const pcl::PointXYZRGBNormal &b, float distance)
virtual void ransacEstimation(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointIndices::Ptr &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficient)
ros::Publisher pub_polygons_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
bool done_initialization_
ros::Publisher pub_coefficients_
ros::Publisher pub_latest_time_
virtual void unsubscribe()
T dot(T *pf1, T *pf2, int length)
RegionGrowingMultiplePlaneSegmentationConfig Config
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual ~RegionGrowingMultiplePlaneSegmentation()
boost::mutex mutex
global mutex.
double distance_threshold_
static double global_distance_threshold
boost::shared_ptr< message_filters::Synchronizer< NormalSyncPolicy > > sync_
static boost::mutex global_custom_condigion_function_mutex
ros::Publisher pub_clustering_result_
int ransac_refine_max_iterations_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45