border_estimator.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_BORDER_ESTIMATOR_H_
38 #define JSK_PCL_ROS_BORDER_ESTIMATOR_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <pcl/range_image/range_image.h>
42 #include <pcl/features/range_image_border_extractor.h>
43 
44 #include <sensor_msgs/PointCloud2.h>
45 #include <sensor_msgs/CameraInfo.h>
47 
51 
52 #include "jsk_topic_tools/connection_based_nodelet.h"
53 
54 #include <jsk_pcl_ros/BorderEstimatorConfig.h>
55 #include <dynamic_reconfigure/server.h>
56 
57 namespace jsk_pcl_ros
58 {
59  class BorderEstimator: public jsk_topic_tools::ConnectionBasedNodelet
60  {
61  public:
63  sensor_msgs::PointCloud2, sensor_msgs::CameraInfo> SyncPolicy;
64  typedef BorderEstimatorConfig Config;
65  virtual ~BorderEstimator();
66  protected:
67  virtual void onInit();
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);
71  virtual void computeBorder(
72  const pcl::RangeImage& image,
73  const std_msgs::Header& header);
74  virtual void publishCloud(ros::Publisher& pub,
75  const pcl::PointIndices& inlier,
76  const std_msgs::Header& header);
77 
78  virtual void subscribe();
79  virtual void unsubscribe();
80  virtual void configCallback(Config &config, uint32_t level);
89  std::string model_type_;
91  double noise_level_;
92  double min_range_;
93  int border_size_;
94  double angular_resolution_;
95  double max_angle_height_;
96  double max_angle_width_;
97 
98  private:
99 
100  };
101 }
102 
103 #endif
jsk_pcl_ros::BorderEstimator::subscribe
virtual void subscribe()
Definition: border_estimator_nodelet.cpp:78
jsk_pcl_ros::BorderEstimator::pub_veil_
ros::Publisher pub_veil_
Definition: border_estimator.h:149
ros::Publisher
jsk_pcl_ros::BorderEstimator::pub_range_image_
ros::Publisher pub_range_image_
Definition: border_estimator.h:150
boost::shared_ptr
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::BorderEstimator::sub_
ros::Subscriber sub_
Definition: border_estimator.h:152
jsk_pcl_ros::BorderEstimator::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: border_estimator.h:148
jsk_pcl_ros::BorderEstimator::publishCloud
virtual void publishCloud(ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header)
Definition: border_estimator_nodelet.cpp:103
jsk_pcl_ros::BorderEstimator::pub_border_
ros::Publisher pub_border_
Definition: border_estimator.h:149
jsk_pcl_ros::BorderEstimator::pub_cloud_
ros::Publisher pub_cloud_
Definition: border_estimator.h:151
attention_pose_set.pub
pub
Definition: attention_pose_set.py:8
time_synchronizer.h
jsk_pcl_ros::BorderEstimator::onInit
virtual void onInit()
Definition: border_estimator_nodelet.cpp:46
jsk_pcl_ros::BorderEstimator::model_type_
std::string model_type_
Definition: border_estimator.h:153
jsk_pcl_ros::BorderEstimator::computeBorder
virtual void computeBorder(const pcl::RangeImage &image, const std_msgs::Header &header)
Definition: border_estimator_nodelet.cpp:137
jsk_pcl_ros::BorderEstimator::max_angle_width_
double max_angle_width_
Definition: border_estimator.h:160
jsk_pcl_ros::BorderEstimator::angular_resolution_
double angular_resolution_
Definition: border_estimator.h:158
jsk_pcl_ros::BorderEstimator::pub_shadow_
ros::Publisher pub_shadow_
Definition: border_estimator.h:149
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::BorderEstimator::unsubscribe
virtual void unsubscribe()
Definition: border_estimator_nodelet.cpp:92
pcl_nodelet.h
jsk_pcl_ros::BorderEstimator::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo)
Definition: border_estimator_nodelet.cpp:174
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::BorderEstimator::SyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::CameraInfo > SyncPolicy
Definition: border_estimator.h:127
jsk_pcl_ros
Definition: add_color_from_image.h:51
subscriber.h
jsk_pcl_ros::BorderEstimator::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: border_estimator.h:147
jsk_pcl_ros::BorderEstimator::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: border_estimator_nodelet.cpp:201
jsk_pcl_ros::BorderEstimator::noise_level_
double noise_level_
Definition: border_estimator.h:155
pcl_conversion_util.h
jsk_pcl_ros::BorderEstimator::Config
BorderEstimatorConfig Config
Definition: border_estimator.h:128
jsk_pcl_ros::BorderEstimator::border_size_
int border_size_
Definition: border_estimator.h:157
jsk_pcl_ros::BorderEstimator::min_range_
double min_range_
Definition: border_estimator.h:156
jsk_pcl_ros::BorderEstimator::mutex_
boost::mutex mutex_
Definition: border_estimator.h:154
jsk_pcl_ros::BorderEstimator::max_angle_height_
double max_angle_height_
Definition: border_estimator.h:159
synchronizer.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::BorderEstimator::sub_camera_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: border_estimator.h:146
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::BorderEstimator::~BorderEstimator
virtual ~BorderEstimator()
Definition: border_estimator_nodelet.cpp:67
ros::Subscriber
jsk_pcl_ros::BorderEstimator::sub_point_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_
Definition: border_estimator.h:145


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