Go to the documentation of this file.
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>
52 #include "jsk_topic_tools/connection_based_nodelet.h"
54 #include <jsk_pcl_ros/BorderEstimatorConfig.h>
55 #include <dynamic_reconfigure/server.h>
59 class BorderEstimator:
public jsk_topic_tools::ConnectionBasedNodelet
63 sensor_msgs::PointCloud2, sensor_msgs::CameraInfo>
SyncPolicy;
64 typedef BorderEstimatorConfig
Config;
68 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr&
msg,
69 const sensor_msgs::CameraInfo::ConstPtr& caminfo);
70 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
72 const pcl::RangeImage& image,
73 const std_msgs::Header&
header);
75 const pcl::PointIndices& inlier,
76 const std_msgs::Header&
header);
ros::Publisher pub_range_image_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void publishCloud(ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header)
ros::Publisher pub_border_
ros::Publisher pub_cloud_
virtual void computeBorder(const pcl::RangeImage &image, const std_msgs::Header &header)
double angular_resolution_
ros::Publisher pub_shadow_
virtual void unsubscribe()
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
BorderEstimatorConfig Config
boost::mutex mutex
global mutex.
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
virtual ~BorderEstimator()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44