37 #ifndef JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_ 38 #define JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_ 44 #include <dynamic_reconfigure/server.h> 50 #include <jsk_pcl_ros/MultiPlaneSACSegmentationConfig.h> 58 #include <sensor_msgs/PointCloud2.h> 59 #include <jsk_recognition_msgs/PolygonArray.h> 60 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 61 #include <jsk_recognition_msgs/ClusterPointIndices.h> 62 #include <sensor_msgs/Imu.h> 70 typedef jsk_pcl_ros::MultiPlaneSACSegmentationConfig
Config;
72 sensor_msgs::PointCloud2,
75 sensor_msgs::PointCloud2,
78 sensor_msgs::PointCloud2,
82 sensor_msgs::PointCloud2,
83 sensor_msgs::PointCloud2,
94 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
95 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg,
96 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal);
98 const sensor_msgs::Imu::ConstPtr& imu);
100 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal,
101 const sensor_msgs::Imu::ConstPtr& imu);
103 const sensor_msgs::PointCloud2::ConstPtr&
msg,
104 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters);
106 const pcl::PointCloud<PointT>::Ptr& input,
107 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
108 const Eigen::Vector3f& imu_vector,
109 std::vector<pcl::PointIndices::Ptr>& output_inliers,
110 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
111 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons);
113 const std_msgs::Header&
header,
114 const std::vector<pcl::PointIndices::Ptr>& inliers,
115 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
116 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);
ros::Publisher pub_coefficients_
virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
virtual void publishResult(const std_msgs::Header &header, const std::vector< pcl::PointIndices::Ptr > &inliers, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncImuPolicy
ros::Publisher pub_polygons_
virtual void segmentWithClusters(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters)
message_filters::Synchronizer< SyncNormalImuPolicy > NormalImuSynchronizer
boost::shared_ptr< message_filters::Synchronizer< SyncClusterPolicy > > sync_cluster_
virtual void configCallback(Config &config, uint32_t level)
bool use_imu_perpendicular_
boost::shared_ptr< message_filters::Synchronizer< SyncNormalImuPolicy > > sync_normal_imu_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncClusterPolicy
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_clusters_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > SyncPolicy
double outlier_threshold_
boost::mutex mutex
global mutex.
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
double normal_distance_weight_
tf::TransformListener * tf_listener_
ros::Publisher pub_inliers_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncNormalImuPolicy
virtual void applyRecursiveRANSAC(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &imu_vector, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_polygons)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncImuPolicy > > sync_imu_