Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_UTILS_PLANE_REASONER_H_
00038 #define JSK_PCL_ROS_UTILS_PLANE_REASONER_H_
00039
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00042 #include "jsk_recognition_msgs/PolygonArray.h"
00043 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00044
00045 #include <message_filters/subscriber.h>
00046 #include <message_filters/time_synchronizer.h>
00047 #include <message_filters/synchronizer.h>
00048 #include "jsk_recognition_utils/tf_listener_singleton.h"
00049
00050 #include <dynamic_reconfigure/server.h>
00051 #include "jsk_pcl_ros_utils/PlaneReasonerConfig.h"
00052
00053 #include "jsk_recognition_utils/geo_util.h"
00054
00055 namespace jsk_pcl_ros_utils
00056 {
00057 typedef boost::tuple<pcl::PointIndices::Ptr,
00058 pcl::ModelCoefficients::Ptr,
00059 jsk_recognition_utils::Plane::Ptr,
00060 geometry_msgs::PolygonStamped>
00061 PlaneInfoContainer;
00062
00063 class PlaneReasoner: public jsk_topic_tools::DiagnosticNodelet
00064 {
00065 public:
00067
00069 typedef message_filters::sync_policies::ExactTime<
00070 sensor_msgs::PointCloud2,
00071 jsk_recognition_msgs::ClusterPointIndices,
00072 jsk_recognition_msgs::ModelCoefficientsArray,
00073 jsk_recognition_msgs::PolygonArray> SyncPolicy;
00074 typedef jsk_pcl_ros_utils::PlaneReasonerConfig Config;
00075 typedef pcl::PointXYZRGB PointT;
00076
00077
00078 PlaneReasoner(): DiagnosticNodelet("PlaneReasoner") { }
00079
00080 protected:
00082
00084 virtual void onInit();
00085
00086 virtual void subscribe();
00087
00088 virtual void unsubscribe();
00089
00090 virtual void reason(
00091 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00092 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
00093 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
00094 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg);
00095
00096 virtual void configCallback (Config &config, uint32_t level);
00097
00098 virtual std::vector<PlaneInfoContainer>
00099 packInfo(std::vector<pcl::PointIndices::Ptr>& inliers,
00100 std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00101 std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
00102 std::vector<geometry_msgs::PolygonStamped>& polygons);
00103
00104 virtual std::vector<PlaneInfoContainer>
00105 filterHorizontalPlanes(
00106 std::vector<PlaneInfoContainer>& infos);
00107
00108 virtual std::vector<PlaneInfoContainer>
00109 filterVerticalPlanes(
00110 std::vector<PlaneInfoContainer>& infos);
00111
00112 virtual std::vector<PlaneInfoContainer>
00113 filterPlanesAroundAngle(
00114 double reference_angle,
00115 double thrshold,
00116 std::vector<PlaneInfoContainer>& infos);
00117
00118 virtual void publishPlaneInfo(
00119 std::vector<PlaneInfoContainer>& containers,
00120 const std_msgs::Header& header,
00121 pcl::PointCloud<PointT>::Ptr cloud,
00122 ros::Publisher& pub_inlier,
00123 ros::Publisher& pub_coefficients,
00124 ros::Publisher& pub_polygons);
00125
00127
00129 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00130 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_inliers_;
00131 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00132 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00133 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00134 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00135 tf::TransformListener* tf_listener_;
00136 ros::Publisher pub_vertical_inliers_;
00137 ros::Publisher pub_vertical_coefficients_;
00138 ros::Publisher pub_vertical_polygons_;
00139 ros::Publisher pub_horizontal_inliers_;
00140 ros::Publisher pub_horizontal_coefficients_;
00141 ros::Publisher pub_horizontal_polygons_;
00142
00143 boost::mutex mutex_;
00144
00146
00148 std::string global_frame_id_;
00149 double horizontal_angular_threshold_;
00150 double vertical_angular_threshold_;
00151 private:
00152
00153 };
00154 }
00155
00156 #endif