hinted_stick_finder.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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_HINTED_STICK_FINDER_H_
38 #define JSK_PCL_ROS_HINTED_STICK_FINDER_H_
39 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
46 
47 #include <sensor_msgs/Image.h>
48 #include <geometry_msgs/PolygonStamped.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include <sensor_msgs/PointCloud2.h>
51 
54 #include <dynamic_reconfigure/server.h>
55 #include <jsk_pcl_ros/HintedStickFinderConfig.h>
56 
57 namespace jsk_pcl_ros
58 {
59  class HintedStickFinder: public jsk_topic_tools::DiagnosticNodelet
60  {
61  public:
63  geometry_msgs::PolygonStamped, // line
64  sensor_msgs::CameraInfo, // camera info
65  sensor_msgs::PointCloud2> ASyncPolicy;
66  typedef HintedStickFinderConfig Config;
67  HintedStickFinder(): DiagnosticNodelet("HintedStickFinder") {}
68  virtual ~HintedStickFinder();
69  protected:
70 
71  virtual void onInit();
72  virtual void subscribe();
73  virtual void unsubscribe();
74  virtual void configCallback(Config &config, uint32_t level);
75 
79  virtual void detect(
80  const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
81  const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
82  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
83 
87  virtual void cloudCallback(
88  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
89 
93  virtual void hintCallback(
94  const geometry_msgs::PolygonStamped::ConstPtr& hint_msg);
95 
99  virtual void infoCallback(
100  const sensor_msgs::CameraInfo::ConstPtr& info_msg);
101 
103  const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
105  Eigen::Vector3f& a,
106  Eigen::Vector3f& b);
107 
108  virtual void filterPointCloud(
109  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
111  pcl::PointIndices& output_indices);
112  virtual void normalEstimate(
113  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
114  const pcl::PointIndices::Ptr indices,
115  pcl::PointCloud<pcl::Normal>& normals,
116  pcl::PointCloud<pcl::PointXYZ>& normals_cloud);
117 
118  virtual void fittingCylinder(
119  const pcl::PointCloud<pcl::PointXYZ>::Ptr& filtered_cloud,
120  const pcl::PointCloud<pcl::Normal>::Ptr& cloud_nromals,
121  const Eigen::Vector3f& a,
122  const Eigen::Vector3f& b);
123 
132  virtual bool rejected2DHint(
133  const jsk_recognition_utils::Cylinder::Ptr& cylinder,
134  const Eigen::Vector3f& a,
135  const Eigen::Vector3f& b);
136 
138 
144 
151  // params from continuous_mode
156 
157  double max_radius_;
158  double min_radius_;
159  double filter_distance_;
160  double outlier_threshold_;
161  int max_iteration_;
162  double eps_angle_;
163  double min_probability_;
165  int min_inliers_;
166  double eps_2d_angle_;
167 
171  bool use_normal_;
172 
177  bool not_synchronize_;
178 
179  sensor_msgs::CameraInfo::ConstPtr latest_camera_info_;
180  geometry_msgs::PolygonStamped::ConstPtr latest_hint_;
181 
182  private:
183 
184  };
185 }
186 
187 #endif
jsk_pcl_ros::HintedStickFinder::eps_2d_angle_
double eps_2d_angle_
Definition: hinted_stick_finder.h:230
jsk_pcl_ros::HintedStickFinder::normalEstimate
virtual void normalEstimate(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::PointIndices::Ptr indices, pcl::PointCloud< pcl::Normal > &normals, pcl::PointCloud< pcl::PointXYZ > &normals_cloud)
Definition: hinted_stick_finder_nodelet.cpp:198
jsk_pcl_ros::HintedStickFinder::use_normal_
bool use_normal_
True if use ~input has normal fields.
Definition: hinted_stick_finder.h:235
ros::Publisher
jsk_pcl_ros::HintedStickFinder::max_iteration_
int max_iteration_
Definition: hinted_stick_finder.h:225
jsk_pcl_ros::HintedStickFinder::cloudCallback
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Non synchronized message callback for ~input pointcloud.
Definition: hinted_stick_finder_nodelet.cpp:107
sample_simulate_tabletop_cloud.polygon
polygon
Definition: sample_simulate_tabletop_cloud.py:167
boost::shared_ptr< ConvexPolygon >
pinhole_camera_model.h
jsk_pcl_ros::HintedStickFinder::pub_line_filtered_indices_
ros::Publisher pub_line_filtered_indices_
Definition: hinted_stick_finder.h:209
jsk_pcl_ros::HintedStickFinder::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: hinted_stick_finder.h:204
jsk_pcl_ros::HintedStickFinder::min_radius_
double min_radius_
Definition: hinted_stick_finder.h:222
jsk_pcl_ros::HintedStickFinder::rejected2DHint
virtual bool rejected2DHint(const jsk_recognition_utils::Cylinder::Ptr &cylinder, const Eigen::Vector3f &a, const Eigen::Vector3f &b)
Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_,...
Definition: hinted_stick_finder_nodelet.cpp:218
jsk_pcl_ros::HintedStickFinder::ASyncPolicy
message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > ASyncPolicy
Definition: hinted_stick_finder.h:129
jsk_pcl_ros::HintedStickFinder::latest_hint_
geometry_msgs::PolygonStamped::ConstPtr latest_hint_
Definition: hinted_stick_finder.h:244
geo_util.h
jsk_pcl_ros::HintedStickFinder::infoCallback
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Non synchronized message callback for ~input/camera_info.
Definition: hinted_stick_finder_nodelet.cpp:129
time_synchronizer.h
jsk_pcl_ros::HintedStickFinder::eps_angle_
double eps_angle_
Definition: hinted_stick_finder.h:226
jsk_pcl_ros::HintedStickFinder::pub_line_filtered_normal_
ros::Publisher pub_line_filtered_normal_
Definition: hinted_stick_finder.h:210
jsk_pcl_ros::HintedStickFinder::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: hinted_stick_finder.h:214
message_filters::Subscriber< geometry_msgs::PolygonStamped >
jsk_pcl_ros::HintedStickFinder::fittingCylinder
virtual void fittingCylinder(const pcl::PointCloud< pcl::PointXYZ >::Ptr &filtered_cloud, const pcl::PointCloud< pcl::Normal >::Ptr &cloud_nromals, const Eigen::Vector3f &a, const Eigen::Vector3f &b)
Definition: hinted_stick_finder_nodelet.cpp:234
jsk_pcl_ros::HintedStickFinder::outlier_threshold_
double outlier_threshold_
Definition: hinted_stick_finder.h:224
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HintedStickFinder::Config
HintedStickFinderConfig Config
Definition: hinted_stick_finder.h:130
jsk_pcl_ros::HintedStickFinder::sub_no_sync_camera_info_
ros::Subscriber sub_no_sync_camera_info_
Definition: hinted_stick_finder.h:217
jsk_pcl_ros::HintedStickFinder::filter_distance_
double filter_distance_
Definition: hinted_stick_finder.h:223
subscriber.h
jsk_pcl_ros::HintedStickFinder::unsubscribe
virtual void unsubscribe()
Definition: hinted_stick_finder_nodelet.cpp:137
jsk_pcl_ros::HintedStickFinder::sub_polygon_
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
Definition: hinted_stick_finder.h:203
jsk_pcl_ros::HintedStickFinder::filterPointCloud
virtual void filterPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const jsk_recognition_utils::ConvexPolygon::Ptr polygon, pcl::PointIndices &output_indices)
Definition: hinted_stick_finder_nodelet.cpp:315
jsk_pcl_ros::HintedStickFinder::subscribe
virtual void subscribe()
Definition: hinted_stick_finder_nodelet.cpp:85
jsk_pcl_ros::HintedStickFinder::~HintedStickFinder
virtual ~HintedStickFinder()
Definition: hinted_stick_finder_nodelet.cpp:74
jsk_pcl_ros::HintedStickFinder::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: hinted_stick_finder.h:206
jsk_pcl_ros::HintedStickFinder::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: hinted_stick_finder.h:219
jsk_pcl_ros::HintedStickFinder::sync_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > sync_
Definition: hinted_stick_finder.h:207
jsk_pcl_ros::HintedStickFinder::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: hinted_stick_finder_nodelet.cpp:364
jsk_pcl_ros::HintedStickFinder::polygonFromLine
virtual jsk_recognition_utils::ConvexPolygon::Ptr polygonFromLine(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const image_geometry::PinholeCameraModel &model, Eigen::Vector3f &a, Eigen::Vector3f &b)
Definition: hinted_stick_finder_nodelet.cpp:338
depth_error_calibration.model
model
Definition: depth_error_calibration.py:37
jsk_pcl_ros::HintedStickFinder::pub_cylinder_marker_
ros::Publisher pub_cylinder_marker_
Definition: hinted_stick_finder.h:211
jsk_pcl_ros::HintedStickFinder::not_synchronize_
bool not_synchronize_
Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messag...
Definition: hinted_stick_finder.h:241
jsk_pcl_ros::HintedStickFinder::pub_inliers_
ros::Publisher pub_inliers_
Definition: hinted_stick_finder.h:213
jsk_pcl_ros::HintedStickFinder::detect
virtual void detect(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Synchronized message callback.
Definition: hinted_stick_finder_nodelet.cpp:151
jsk_pcl_ros::HintedStickFinder::cylinder_fitting_trial_
int cylinder_fitting_trial_
Definition: hinted_stick_finder.h:228
image_geometry::PinholeCameraModel
jsk_pcl_ros::HintedStickFinder::HintedStickFinder
HintedStickFinder()
Definition: hinted_stick_finder.h:131
jsk_pcl_ros::HintedStickFinder::latest_camera_info_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
Definition: hinted_stick_finder.h:243
jsk_pcl_ros::HintedStickFinder::hintCallback
virtual void hintCallback(const geometry_msgs::PolygonStamped::ConstPtr &hint_msg)
Non synchronized message callback for ~input/hint/line.
Definition: hinted_stick_finder_nodelet.cpp:122
synchronizer.h
approximate_time.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::HintedStickFinder::sub_no_sync_polygon_
ros::Subscriber sub_no_sync_polygon_
Definition: hinted_stick_finder.h:218
jsk_pcl_ros::HintedStickFinder::sub_no_sync_cloud_
ros::Subscriber sub_no_sync_cloud_
Definition: hinted_stick_finder.h:216
jsk_pcl_ros::HintedStickFinder::pub_cylinder_pose_
ros::Publisher pub_cylinder_pose_
Definition: hinted_stick_finder.h:212
jsk_pcl_ros::HintedStickFinder::max_radius_
double max_radius_
Definition: hinted_stick_finder.h:221
jsk_pcl_ros::HintedStickFinder::min_inliers_
int min_inliers_
Definition: hinted_stick_finder.h:229
jsk_pcl_ros::HintedStickFinder::min_probability_
double min_probability_
Definition: hinted_stick_finder.h:227
ros::Subscriber
jsk_pcl_ros::HintedStickFinder::onInit
virtual void onInit()
Definition: hinted_stick_finder_nodelet.cpp:49
jsk_pcl_ros::HintedStickFinder::mutex_
boost::mutex mutex_
Definition: hinted_stick_finder.h:201
jsk_pcl_ros::HintedStickFinder::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: hinted_stick_finder.h:205


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