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>
56 class PointcloudScreenpoint :
public jsk_topic_tools::ConnectionBasedNodelet
61 typedef PointcloudScreenpointConfig
Config;
64 typedef mf::sync_policies::ApproximateTime<
65 sensor_msgs::PointCloud2,
68 typedef mf::sync_policies::ApproximateTime<
69 sensor_msgs::PointCloud2,
72 typedef mf::sync_policies::ApproximateTime<
73 sensor_msgs::PointCloud2,
77 typedef mf::sync_policies::ExactTime<
78 sensor_msgs::PointCloud2,
81 typedef mf::sync_policies::ExactTime<
82 sensor_msgs::PointCloud2,
85 typedef mf::sync_policies::ExactTime<
86 sensor_msgs::PointCloud2,
96 jsk_recognition_msgs::TransformScreenpoint::Response &
res);
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);
106 void sync_point_cb (
const sensor_msgs::PointCloud2::ConstPtr &points_ptr,
107 const geometry_msgs::PointStamped::ConstPtr &pt_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);
116 bool checkpoint (
const pcl::PointCloud< pcl::PointXYZ > &in_pts,
118 float &resx,
float &resy,
float &resz);
119 bool extract_point (
const pcl::PointCloud< pcl::PointXYZ > &in_pts,
121 float &resx,
float &resy,
float &resz);
122 void extract_rect (
const pcl::PointCloud< pcl::PointXYZ > &in_pts,
125 sensor_msgs::PointCloud2 &out_pts);
150 pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal >
n3d_;