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/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 // 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>
43 #include <jsk_topic_tools/connection_based_nodelet.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 {
56  class PointcloudScreenpoint : public jsk_topic_tools::ConnectionBasedNodelet
57  {
58  public:
59  virtual ~PointcloudScreenpoint();
60  protected:
61  typedef PointcloudScreenpointConfig Config;
62 
63  // approximate sync policies
64  typedef mf::sync_policies::ApproximateTime<
65  sensor_msgs::PointCloud2,
66  geometry_msgs::PolygonStamped > PolygonApproxSyncPolicy;
67 
68  typedef mf::sync_policies::ApproximateTime<
69  sensor_msgs::PointCloud2,
70  geometry_msgs::PointStamped > PointApproxSyncPolicy;
71 
72  typedef mf::sync_policies::ApproximateTime<
73  sensor_msgs::PointCloud2,
74  sensor_msgs::PointCloud2 > PointCloudApproxSyncPolicy;
75 
76  // exact sync policies
77  typedef mf::sync_policies::ExactTime<
78  sensor_msgs::PointCloud2,
79  geometry_msgs::PolygonStamped > PolygonExactSyncPolicy;
80 
81  typedef mf::sync_policies::ExactTime<
82  sensor_msgs::PointCloud2,
83  geometry_msgs::PointStamped > PointExactSyncPolicy;
84 
85  typedef mf::sync_policies::ExactTime<
86  sensor_msgs::PointCloud2,
87  sensor_msgs::PointCloud2 > PointCloudExactSyncPolicy;
88 
89  virtual void onInit();
90  virtual void subscribe();
91  virtual void unsubscribe();
92  virtual void configCallback(Config &config, uint32_t level);
93 
94  // service callback functions
95  bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req,
96  jsk_recognition_msgs::TransformScreenpoint::Response &res);
97 
98  // message callback functions
99  void points_cb (const sensor_msgs::PointCloud2::ConstPtr &msg);
100  void point_cb (const geometry_msgs::PointStamped::ConstPtr &pt_ptr);
101  void point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr);
102  void rect_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
103  void poly_cb (const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
104 
105  // synchronized message callback functions
106  void sync_point_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
107  const geometry_msgs::PointStamped::ConstPtr &pt_ptr);
108  void sync_point_array_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
109  const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr);
110  void sync_rect_cb (const sensor_msgs::PointCloud2ConstPtr &points_ptr,
111  const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
112  void sync_poly_cb (const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
113  const geometry_msgs::PolygonStamped::ConstPtr &array_ptr);
114 
115  // internal functions
116  bool checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
117  int x, int y,
118  float &resx, float &resy, float &resz);
119  bool extract_point (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
120  int reqx, int reqy,
121  float &resx, float &resy, float &resz);
122  void extract_rect (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
123  int st_x, int st_y,
124  int ed_x, int ed_y,
125  sensor_msgs::PointCloud2 &out_pts);
126 
127  // ros
143 
148 
149  // pcl
150  pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_;
151  pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_;
152 
153  // parameters
155  int queue_size_;
156  int search_size_;
157  int crop_size_;
158  double timeout_;
159 
160  std_msgs::Header latest_cloud_header_;
161  pcl::PointCloud<pcl::PointXYZ> latest_cloud_;
162 
163  };
164 }
165 
jsk_pcl_ros::PointcloudScreenpoint::PolygonExactSyncPolicy
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > PolygonExactSyncPolicy
Definition: pointcloud_screenpoint.h:143
jsk_pcl_ros::PointcloudScreenpoint::timeout_
double timeout_
Definition: pointcloud_screenpoint.h:222
ros::Publisher
jsk_pcl_ros::PointcloudScreenpoint::PointApproxSyncPolicy
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > PointApproxSyncPolicy
Definition: pointcloud_screenpoint.h:134
boost::shared_ptr
jsk_pcl_ros::PointcloudScreenpoint::extract_point
bool extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz)
Definition: pointcloud_screenpoint_nodelet.cpp:530
jsk_pcl_ros::PointcloudScreenpoint::checkpoint
bool checkpoint(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz)
Definition: pointcloud_screenpoint_nodelet.cpp:507
jsk_pcl_ros::PointcloudScreenpoint::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: pointcloud_screenpoint_nodelet.cpp:207
jsk_pcl_ros::PointcloudScreenpoint::points_sub_
mf::Subscriber< sensor_msgs::PointCloud2 > points_sub_
Definition: pointcloud_screenpoint.h:198
jsk_pcl_ros::PointcloudScreenpoint::PointCloudApproxSyncPolicy
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > PointCloudApproxSyncPolicy
Definition: pointcloud_screenpoint.h:138
jsk_pcl_ros::PointcloudScreenpoint::PolygonApproxSyncPolicy
mf::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PolygonStamped > PolygonApproxSyncPolicy
Definition: pointcloud_screenpoint.h:130
jsk_pcl_ros::PointcloudScreenpoint::~PointcloudScreenpoint
virtual ~PointcloudScreenpoint()
Definition: pointcloud_screenpoint_nodelet.cpp:102
attention_pose_set.x
x
Definition: attention_pose_set.py:18
jsk_pcl_ros::PointcloudScreenpoint::rect_cb
void rect_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:401
jsk_pcl_ros::PointcloudScreenpoint::async_rect_
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_rect_
Definition: pointcloud_screenpoint.h:203
jsk_pcl_ros::PointcloudScreenpoint::point_array_sub_
mf::Subscriber< sensor_msgs::PointCloud2 > point_array_sub_
Definition: pointcloud_screenpoint.h:201
jsk_pcl_ros::PointcloudScreenpoint::async_point_array_
boost::shared_ptr< mf::Synchronizer< PointCloudApproxSyncPolicy > > async_point_array_
Definition: pointcloud_screenpoint.h:205
message_filters::Subscriber< sensor_msgs::PointCloud2 >
ros::ServiceServer
jsk_pcl_ros::PointcloudScreenpoint::onInit
virtual void onInit()
Definition: pointcloud_screenpoint_nodelet.cpp:79
jsk_pcl_ros::PointcloudScreenpoint::sync_point_array_
boost::shared_ptr< mf::Synchronizer< PointCloudExactSyncPolicy > > sync_point_array_
Definition: pointcloud_screenpoint.h:210
jsk_pcl_ros::PointcloudScreenpoint::pub_point_
ros::Publisher pub_point_
Definition: pointcloud_screenpoint.h:195
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::PointcloudScreenpoint::PointCloudExactSyncPolicy
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > PointCloudExactSyncPolicy
Definition: pointcloud_screenpoint.h:151
jsk_pcl_ros::PointcloudScreenpoint::sync_poly_cb
void sync_poly_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:490
jsk_pcl_ros::PointcloudScreenpoint::point_array_cb
void point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:369
subscriber.h
jsk_pcl_ros::PointcloudScreenpoint::n3d_
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_
Definition: pointcloud_screenpoint.h:214
jsk_pcl_ros::PointcloudScreenpoint::Config
PointcloudScreenpointConfig Config
Definition: pointcloud_screenpoint.h:125
jsk_pcl_ros::PointcloudScreenpoint::extract_rect
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)
Definition: pointcloud_screenpoint_nodelet.cpp:570
jsk_pcl_ros::PointcloudScreenpoint::sync_point_
boost::shared_ptr< mf::Synchronizer< PointExactSyncPolicy > > sync_point_
Definition: pointcloud_screenpoint.h:209
jsk_pcl_ros::PointcloudScreenpoint::pub_polygon_
ros::Publisher pub_polygon_
Definition: pointcloud_screenpoint.h:196
jsk_pcl_ros::PointcloudScreenpoint::sync_rect_
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_rect_
Definition: pointcloud_screenpoint.h:208
jsk_pcl_ros::PointcloudScreenpoint::rect_sub_
mf::Subscriber< geometry_msgs::PolygonStamped > rect_sub_
Definition: pointcloud_screenpoint.h:199
jsk_pcl_ros::PointcloudScreenpoint::dyn_srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > dyn_srv_
Definition: pointcloud_screenpoint.h:193
jsk_pcl_ros::PointcloudScreenpoint::unsubscribe
virtual void unsubscribe()
Definition: pointcloud_screenpoint_nodelet.cpp:198
exact_time.h
jsk_pcl_ros::PointcloudScreenpoint::sync_poly_
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_poly_
Definition: pointcloud_screenpoint.h:211
jsk_pcl_ros::PointcloudScreenpoint::latest_cloud_header_
std_msgs::Header latest_cloud_header_
Definition: pointcloud_screenpoint.h:224
jsk_pcl_ros::PointcloudScreenpoint::synchronization_
bool synchronization_
Definition: pointcloud_screenpoint.h:218
jsk_pcl_ros::PointcloudScreenpoint::mutex_
boost::mutex mutex_
Definition: pointcloud_screenpoint.h:192
jsk_pcl_ros::PointcloudScreenpoint::sync_point_cb
void sync_point_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:472
jsk_pcl_ros::PointcloudScreenpoint::point_sub_
mf::Subscriber< geometry_msgs::PointStamped > point_sub_
Definition: pointcloud_screenpoint.h:200
jsk_pcl_ros::PointcloudScreenpoint::subscribe
virtual void subscribe()
Definition: pointcloud_screenpoint_nodelet.cpp:120
jsk_pcl_ros::PointcloudScreenpoint::async_poly_
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_poly_
Definition: pointcloud_screenpoint.h:206
jsk_pcl_ros::PointcloudScreenpoint::pub_points_
ros::Publisher pub_points_
Definition: pointcloud_screenpoint.h:194
jsk_pcl_ros::PointcloudScreenpoint::srv_
ros::ServiceServer srv_
Definition: pointcloud_screenpoint.h:197
jsk_pcl_ros::PointcloudScreenpoint::points_cb
void points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: pointcloud_screenpoint_nodelet.cpp:329
synchronizer.h
jsk_pcl_ros::PointcloudScreenpoint::approximate_sync_
bool approximate_sync_
Definition: pointcloud_screenpoint.h:218
jsk_pcl_ros::PointcloudScreenpoint::PointExactSyncPolicy
mf::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > PointExactSyncPolicy
Definition: pointcloud_screenpoint.h:147
jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb
bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res)
Definition: pointcloud_screenpoint_nodelet.cpp:237
approximate_time.h
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::PointcloudScreenpoint::point_cb
void point_cb(const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:338
jsk_pcl_ros::PointcloudScreenpoint::search_size_
int search_size_
Definition: pointcloud_screenpoint.h:220
message_filters
jsk_pcl_ros::PointcloudScreenpoint::latest_cloud_
pcl::PointCloud< pcl::PointXYZ > latest_cloud_
Definition: pointcloud_screenpoint.h:225
jsk_pcl_ros::PointcloudScreenpoint::poly_sub_
mf::Subscriber< geometry_msgs::PolygonStamped > poly_sub_
Definition: pointcloud_screenpoint.h:202
jsk_pcl_ros::PointcloudScreenpoint::crop_size_
int crop_size_
Definition: pointcloud_screenpoint.h:221
attention_pose_set.y
y
Definition: attention_pose_set.py:19
jsk_pcl_ros::PointcloudScreenpoint::sync_point_array_cb
void sync_point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:481
jsk_pcl_ros::PointcloudScreenpoint::sync_rect_cb
void sync_rect_cb(const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:499
jsk_pcl_ros::PointcloudScreenpoint::poly_cb
void poly_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
Definition: pointcloud_screenpoint_nodelet.cpp:443
jsk_pcl_ros::PointcloudScreenpoint::async_point_
boost::shared_ptr< mf::Synchronizer< PointApproxSyncPolicy > > async_point_
Definition: pointcloud_screenpoint.h:204
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::PointcloudScreenpoint::normals_tree_
pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_
Definition: pointcloud_screenpoint.h:215
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::PointcloudScreenpoint::queue_size_
int queue_size_
Definition: pointcloud_screenpoint.h:219


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