37 #ifndef JSK_PCL_ROS_UTILS_PLANE_REASONER_H_ 38 #define JSK_PCL_ROS_UTILS_PLANE_REASONER_H_ 41 #include "jsk_recognition_msgs/ClusterPointIndices.h" 42 #include "jsk_recognition_msgs/PolygonArray.h" 43 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 50 #include <dynamic_reconfigure/server.h> 51 #include "jsk_pcl_ros_utils/PlaneReasonerConfig.h" 57 typedef boost::tuple<pcl::PointIndices::Ptr,
58 pcl::ModelCoefficients::Ptr,
60 geometry_msgs::PolygonStamped>
70 sensor_msgs::PointCloud2,
71 jsk_recognition_msgs::ClusterPointIndices,
72 jsk_recognition_msgs::ModelCoefficientsArray,
74 typedef jsk_pcl_ros_utils::PlaneReasonerConfig
Config;
91 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
92 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
93 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
94 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg);
98 virtual std::vector<PlaneInfoContainer>
99 packInfo(std::vector<pcl::PointIndices::Ptr>& inliers,
101 std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
102 std::vector<geometry_msgs::PolygonStamped>&
polygons);
104 virtual std::vector<PlaneInfoContainer>
106 std::vector<PlaneInfoContainer>& infos);
108 virtual std::vector<PlaneInfoContainer>
110 std::vector<PlaneInfoContainer>& infos);
112 virtual std::vector<PlaneInfoContainer>
114 double reference_angle,
116 std::vector<PlaneInfoContainer>& infos);
119 std::vector<PlaneInfoContainer>& containers,
120 const std_msgs::Header&
header,
121 pcl::PointCloud<PointT>::Ptr
cloud,
double horizontal_angular_threshold_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
virtual void unsubscribe()
virtual std::vector< PlaneInfoContainer > packInfo(std::vector< pcl::PointIndices::Ptr > &inliers, std::vector< pcl::ModelCoefficients::Ptr > &coefficients, std::vector< jsk_recognition_utils::Plane::Ptr > &planes, std::vector< geometry_msgs::PolygonStamped > &polygons)
ros::Publisher pub_vertical_coefficients_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::PolygonArray > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_horizontal_inliers_
boost::shared_ptr< Plane > Ptr
boost::tuple< pcl::PointIndices::Ptr, pcl::ModelCoefficients::Ptr, jsk_recognition_utils::Plane::Ptr, geometry_msgs::PolygonStamped > PlaneInfoContainer
tf::TransformListener * tf_listener_
jsk_pcl_ros_utils::PlaneReasonerConfig Config
virtual void reason(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &inliers_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons_msg)
double vertical_angular_threshold_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual std::vector< PlaneInfoContainer > filterHorizontalPlanes(std::vector< PlaneInfoContainer > &infos)
ros::Publisher pub_vertical_inliers_
ros::Publisher pub_horizontal_coefficients_
virtual std::vector< PlaneInfoContainer > filterPlanesAroundAngle(double reference_angle, double thrshold, std::vector< PlaneInfoContainer > &infos)
ros::Publisher pub_vertical_polygons_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void publishPlaneInfo(std::vector< PlaneInfoContainer > &containers, const std_msgs::Header &header, pcl::PointCloud< PointT >::Ptr cloud, ros::Publisher &pub_inlier, ros::Publisher &pub_coefficients, ros::Publisher &pub_polygons)
std::string global_frame_id_
ros::Publisher pub_horizontal_polygons_
virtual std::vector< PlaneInfoContainer > filterVerticalPlanes(std::vector< PlaneInfoContainer > &infos)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_