37 #ifndef JSK_PCL_ROS_ORGANIZED_EDGE_DETECTOR_H_ 38 #define JSK_PCL_ROS_ORGANIZED_EDGE_DETECTOR_H_ 41 #include <sensor_msgs/PointCloud2.h> 42 #include <jsk_pcl_ros/OrganizedEdgeDetectorConfig.h> 43 #include <dynamic_reconfigure/server.h> 53 typedef jsk_pcl_ros::OrganizedEdgeDetectorConfig
Config;
61 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
63 const pcl::PointCloud<PointT>::Ptr& input,
64 pcl::PointCloud<pcl::Normal>::Ptr output,
65 const std_msgs::Header&
header);
67 const pcl::PointCloud<PointT>::Ptr& input,
68 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
69 pcl::PointCloud<pcl::Label>::Ptr& output,
70 std::vector<pcl::PointIndices>& label_indices);
74 const pcl::PointCloud<PointT>::Ptr& cloud,
75 const std::vector<int>& indices,
76 const std_msgs::Header&
header);
78 const pcl::PointCloud<PointT>::Ptr& cloud,
79 const std::vector<int>& indices,
80 const std_msgs::Header&
header,
81 std::vector<std::vector<int> >& output_indices);
83 const pcl::PointCloud<PointT>::Ptr& cloud,
84 const std_msgs::Header&
header,
85 const std::vector<std::vector<int> > indices);
ros::Publisher pub_occluding_edges_indices_
int max_search_neighbors_
ros::Publisher pub_all_edges_
ros::Publisher pub_curvature_edges_indices_
image_transport::Publisher pub_hough_image_
bool use_straightline_detection_
virtual void estimateNormal(const pcl::PointCloud< PointT >::Ptr &input, pcl::PointCloud< pcl::Normal >::Ptr output, const std_msgs::Header &header)
ros::Publisher pub_occluded_edges_indices_
ros::Publisher pub_occluding_edges_
virtual void unsubscribe()
image_transport::Publisher pub_edge_image_
ros::Publisher pub_straight_edges_indices_
ros::Publisher pub_normal_
bool publish_debug_image_
ros::Publisher pub_rgb_edges_
ros::Publisher pub_nan_boundary_edges_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_curvature_edges_
ros::Publisher pub_all_edges_indices_
ros::Publisher pub_rgb_edges_indices_
ros::Publisher pub_occluded_edges_
virtual void estimateEdge(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, pcl::PointCloud< pcl::Label >::Ptr &output, std::vector< pcl::PointIndices > &label_indices)
bool depth_dependent_smoothing_
virtual void configCallback(Config &config, uint32_t level)
jsk_pcl_ros::OrganizedEdgeDetectorConfig Config
boost::mutex mutex
global mutex.
int straightline_threshold_
double depth_discontinuation_threshold_
bool border_policy_ignore_
ros::Publisher pub_nan_boundary_edges_indices_
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void publishStraightEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std_msgs::Header &header, const std::vector< std::vector< int > > indices)
virtual void publishIndices(ros::Publisher &pub, ros::Publisher &pub_indices, const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header)
virtual void estimateStraightEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const std_msgs::Header &header, std::vector< std::vector< int > > &output_indices)
double max_depth_change_factor_
double normal_smoothing_size_