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/o2r 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 
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 {
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  protected:
69 
70  virtual void onInit();
71  virtual void subscribe();
72  virtual void unsubscribe();
73  virtual void configCallback(Config &config, uint32_t level);
74 
78  virtual void detect(
79  const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
80  const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
81  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
82 
86  virtual void cloudCallback(
87  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
88 
92  virtual void hintCallback(
93  const geometry_msgs::PolygonStamped::ConstPtr& hint_msg);
94 
98  virtual void infoCallback(
99  const sensor_msgs::CameraInfo::ConstPtr& info_msg);
100 
102  const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
104  Eigen::Vector3f& a,
105  Eigen::Vector3f& b);
106 
107  virtual void filterPointCloud(
108  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
110  pcl::PointIndices& output_indices);
111  virtual void normalEstimate(
112  const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
113  const pcl::PointIndices::Ptr indices,
114  pcl::PointCloud<pcl::Normal>& normals,
115  pcl::PointCloud<pcl::PointXYZ>& normals_cloud);
116 
117  virtual void fittingCylinder(
118  const pcl::PointCloud<pcl::PointXYZ>::Ptr& filtered_cloud,
119  const pcl::PointCloud<pcl::Normal>::Ptr& cloud_nromals,
120  const Eigen::Vector3f& a,
121  const Eigen::Vector3f& b);
122 
131  virtual bool rejected2DHint(
132  const jsk_recognition_utils::Cylinder::Ptr& cylinder,
133  const Eigen::Vector3f& a,
134  const Eigen::Vector3f& b);
135 
137 
143 
150  // params from continuous_mode
155 
156  double max_radius_;
157  double min_radius_;
161  double eps_angle_;
166 
171 
177 
178  sensor_msgs::CameraInfo::ConstPtr latest_camera_info_;
179  geometry_msgs::PolygonStamped::ConstPtr latest_hint_;
180 
181  private:
182 
183  };
184 }
185 
186 #endif
virtual void hintCallback(const geometry_msgs::PolygonStamped::ConstPtr &hint_msg)
Non synchronized message callback for ~input/hint/line.
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)
bool use_normal_
True if use ~input has normal fields.
config
geometry_msgs::PolygonStamped::ConstPtr latest_hint_
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Non synchronized message callback for ~input pointcloud.
info_msg
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Non synchronized message callback for ~input/camera_info.
message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > ASyncPolicy
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > sync_
DiagnosticNodelet(const std::string &name)
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)
HintedStickFinderConfig Config
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
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)
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
bool not_synchronize_
Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messag...
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
virtual void filterPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const jsk_recognition_utils::ConvexPolygon::Ptr polygon, pcl::PointIndices &output_indices)
boost::mutex mutex
global mutex.
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
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.
cloud
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_...
char a[26]
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46