#include <border_estimator.h>

| Public Types | |
| typedef BorderEstimatorConfig | Config | 
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > | SyncPolicy | 
| Protected Member Functions | |
| virtual void | computeBorder (const pcl::RangeImage &image, const std_msgs::Header &header) | 
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo) | 
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| virtual void | onInit () | 
| virtual void | publishCloud (ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| double | angular_resolution_ | 
| int | border_size_ | 
| double | max_angle_height_ | 
| double | max_angle_width_ | 
| double | min_range_ | 
| std::string | model_type_ | 
| boost::mutex | mutex_ | 
| double | noise_level_ | 
| ros::Publisher | pub_border_ | 
| ros::Publisher | pub_cloud_ | 
| ros::Publisher | pub_range_image_ | 
| ros::Publisher | pub_shadow_ | 
| ros::Publisher | pub_veil_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| ros::Subscriber | sub_ | 
| message_filters::Subscriber < sensor_msgs::CameraInfo > | sub_camera_info_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_point_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
Definition at line 59 of file border_estimator.h.
| typedef BorderEstimatorConfig jsk_pcl_ros::BorderEstimator::Config | 
Definition at line 64 of file border_estimator.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> jsk_pcl_ros::BorderEstimator::SyncPolicy | 
Definition at line 63 of file border_estimator.h.
| void jsk_pcl_ros::BorderEstimator::computeBorder | ( | const pcl::RangeImage & | image, | 
| const std_msgs::Header & | header | ||
| ) |  [protected, virtual] | 
Definition at line 126 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 190 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::estimate | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg, | 
| const sensor_msgs::CameraInfo::ConstPtr & | caminfo | ||
| ) |  [protected, virtual] | 
Definition at line 163 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::estimate | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [protected, virtual] | 
Definition at line 103 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 46 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::publishCloud | ( | ros::Publisher & | pub, | 
| const pcl::PointIndices & | inlier, | ||
| const std_msgs::Header & | header | ||
| ) |  [protected, virtual] | 
Definition at line 92 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 67 of file border_estimator_nodelet.cpp.
| void jsk_pcl_ros::BorderEstimator::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 81 of file border_estimator_nodelet.cpp.
| double jsk_pcl_ros::BorderEstimator::angular_resolution_  [protected] | 
Definition at line 93 of file border_estimator.h.
| int jsk_pcl_ros::BorderEstimator::border_size_  [protected] | 
Definition at line 92 of file border_estimator.h.
| double jsk_pcl_ros::BorderEstimator::max_angle_height_  [protected] | 
Definition at line 94 of file border_estimator.h.
| double jsk_pcl_ros::BorderEstimator::max_angle_width_  [protected] | 
Definition at line 95 of file border_estimator.h.
| double jsk_pcl_ros::BorderEstimator::min_range_  [protected] | 
Definition at line 91 of file border_estimator.h.
| std::string jsk_pcl_ros::BorderEstimator::model_type_  [protected] | 
Definition at line 88 of file border_estimator.h.
| boost::mutex jsk_pcl_ros::BorderEstimator::mutex_  [protected] | 
Definition at line 89 of file border_estimator.h.
| double jsk_pcl_ros::BorderEstimator::noise_level_  [protected] | 
Definition at line 90 of file border_estimator.h.
Definition at line 84 of file border_estimator.h.
Definition at line 86 of file border_estimator.h.
Definition at line 85 of file border_estimator.h.
Definition at line 84 of file border_estimator.h.
Definition at line 84 of file border_estimator.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::BorderEstimator::srv_  [protected] | 
Definition at line 83 of file border_estimator.h.
| ros::Subscriber jsk_pcl_ros::BorderEstimator::sub_  [protected] | 
Definition at line 87 of file border_estimator.h.
| message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::BorderEstimator::sub_camera_info_  [protected] | 
Definition at line 81 of file border_estimator.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::BorderEstimator::sub_point_  [protected] | 
Definition at line 80 of file border_estimator.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::BorderEstimator::sync_  [protected] | 
Definition at line 82 of file border_estimator.h.