40 #ifndef JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__ 41 #define JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__ 43 #include <boost/shared_ptr.hpp> 44 #include <dynamic_reconfigure/server.h> 49 #include <sensor_msgs/PointCloud2.h> 50 #include <jsk_recognition_msgs/ClusterPointIndices.h> 51 #include <jsk_recognition_msgs/ClassificationResult.h> 52 #include <jsk_recognition_msgs/PolygonArray.h> 55 #include <jsk_pcl_ros/PrimitiveShapeClassifierConfig.h> 56 #include <pcl/point_types.h> 57 #include <pcl/point_cloud.h> 58 #include <pcl/ModelCoefficients.h> 66 sensor_msgs::PointCloud2,
67 jsk_recognition_msgs::ClusterPointIndices,
69 typedef PrimitiveShapeClassifierConfig
Config;
80 process(
const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
81 const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
82 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
83 const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
87 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
88 const pcl::ModelCoefficients::Ptr& plane,
89 pcl::PointIndices::Ptr& boundary_indices,
90 pcl::PointCloud<PointT>::Ptr& projected_cloud,
91 float& circle_likelihood,
92 float& box_likelihood);
96 const std::vector<jsk_recognition_utils::Polygon::Ptr>&
polygons,
97 pcl::ModelCoefficients::Ptr& coeff);
100 checkFrameId(
const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
101 const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
102 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
103 const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
127 #endif // JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__ PrimitiveShapeClassifierConfig Config
ros::Publisher pub_class_
ros::Publisher pub_boundary_indices_
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_projected_cloud_
virtual bool estimate(const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const pcl::ModelCoefficients::Ptr &plane, pcl::PointIndices::Ptr &boundary_indices, pcl::PointCloud< PointT >::Ptr &projected_cloud, float &circle_likelihood, float &box_likelihood)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual void unsubscribe()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray > SyncPolicy
double sac_distance_threshold_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
PrimitiveShapeClassifier()
virtual void process(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::mutex mutex
global mutex.
virtual bool checkFrameId(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
double sac_radius_limit_min_
virtual bool getSupportPlane(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< jsk_recognition_utils::Polygon::Ptr > &polygons, pcl::ModelCoefficients::Ptr &coeff)
double sac_radius_limit_max_