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_PLANE_REASONER_H_
00038 #define JSK_PCL_ROS_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_pcl_ros/tf_listener_singleton.h"
00049
00050 #include <dynamic_reconfigure/server.h>
00051 #include "jsk_pcl_ros/PlaneReasonerConfig.h"
00052
00053 #include "jsk_pcl_ros/geo_util.h"
00054
00055 namespace jsk_pcl_ros
00056 {
00057 typedef boost::tuple<pcl::PointIndices::Ptr,
00058 pcl::ModelCoefficients::Ptr,
00059 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::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 void updateDiagnostic(
00099 diagnostic_updater::DiagnosticStatusWrapper &stat);
00100
00101 virtual std::vector<PlaneInfoContainer>
00102 packInfo(std::vector<pcl::PointIndices::Ptr>& inliers,
00103 std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
00104 std::vector<Plane::Ptr>& planes,
00105 std::vector<geometry_msgs::PolygonStamped>& polygons);
00106
00107 virtual std::vector<PlaneInfoContainer>
00108 filterHorizontalPlanes(
00109 std::vector<PlaneInfoContainer>& infos);
00110
00111 virtual std::vector<PlaneInfoContainer>
00112 filterVerticalPlanes(
00113 std::vector<PlaneInfoContainer>& infos);
00114
00115 virtual std::vector<PlaneInfoContainer>
00116 filterPlanesAroundAngle(
00117 double reference_angle,
00118 double thrshold,
00119 std::vector<PlaneInfoContainer>& infos);
00120
00121 virtual void publishPlaneInfo(
00122 std::vector<PlaneInfoContainer>& containers,
00123 const std_msgs::Header& header,
00124 pcl::PointCloud<PointT>::Ptr cloud,
00125 ros::Publisher& pub_inlier,
00126 ros::Publisher& pub_coefficients,
00127 ros::Publisher& pub_polygons);
00128
00130
00132 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00133 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_inliers_;
00134 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00135 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00136 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00137 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00138 tf::TransformListener* tf_listener_;
00139 ros::Publisher pub_vertical_inliers_;
00140 ros::Publisher pub_vertical_coefficients_;
00141 ros::Publisher pub_vertical_polygons_;
00142 ros::Publisher pub_horizontal_inliers_;
00143 ros::Publisher pub_horizontal_coefficients_;
00144 ros::Publisher pub_horizontal_polygons_;
00145
00146 boost::mutex mutex_;
00147
00149
00151 std::string global_frame_id_;
00152 double horizontal_angular_threshold_;
00153 double vertical_angular_threshold_;
00154 private:
00155
00156 };
00157 }
00158
00159 #endif