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 00036 #ifndef JSK_PCL_ROS_IMAGE_CREATOR_H_ 00037 #define JSK_PCL_ROS_IMAGE_CREATOR_H_ 00038 00039 #include <pcl_ros/pcl_nodelet.h> 00040 #include <pcl_ros/transforms.h> 00041 00042 #include <pluginlib/class_list_macros.h> 00043 #include <dynamic_reconfigure/server.h> 00044 00045 #include <pcl/range_image/range_image_planar.h> 00046 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) 00047 #include <pcl/common/transforms.h> 00048 #else 00049 #include <pcl/common/transform.h> 00050 #endif 00051 00052 #include <sensor_msgs/Image.h> 00053 #include <sensor_msgs/CameraInfo.h> 00054 #include <sensor_msgs/PointCloud2.h> 00055 #include <sensor_msgs/image_encodings.h> 00056 #include <stereo_msgs/DisparityImage.h> 00057 00058 #include <opencv2/opencv.hpp> 00059 00060 #include <std_srvs/Empty.h> 00061 #include <boost/thread/mutex.hpp> 00062 00063 #include <jsk_topic_tools/connection_based_nodelet.h> 00064 #include "jsk_pcl_ros/tf_listener_singleton.h" 00065 00066 namespace jsk_pcl_ros 00067 { 00068 class DepthImageCreator : public jsk_topic_tools::ConnectionBasedNodelet 00069 { 00070 protected: 00071 message_filters::Subscriber<sensor_msgs::CameraInfo> sub_info_; 00072 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_cloud_; 00073 ros::Subscriber sub_as_info_; 00074 ros::Subscriber sub_as_cloud_; 00075 ros::Publisher pub_depth_; 00076 ros::Publisher pub_image_; 00077 ros::Publisher pub_cloud_; 00078 ros::Publisher pub_disp_image_; 00079 ros::ServiceServer service_; 00080 00081 sensor_msgs::PointCloud2ConstPtr points_ptr_; 00082 00083 boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > sync_inputs_e_; 00084 boost::shared_ptr<message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > sync_inputs_a_; 00085 boost::mutex mutex_points; 00086 bool use_fixed_transform; 00087 bool use_service; 00088 bool use_asynchronous; 00089 bool use_approximate; 00090 int info_throttle_; 00091 int info_counter_; 00092 int max_queue_size_; 00093 int max_pub_queue_size_; 00094 int max_sub_queue_size_; 00095 tf::StampedTransform fixed_transform; 00096 tf::TransformListener* tf_listener_; 00097 double scale_depth; 00098 typedef pcl::PointXYZRGB Point; 00099 typedef pcl::PointCloud< Point > PointCloud; 00100 00101 void onInit(); 00102 00103 bool service_cb (std_srvs::Empty::Request &req, 00104 std_srvs::Empty::Response &res); 00105 00106 void callback_sync(const sensor_msgs::CameraInfoConstPtr& info, 00107 const sensor_msgs::PointCloud2ConstPtr& pcloud2); 00108 00109 void callback_cloud(const sensor_msgs::PointCloud2ConstPtr& pcloud2); 00110 00111 void callback_info(const sensor_msgs::CameraInfoConstPtr& info); 00112 00113 void publish_points(const sensor_msgs::CameraInfoConstPtr& info, 00114 const sensor_msgs::PointCloud2ConstPtr& pcloud2); 00115 00116 void subscribe(); 00117 void unsubscribe(); 00118 public: 00119 }; 00120 } 00121 00122 #endif 00123