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_ORGANIZED_EDGE_DETECTOR_H_
00038 #define JSK_PCL_ROS_ORGANIZED_EDGE_DETECTOR_H_
00039
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <sensor_msgs/PointCloud2.h>
00042 #include <jsk_pcl_ros/OrganizedEdgeDetectorConfig.h>
00043 #include <dynamic_reconfigure/server.h>
00044 #include <image_transport/image_transport.h>
00045 #include "jsk_topic_tools/connection_based_nodelet.h"
00046
00047 namespace jsk_pcl_ros
00048 {
00049 class OrganizedEdgeDetector: public jsk_topic_tools::ConnectionBasedNodelet
00050 {
00051 public:
00052 typedef pcl::PointXYZRGB PointT;
00053 typedef jsk_pcl_ros::OrganizedEdgeDetectorConfig Config;
00054
00055 protected:
00057
00059 virtual void onInit();
00060 virtual void configCallback (Config &config, uint32_t level);
00061 virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& msg);
00062 virtual void estimateNormal(
00063 const pcl::PointCloud<PointT>::Ptr& input,
00064 pcl::PointCloud<pcl::Normal>::Ptr output,
00065 const std_msgs::Header& header);
00066 virtual void estimateEdge(
00067 const pcl::PointCloud<PointT>::Ptr& input,
00068 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
00069 pcl::PointCloud<pcl::Label>::Ptr& output,
00070 std::vector<pcl::PointIndices>& label_indices);
00071 virtual void publishIndices(
00072 ros::Publisher& pub,
00073 ros::Publisher& pub_indices,
00074 const pcl::PointCloud<PointT>::Ptr& cloud,
00075 const std::vector<int>& indices,
00076 const std_msgs::Header& header);
00077 virtual void estimateStraightEdges(
00078 const pcl::PointCloud<PointT>::Ptr& cloud,
00079 const std::vector<int>& indices,
00080 const std_msgs::Header& header,
00081 std::vector<std::vector<int> >& output_indices);
00082 virtual void publishStraightEdges(
00083 const pcl::PointCloud<PointT>::Ptr& cloud,
00084 const std_msgs::Header& header,
00085 const std::vector<std::vector<int> > indices);
00086
00087 virtual void subscribe();
00088 virtual void unsubscribe();
00089
00091
00093 ros::Subscriber sub_;
00094 ros::Publisher pub_nan_boundary_edges_indices_,
00095 pub_occluding_edges_indices_, pub_occluded_edges_indices_,
00096 pub_curvature_edges_indices_, pub_rgb_edges_indices_, pub_all_edges_indices_;
00097 ros::Publisher pub_nan_boundary_edges_,
00098 pub_occluding_edges_, pub_occluded_edges_,
00099 pub_curvature_edges_, pub_rgb_edges_, pub_all_edges_;
00100 ros::Publisher pub_normal_;
00101 ros::Publisher pub_straight_edges_indices_;
00102 image_transport::Publisher pub_edge_image_, pub_hough_image_;
00103 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00104 boost::mutex mutex_;
00106
00108 int estimation_method_;
00109 bool border_policy_ignore_;
00110 double max_depth_change_factor_;
00111 double normal_smoothing_size_;
00112 bool depth_dependent_smoothing_;
00113 bool publish_normal_;
00115
00117 double depth_discontinuation_threshold_;
00118 int max_search_neighbors_;
00119 bool use_nan_boundary_;
00120 bool use_occluding_;
00121 bool use_occluded_;
00122 bool use_curvature_;
00123 bool use_rgb_;
00124
00126
00128 bool use_straightline_detection_;
00129 double rho_;
00130 double theta_;
00131 int straightline_threshold_;
00132 double min_line_length_;
00133 double max_line_gap_;
00134 bool publish_debug_image_;
00135
00136 private:
00137
00138 };
00139 }
00140
00141 #endif