pointcloud_screenpoint.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/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 // Haseru Chen, Kei Okada, Yohei Kakiuchi
36 
37 #include <boost/thread/mutex.hpp>
38 #include <dynamic_reconfigure/server.h>
39 #include <geometry_msgs/PointStamped.h>
40 #include <geometry_msgs/PolygonStamped.h>
41 #include <jsk_pcl_ros/PointcloudScreenpointConfig.h>
42 #include <jsk_recognition_msgs/TransformScreenpoint.h>
48 #include <pcl/features/normal_3d.h>
49 #include <pcl/kdtree/kdtree_flann.h>
50 #include <sensor_msgs/PointCloud2.h>
51 
52 namespace mf = message_filters;
53 
54 namespace jsk_pcl_ros
55 {
57  {
58  protected:
59  typedef PointcloudScreenpointConfig Config;
60 
61  // approximate sync policies
62  typedef mf::sync_policies::ApproximateTime<
63  sensor_msgs::PointCloud2,
64  geometry_msgs::PolygonStamped > PolygonApproxSyncPolicy;
65 
66  typedef mf::sync_policies::ApproximateTime<
67  sensor_msgs::PointCloud2,
68  geometry_msgs::PointStamped > PointApproxSyncPolicy;
69 
70  typedef mf::sync_policies::ApproximateTime<
71  sensor_msgs::PointCloud2,
72  sensor_msgs::PointCloud2 > PointCloudApproxSyncPolicy;
73 
74  // exact sync policies
75  typedef mf::sync_policies::ExactTime<
76  sensor_msgs::PointCloud2,
77  geometry_msgs::PolygonStamped > PolygonExactSyncPolicy;
78 
79  typedef mf::sync_policies::ExactTime<
80  sensor_msgs::PointCloud2,
81  geometry_msgs::PointStamped > PointExactSyncPolicy;
82 
83  typedef mf::sync_policies::ExactTime<
84  sensor_msgs::PointCloud2,
85  sensor_msgs::PointCloud2 > PointCloudExactSyncPolicy;
86 
87  virtual void onInit();
88  virtual void subscribe();
89  virtual void unsubscribe();
90  virtual void configCallback(Config &config, uint32_t level);
91 
92  // service callback functions
93  bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req,
94  jsk_recognition_msgs::TransformScreenpoint::Response &res);
95 
96  // message callback functions
97  void points_cb (const sensor_msgs::PointCloud2::ConstPtr &msg);
98  void point_cb (const geometry_msgs::PointStamped::ConstPtr &pt_ptr);
99  void point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr);
100  void rect_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
101  void poly_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
102 
103  // synchronized message callback functions
104  void sync_point_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
105  const geometry_msgs::PointStamped::ConstPtr &pt_ptr);
106  void sync_point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
107  const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr);
108  void sync_rect_cb (const sensor_msgs::PointCloud2ConstPtr &points_ptr,
109  const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
110  void sync_poly_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
111  const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
112 
113  // internal functions
114  bool checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
115  int x, int y,
116  float &resx, float &resy, float &resz);
117  bool extract_point (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
118  int reqx, int reqy,
119  float &resx, float &resy, float &resz);
120  void extract_rect (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
121  int st_x, int st_y,
122  int ed_x, int ed_y,
123  sensor_msgs::PointCloud2 &out_pts);
124 
125  // ros
141 
146 
147  // pcl
148  pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_;
149  pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_;
150 
151  // parameters
156  double timeout_;
157 
158  std_msgs::Header latest_cloud_header_;
159  pcl::PointCloud<pcl::PointXYZ> latest_cloud_;
160 
161  };
162 }
163 
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_rect_
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_poly_
PointcloudScreenpointConfig Config
void sync_rect_cb(const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > PointExactSyncPolicy
mf::Subscriber< geometry_msgs::PointStamped > point_sub_
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > PointCloudApproxSyncPolicy
boost::shared_ptr< mf::Synchronizer< PointApproxSyncPolicy > > async_point_
bool extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz)
boost::shared_ptr< mf::Synchronizer< PointExactSyncPolicy > > sync_point_
void point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_
bool checkpoint(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz)
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_poly_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > dyn_srv_
void sync_point_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
mf::Subscriber< geometry_msgs::PolygonStamped > rect_sub_
void point_cb(const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > PointCloudExactSyncPolicy
void sync_point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
virtual void configCallback(Config &config, uint32_t level)
bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res)
boost::mutex mutex
global mutex.
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > PolygonApproxSyncPolicy
mf::Subscriber< sensor_msgs::PointCloud2 > points_sub_
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > PolygonExactSyncPolicy
void extract_rect(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int st_x, int st_y, int ed_x, int ed_y, sensor_msgs::PointCloud2 &out_pts)
mf::Subscriber< geometry_msgs::PolygonStamped > poly_sub_
void points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
void poly_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_rect_
pcl::PointCloud< pcl::PointXYZ > latest_cloud_
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > PointApproxSyncPolicy
void rect_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
void sync_poly_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PointCloudApproxSyncPolicy > > async_point_array_
boost::shared_ptr< mf::Synchronizer< PointCloudExactSyncPolicy > > sync_point_array_
mf::Subscriber< sensor_msgs::PointCloud2 > point_array_sub_


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