pointcloud_screenpoint.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 // Haseru Chen, Kei Okada, Yohei Kakiuchi
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 // F/K/A <ray ocnverter>
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 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48