#include <border_estimator.h>
Public Types | |
typedef BorderEstimatorConfig | Config |
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > | SyncPolicy |
Public Member Functions | |
virtual | ~BorderEstimator () |
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) |
virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo) |
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 91 of file border_estimator.h.
typedef BorderEstimatorConfig jsk_pcl_ros::BorderEstimator::Config |
Definition at line 128 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 127 of file border_estimator.h.
|
virtual |
Definition at line 67 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 137 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 201 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 114 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 174 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 46 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 103 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 78 of file border_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 92 of file border_estimator_nodelet.cpp.
|
protected |
Definition at line 158 of file border_estimator.h.
|
protected |
Definition at line 157 of file border_estimator.h.
|
protected |
Definition at line 159 of file border_estimator.h.
|
protected |
Definition at line 160 of file border_estimator.h.
|
protected |
Definition at line 156 of file border_estimator.h.
|
protected |
Definition at line 153 of file border_estimator.h.
|
protected |
Definition at line 154 of file border_estimator.h.
|
protected |
Definition at line 155 of file border_estimator.h.
|
protected |
Definition at line 149 of file border_estimator.h.
|
protected |
Definition at line 151 of file border_estimator.h.
|
protected |
Definition at line 150 of file border_estimator.h.
|
protected |
Definition at line 149 of file border_estimator.h.
|
protected |
Definition at line 149 of file border_estimator.h.
|
protected |
Definition at line 148 of file border_estimator.h.
|
protected |
Definition at line 152 of file border_estimator.h.
|
protected |
Definition at line 146 of file border_estimator.h.
|
protected |
Definition at line 145 of file border_estimator.h.
|
protected |
Definition at line 147 of file border_estimator.h.