37 #ifndef JSK_PCL_ROS_BORDER_ESTIMATOR_H_ 38 #define JSK_PCL_ROS_BORDER_ESTIMATOR_H_ 41 #include <pcl/range_image/range_image.h> 42 #include <pcl/features/range_image_border_extractor.h> 44 #include <sensor_msgs/PointCloud2.h> 45 #include <sensor_msgs/CameraInfo.h> 54 #include <jsk_pcl_ros/BorderEstimatorConfig.h> 55 #include <dynamic_reconfigure/server.h> 63 sensor_msgs::PointCloud2, sensor_msgs::CameraInfo>
SyncPolicy;
64 typedef BorderEstimatorConfig
Config;
67 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr&
msg,
68 const sensor_msgs::CameraInfo::ConstPtr& caminfo);
69 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
71 const pcl::RangeImage& image,
72 const std_msgs::Header&
header);
74 const pcl::PointIndices& inlier,
75 const std_msgs::Header&
header);
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_
BorderEstimatorConfig Config
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > SyncPolicy
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo)
ros::Publisher pub_shadow_
ros::Publisher pub_border_
virtual void configCallback(Config &config, uint32_t level)
virtual void publishCloud(ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_cloud_
virtual void computeBorder(const pcl::RangeImage &image, const std_msgs::Header &header)
boost::mutex mutex
global mutex.
double angular_resolution_
ros::Publisher pub_range_image_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_