Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::BorderEstimator Class Reference

#include <border_estimator.h>

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

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_
 

Detailed Description

Definition at line 91 of file border_estimator.h.

Member Typedef Documentation

◆ Config

typedef BorderEstimatorConfig jsk_pcl_ros::BorderEstimator::Config

Definition at line 128 of file border_estimator.h.

◆ SyncPolicy

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.

Constructor & Destructor Documentation

◆ ~BorderEstimator()

jsk_pcl_ros::BorderEstimator::~BorderEstimator ( )
virtual

Definition at line 67 of file border_estimator_nodelet.cpp.

Member Function Documentation

◆ computeBorder()

void jsk_pcl_ros::BorderEstimator::computeBorder ( const pcl::RangeImage &  image,
const std_msgs::Header header 
)
protectedvirtual

Definition at line 137 of file border_estimator_nodelet.cpp.

◆ configCallback()

void jsk_pcl_ros::BorderEstimator::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 201 of file border_estimator_nodelet.cpp.

◆ estimate() [1/2]

void jsk_pcl_ros::BorderEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg)
protectedvirtual

Definition at line 114 of file border_estimator_nodelet.cpp.

◆ estimate() [2/2]

void jsk_pcl_ros::BorderEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  msg,
const sensor_msgs::CameraInfo::ConstPtr &  caminfo 
)
protectedvirtual

Definition at line 174 of file border_estimator_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::BorderEstimator::onInit ( )
protectedvirtual

Definition at line 46 of file border_estimator_nodelet.cpp.

◆ publishCloud()

void jsk_pcl_ros::BorderEstimator::publishCloud ( ros::Publisher pub,
const pcl::PointIndices &  inlier,
const std_msgs::Header header 
)
protectedvirtual

Definition at line 103 of file border_estimator_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::BorderEstimator::subscribe ( )
protectedvirtual

Definition at line 78 of file border_estimator_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::BorderEstimator::unsubscribe ( )
protectedvirtual

Definition at line 92 of file border_estimator_nodelet.cpp.

Member Data Documentation

◆ angular_resolution_

double jsk_pcl_ros::BorderEstimator::angular_resolution_
protected

Definition at line 158 of file border_estimator.h.

◆ border_size_

int jsk_pcl_ros::BorderEstimator::border_size_
protected

Definition at line 157 of file border_estimator.h.

◆ max_angle_height_

double jsk_pcl_ros::BorderEstimator::max_angle_height_
protected

Definition at line 159 of file border_estimator.h.

◆ max_angle_width_

double jsk_pcl_ros::BorderEstimator::max_angle_width_
protected

Definition at line 160 of file border_estimator.h.

◆ min_range_

double jsk_pcl_ros::BorderEstimator::min_range_
protected

Definition at line 156 of file border_estimator.h.

◆ model_type_

std::string jsk_pcl_ros::BorderEstimator::model_type_
protected

Definition at line 153 of file border_estimator.h.

◆ mutex_

boost::mutex jsk_pcl_ros::BorderEstimator::mutex_
protected

Definition at line 154 of file border_estimator.h.

◆ noise_level_

double jsk_pcl_ros::BorderEstimator::noise_level_
protected

Definition at line 155 of file border_estimator.h.

◆ pub_border_

ros::Publisher jsk_pcl_ros::BorderEstimator::pub_border_
protected

Definition at line 149 of file border_estimator.h.

◆ pub_cloud_

ros::Publisher jsk_pcl_ros::BorderEstimator::pub_cloud_
protected

Definition at line 151 of file border_estimator.h.

◆ pub_range_image_

ros::Publisher jsk_pcl_ros::BorderEstimator::pub_range_image_
protected

Definition at line 150 of file border_estimator.h.

◆ pub_shadow_

ros::Publisher jsk_pcl_ros::BorderEstimator::pub_shadow_
protected

Definition at line 149 of file border_estimator.h.

◆ pub_veil_

ros::Publisher jsk_pcl_ros::BorderEstimator::pub_veil_
protected

Definition at line 149 of file border_estimator.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::BorderEstimator::srv_
protected

Definition at line 148 of file border_estimator.h.

◆ sub_

ros::Subscriber jsk_pcl_ros::BorderEstimator::sub_
protected

Definition at line 152 of file border_estimator.h.

◆ sub_camera_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::BorderEstimator::sub_camera_info_
protected

Definition at line 146 of file border_estimator.h.

◆ sub_point_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::BorderEstimator::sub_point_
protected

Definition at line 145 of file border_estimator.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::BorderEstimator::sync_
protected

Definition at line 147 of file border_estimator.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45