Public Types | Protected Member Functions | Protected Attributes
jsk_pcl_ros::OrganizedEdgeDetector Class Reference

#include <organized_edge_detector.h>

Inheritance diagram for jsk_pcl_ros::OrganizedEdgeDetector:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
jsk_pcl_ros::OrganizedEdgeDetectorConfig 
Config
typedef pcl::PointXYZRGB PointT

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
virtual void estimate (const sensor_msgs::PointCloud2::ConstPtr &msg)
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)
virtual void estimateNormal (const pcl::PointCloud< PointT >::Ptr &input, pcl::PointCloud< pcl::Normal >::Ptr output, 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)
virtual void onInit ()
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 publishStraightEdges (const pcl::PointCloud< PointT >::Ptr &cloud, const std_msgs::Header &header, const std::vector< std::vector< int > > indices)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

bool border_policy_ignore_
bool depth_dependent_smoothing_
double depth_discontinuation_threshold_
int estimation_method_
double max_depth_change_factor_
double max_line_gap_
int max_search_neighbors_
double min_line_length_
boost::mutex mutex_
double normal_smoothing_size_
ros::Publisher pub_all_edges_
ros::Publisher pub_all_edges_indices_
ros::Publisher pub_curvature_edges_
ros::Publisher pub_curvature_edges_indices_
image_transport::Publisher pub_edge_image_
image_transport::Publisher pub_hough_image_
ros::Publisher pub_nan_boundary_edges_
ros::Publisher pub_nan_boundary_edges_indices_
ros::Publisher pub_normal_
ros::Publisher pub_occluded_edges_
ros::Publisher pub_occluded_edges_indices_
ros::Publisher pub_occluding_edges_
ros::Publisher pub_occluding_edges_indices_
ros::Publisher pub_rgb_edges_
ros::Publisher pub_rgb_edges_indices_
ros::Publisher pub_straight_edges_indices_
bool publish_debug_image_
bool publish_normal_
double rho_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
int straightline_threshold_
ros::Subscriber sub_
double theta_
bool use_curvature_
bool use_nan_boundary_
bool use_occluded_
bool use_occluding_
bool use_rgb_
bool use_straightline_detection_

Detailed Description

Definition at line 49 of file organized_edge_detector.h.


Member Typedef Documentation

typedef jsk_pcl_ros::OrganizedEdgeDetectorConfig jsk_pcl_ros::OrganizedEdgeDetector::Config

Definition at line 53 of file organized_edge_detector.h.

Definition at line 52 of file organized_edge_detector.h.


Member Function Documentation

void jsk_pcl_ros::OrganizedEdgeDetector::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 156 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [protected, virtual]

Definition at line 315 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::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 
) [protected, virtual]

Definition at line 181 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::estimateNormal ( const pcl::PointCloud< PointT >::Ptr &  input,
pcl::PointCloud< pcl::Normal >::Ptr  output,
const std_msgs::Header header 
) [protected, virtual]

Definition at line 116 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::estimateStraightEdges ( const pcl::PointCloud< PointT >::Ptr &  cloud,
const std::vector< int > &  indices,
const std_msgs::Header header,
std::vector< std::vector< int > > &  output_indices 
) [protected, virtual]

Definition at line 256 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 52 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::publishIndices ( ros::Publisher pub,
ros::Publisher pub_indices,
const pcl::PointCloud< PointT >::Ptr &  cloud,
const std::vector< int > &  indices,
const std_msgs::Header header 
) [protected, virtual]

Definition at line 212 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::publishStraightEdges ( const pcl::PointCloud< PointT >::Ptr &  cloud,
const std_msgs::Header header,
const std::vector< std::vector< int > >  indices 
) [protected, virtual]

Definition at line 238 of file organized_edge_detector_nodelet.cpp.

void jsk_pcl_ros::OrganizedEdgeDetector::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::OrganizedEdgeDetector::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 109 of file organized_edge_detector.h.

Definition at line 112 of file organized_edge_detector.h.

Definition at line 117 of file organized_edge_detector.h.

Definition at line 108 of file organized_edge_detector.h.

Definition at line 110 of file organized_edge_detector.h.

Definition at line 133 of file organized_edge_detector.h.

Definition at line 118 of file organized_edge_detector.h.

Definition at line 132 of file organized_edge_detector.h.

Definition at line 104 of file organized_edge_detector.h.

Definition at line 111 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 102 of file organized_edge_detector.h.

Definition at line 102 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 100 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 97 of file organized_edge_detector.h.

Definition at line 94 of file organized_edge_detector.h.

Definition at line 101 of file organized_edge_detector.h.

Definition at line 134 of file organized_edge_detector.h.

Definition at line 113 of file organized_edge_detector.h.

Definition at line 129 of file organized_edge_detector.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::OrganizedEdgeDetector::srv_ [protected]

Definition at line 103 of file organized_edge_detector.h.

Definition at line 131 of file organized_edge_detector.h.

Definition at line 93 of file organized_edge_detector.h.

Definition at line 130 of file organized_edge_detector.h.

Definition at line 122 of file organized_edge_detector.h.

Definition at line 119 of file organized_edge_detector.h.

Definition at line 121 of file organized_edge_detector.h.

Definition at line 120 of file organized_edge_detector.h.

Definition at line 123 of file organized_edge_detector.h.

Definition at line 128 of file organized_edge_detector.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:51