36 #ifndef JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_ 37 #define JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_ 42 #include "jsk_recognition_msgs/ClusterPointIndices.h" 43 #include "sensor_msgs/PointCloud2.h" 45 #include <pcl/segmentation/organized_multi_plane_segmentation.h> 46 #include <dynamic_reconfigure/server.h> 47 #include "jsk_pcl_ros/OrganizedMultiPlaneSegmentationConfig.h" 48 #include "jsk_recognition_msgs/PolygonArray.h" 49 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 67 typedef std::vector<pcl::PlanarRegion<PointT>,
68 Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > >
70 typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig
Config;
75 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
77 pcl::PointCloud<pcl::Normal>::Ptr output);
80 geometry_msgs::Polygon&
polygon);
82 const std_msgs::Header&
header,
83 jsk_recognition_msgs::ClusterPointIndices& output_indices);
85 const std::vector<pcl::ModelCoefficients>& model_coefficients,
86 const std::vector<pcl::PointIndices>& boundary_indices,
89 const std_msgs::Header&
header,
90 const std::vector<pcl::PointIndices>& inlier_indices,
91 const std::vector<pcl::PointIndices>& boundary_indices,
92 const std::vector<pcl::ModelCoefficients>& model_coefficients,
94 std::vector<pcl::PointIndices>& output_indices,
95 std::vector<pcl::ModelCoefficients>& output_coefficients,
96 std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds);
98 std::vector<pcl::ModelCoefficients>& output_coefficients);
101 const pcl::PointCloud<PointT>::Ptr cloud,
102 const std::vector<pcl::PointIndices>& inliers,
103 const std_msgs::Header&
header);
106 pcl::PointCloud<PointT>::Ptr input,
107 pcl::PointCloud<pcl::Normal>::Ptr normal,
109 std::vector<pcl::ModelCoefficients>& model_coefficients,
110 std::vector<pcl::PointIndices>& inlier_indices,
111 pcl::PointCloud<pcl::Label>::Ptr& labels,
112 std::vector<pcl::PointIndices>& label_indices,
113 std::vector<pcl::PointIndices>& boundary_indices);
116 pcl::PointCloud<pcl::Normal>::Ptr normal,
117 const std_msgs::Header&
header);
120 const std_msgs::Header&
header,
121 const pcl::PointCloud<PointT>::Ptr input,
125 const std::vector<pcl::PointIndices>& inlier_indices,
126 const std::vector<pcl::PointCloud<PointT> >& boundaries,
127 const std::vector<pcl::ModelCoefficients>& model_coefficients);
129 const std_msgs::Header&
header,
130 const pcl::PointCloud<PointT>::Ptr input,
134 const std::vector<pcl::PointIndices>& inlier_indices,
135 const std::vector<pcl::PointIndices>& boundary_indices,
136 const std::vector<pcl::ModelCoefficients>& model_coefficients);
139 const pcl::PointCloud<PointT>::Ptr input,
140 const std::vector<pcl::PointIndices>& input_indices,
141 const std::vector<pcl::ModelCoefficients>& input_coefficients,
142 std::vector<pcl::PointIndices>& output_indices,
143 std::vector<pcl::ModelCoefficients>& output_coefficients,
144 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_boundaries);
ros::Publisher refined_polygon_pub_
jsk_topic_tools::VitalChecker::Ptr normal_estimation_vital_checker_
bool depth_dependent_smoothing_
jsk_topic_tools::TimeAccumulator plane_segmentation_time_acc_
double normal_smoothing_size_
double angular_threshold_
ros::Publisher polygon_pub_
double max_depth_change_factor_
ros::Publisher org_polygon_pub_
ros::Publisher coefficients_pub_
virtual void unsubscribe()
ros::Publisher refined_coefficients_pub_
ros::Timer diagnostics_timer_
jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig Config
jsk_recognition_utils::Counter connected_plane_num_counter_
virtual void pclIndicesArrayToClusterPointIndices(const std::vector< pcl::PointIndices > &inlier_indices, const std_msgs::Header &header, jsk_recognition_msgs::ClusterPointIndices &output_indices)
jsk_recognition_utils::Counter original_plane_num_counter_
jsk_topic_tools::VitalChecker::Ptr plane_segmentation_vital_checker_
virtual void publishMarkerOfConnection(jsk_recognition_utils::IntegerGraphMap connection_map, const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< pcl::PointIndices > &inliers, const std_msgs::Header &header)
std::map< int, std::vector< int > > IntegerGraphMap
ros::Publisher org_coefficients_pub_
double distance_threshold_
double max_refined_area_threshold_
virtual void publishSegmentationInformation(const std_msgs::Header &header, const pcl::PointCloud< PointT >::Ptr input, ros::Publisher &indices_pub, ros::Publisher &polygon_pub, ros::Publisher &coefficients_pub, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointCloud< PointT > > &boundaries, const std::vector< pcl::ModelCoefficients > &model_coefficients)
virtual void estimateNormal(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr output)
virtual void configCallback(Config &config, uint32_t level)
virtual void forceToDirectOrigin(const std::vector< pcl::ModelCoefficients > &coefficients, std::vector< pcl::ModelCoefficients > &output_coefficients)
bool border_policy_ignore_
ros::Publisher pub_connection_marker_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void segmentOrganizedMultiPlanes(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, PlanarRegionVector ®ions, std::vector< pcl::ModelCoefficients > &model_coefficients, std::vector< pcl::PointIndices > &inlier_indices, pcl::PointCloud< pcl::Label >::Ptr &labels, std::vector< pcl::PointIndices > &label_indices, std::vector< pcl::PointIndices > &boundary_indices)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool ransac_refine_coefficients_
virtual void connectPlanesMap(const pcl::PointCloud< PointT >::Ptr &input, const std::vector< pcl::ModelCoefficients > &model_coefficients, const std::vector< pcl::PointIndices > &boundary_indices, jsk_recognition_utils::IntegerGraphMap &connection_map)
double connect_distance_threshold_
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::mutex mutex
global mutex.
ros::Publisher normal_pub_
jsk_topic_tools::TimeAccumulator ransac_refinement_time_acc_
virtual void updateDiagnosticNormalEstimation(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void refineBasedOnRANSAC(const pcl::PointCloud< PointT >::Ptr input, const std::vector< pcl::PointIndices > &input_indices, const std::vector< pcl::ModelCoefficients > &input_coefficients, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_boundaries)
virtual void buildConnectedPlanes(const pcl::PointCloud< PointT >::Ptr &input, const std_msgs::Header &header, const std::vector< pcl::PointIndices > &inlier_indices, const std::vector< pcl::PointIndices > &boundary_indices, const std::vector< pcl::ModelCoefficients > &model_coefficients, const jsk_recognition_utils::IntegerGraphMap &connection_map, std::vector< pcl::PointIndices > &output_indices, std::vector< pcl::ModelCoefficients > &output_coefficients, std::vector< pcl::PointCloud< PointT > > &output_boundary_clouds)
double min_refined_area_threshold_
double connect_plane_angle_threshold_
std::vector< pcl::PlanarRegion< PointT >, Eigen::aligned_allocator< pcl::PlanarRegion< PointT > > > PlanarRegionVector
virtual void updateDiagnosticPlaneSegmentation(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher refined_pub_
virtual void updateDiagnostics(const ros::TimerEvent &event)
double ransac_refine_outlier_distance_threshold_
virtual void segmentFromNormals(pcl::PointCloud< PointT >::Ptr input, pcl::PointCloud< pcl::Normal >::Ptr normal, const std_msgs::Header &header)
virtual void pointCloudToPolygon(const pcl::PointCloud< PointT > &input, geometry_msgs::Polygon &polygon)
jsk_topic_tools::TimeAccumulator normal_estimation_time_acc_