Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <pcl_ros/pcl_nodelet.h>
00038 #include <pcl_ros/point_cloud.h>
00039
00040 #include <pcl/features/normal_3d.h>
00041 #include <pcl/kdtree/kdtree_flann.h>
00042
00043 #include <pluginlib/class_list_macros.h>
00044
00045 #include <message_filters/subscriber.h>
00046 #include <message_filters/synchronizer.h>
00047 #include <message_filters/sync_policies/exact_time.h>
00048 #include <message_filters/sync_policies/approximate_time.h>
00049
00050 #include <geometry_msgs/PointStamped.h>
00051 #include <geometry_msgs/PolygonStamped.h>
00052
00053 #include "jsk_pcl_ros/TransformScreenpoint.h"
00054
00055 #include <boost/thread/mutex.hpp>
00056
00057
00058
00059 namespace jsk_pcl_ros
00060 {
00061 class PointcloudScreenpoint : public pcl_ros::PCLNodelet
00062 {
00063 typedef message_filters::sync_policies::ApproximateTime<
00064 sensor_msgs::PointCloud2,
00065 geometry_msgs::PolygonStamped > PolygonApproxSyncPolicy;
00066
00067 typedef message_filters::sync_policies::ApproximateTime<
00068 sensor_msgs::PointCloud2,
00069 geometry_msgs::PointStamped > PointApproxSyncPolicy;
00070 typedef message_filters::sync_policies::ApproximateTime<
00071 sensor_msgs::PointCloud2,
00072 sensor_msgs::PointCloud2 > PointCloudApproxSyncPolicy;
00073
00074
00075 private:
00076 message_filters::Subscriber < sensor_msgs::PointCloud2 > points_sub_;
00077 message_filters::Subscriber < geometry_msgs::PolygonStamped > rect_sub_;
00078 message_filters::Subscriber < geometry_msgs::PointStamped > point_sub_;
00079 message_filters::Subscriber < sensor_msgs::PointCloud2 > point_array_sub_;
00080 message_filters::Subscriber < geometry_msgs::PolygonStamped > poly_sub_;
00081
00082 boost::shared_ptr < message_filters::Synchronizer < PolygonApproxSyncPolicy > > sync_a_rect_;
00083 boost::shared_ptr < message_filters::Synchronizer < PointApproxSyncPolicy > > sync_a_point_;
00084 boost::shared_ptr < message_filters::Synchronizer < PointCloudApproxSyncPolicy > > sync_a_point_array_;
00085 boost::shared_ptr < message_filters::Synchronizer < PolygonApproxSyncPolicy > > sync_a_poly_;
00086
00087 ros::Publisher pub_points_;
00088 ros::Publisher pub_point_;
00089 ros::Publisher pub_polygon_;
00090 ros::ServiceServer srv_;
00091 pcl::PointCloud<pcl::PointXYZ> pts_;
00092 std_msgs::Header header_;
00093
00094 bool use_rect_, use_point_, use_sync_, use_point_array_, use_poly_;
00095
00096 pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_;
00097 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00098 pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_;
00099 #else
00100 pcl::KdTree< pcl::PointXYZ >::Ptr normals_tree_;
00101 #endif
00102
00103 void onInit();
00104 bool screenpoint_cb(jsk_pcl_ros::TransformScreenpoint::Request &req,
00105 jsk_pcl_ros::TransformScreenpoint::Response &res);
00106 void points_cb(const sensor_msgs::PointCloud2ConstPtr &msg);
00107
00108 bool checkpoint (pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y,
00109 float &resx, float &resy, float &resz);
00110 bool extract_point (pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy,
00111 float &resx, float &resy, float &resz);
00112 void extract_rect (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00113 int st_x, int st_y, int ed_x, int ed_y);
00114 void point_cb (const geometry_msgs::PointStampedConstPtr& pt_ptr);
00115 void callback_point (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00116 const geometry_msgs::PointStampedConstPtr& pt_ptr);
00117 void point_array_cb (const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr);
00118 void callback_point_array (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00119 const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr);
00120
00121 void rect_cb (const geometry_msgs::PolygonStampedConstPtr& array_ptr);
00122 void callback_rect(const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00123 const geometry_msgs::PolygonStampedConstPtr& array_ptr);
00124 void poly_cb(const geometry_msgs::PolygonStampedConstPtr& array_ptr);
00125 void callback_poly(const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00126 const geometry_msgs::PolygonStampedConstPtr& array_ptr);
00127 boost::mutex mutex_callback_;
00128
00129 int k_;
00130 int queue_size_;
00131 int crop_size_;
00132 bool publish_point_;
00133 bool publish_points_;
00134
00135 public:
00136 };
00137 }
00138